rby1_sdk.CartesianCommandBuilder#
- class CartesianCommandBuilder#
Bases:
pybind11_objectCartesian command builder.
Builds end-effector Cartesian pose targets and optional per-joint auxiliary targets. Each Cartesian target specifies a desired homogeneous transform \({}^{ref}\!T^{link}_d \in SE(3)\) together with velocity/acceleration constraints used to time the motion.
Notes
Cartesian error is computed in the reference frame and tracked subject to velocity/acceleration limits provided per target.
Joint targets added via
add_joint_position_targetare auxiliary hints that can help disambiguate IK or bias the posture during Cartesian tracking.
Examples
>>> import numpy as np, rby1_sdk as rby >>> T = np.eye(4); T[0,3] = 0.40; T[2,3] = 0.60 # 40 cm forward, 60 cm up >>> cart = ( ... rby.CartesianCommandBuilder() ... .add_target("base", "link_torso_5", T, ... linear_velocity_limit=0.4, # [m/s] ... angular_velocity_limit=1.0, # [rad/s] ... acceleration_limit_scaling=0.6) ... .add_joint_position_target("right_arm_3", 0.3, velocity_limit=1.2) ... .set_minimum_time(2.0) ... )
- __init__(self: rby1_sdk.CartesianCommandBuilder) None#
Construct a CartesianCommandBuilder instance.
Methods
__init__(self)Construct a CartesianCommandBuilder instance.
add_joint_position_target(self, joint_name, ...)Add an auxiliary joint position target.
add_target(self, ref_link_name, link_name, ...)Add a Cartesian pose target for a link.
set_command_header(self, command_header_builder)Attach a command header.
set_minimum_time(self, minimum_time)Set the minimum execution time for the motion.
set_stop_joint_position_tracking_error(self, ...)Set the stop threshold on joint-space position tracking error.
set_stop_orientation_tracking_error(self, ...)Set the stop threshold on rotational tracking error.
set_stop_position_tracking_error(self, ...)Set the stop threshold on translational tracking error.
- add_joint_position_target(self: rby1_sdk.CartesianCommandBuilder, joint_name: str, target_position: float, velocity_limit: float | None = None, acceleration_limit: float | None = None) rby1_sdk.CartesianCommandBuilder#
Add an auxiliary joint position target.
- Parameters:
joint_name (str) – Joint name to bias.
target_position (float) – Desired joint position [rad].
velocity_limit (Optional[float], default=None) – Per-joint velocity limit [rad/s] for this target (if provided).
acceleration_limit (Optional[float], default=None) – Per-joint acceleration limit [rad/s²] for this target (if provided).
- Returns:
Self reference for method chaining.
- Return type:
Notes
Useful to resolve redundancy or bias posture while tracking Cartesian goals.
If limits are omitted, internal defaults/URDF-derived limits are used.
- add_target(self: rby1_sdk.CartesianCommandBuilder, ref_link_name: str, link_name: str, T: numpy.ndarray[numpy.float64[4, 4]], linear_velocity_limit: float, angular_velocity_limit: float, acceleration_limit_scaling: float) rby1_sdk.CartesianCommandBuilder#
Add a Cartesian pose target for a link.
- Parameters:
ref_link_name (str) – Reference frame (link) in which the target pose is expressed.
link_name (str) – Controlled link name (end-effector).
T (numpy.ndarray, shape (4,4), dtype=float64) – Desired homogeneous transform \({}^{ref}\!T^{link}_d \in SE(3)\).
linear_velocity_limit (float) – Maximum allowed translational speed [m/s].
angular_velocity_limit (float) – Maximum allowed rotational speed [rad/s].
acceleration_limit_scaling (float) – Dimensionless scaling applied to internal Cartesian acceleration limits (e.g.,
0.5halves the default internal limits).
- Returns:
Self reference for method chaining.
- Return type:
Notes
Limits here shape trajectory timing; they do not redefine hardware limits.
- set_command_header(self: rby1_sdk.CartesianCommandBuilder, command_header_builder: rby1_sdk.CommandHeaderBuilder) rby1_sdk.CartesianCommandBuilder#
Attach a command header.
- Parameters:
command_header_builder (CommandHeaderBuilder) – Command header configuration (e.g., control hold time).
- Returns:
Self reference for method chaining.
- Return type:
- set_minimum_time(self: rby1_sdk.CartesianCommandBuilder, minimum_time: float) rby1_sdk.CartesianCommandBuilder#
Set the minimum execution time for the motion.
- Parameters:
minimum_time (float) –
The shortest allowed duration (in seconds) to reach the target.
If the motion profile based on velocity/acceleration limits would finish earlier, the motion is slowed down to take exactly minimum_time.
If the natural motion takes longer than minimum_time, this parameter is ignored.
This parameter provides an additional degree of freedom to control arrival time. Instead of relying solely on velocity and acceleration limits, you can set high limits and then enforce the desired duration using minimum_time.
For streaming commands, this prevents the robot from arriving too early and waiting idly, thereby ensuring smooth and continuous motion.
- Returns:
Self reference for method chaining.
- Return type:
- set_stop_joint_position_tracking_error(self: rby1_sdk.CartesianCommandBuilder, stop_joint_position_tracking_error: float) rby1_sdk.CartesianCommandBuilder#
Set the stop threshold on joint-space position tracking error.
- Parameters:
stop_joint_position_tracking_error (float) – Threshold on per-joint position error [rad]. When joint errors fall below this value (and other conditions are met), the controller may stop.
- Returns:
Self reference for method chaining.
- Return type:
- set_stop_orientation_tracking_error(self: rby1_sdk.CartesianCommandBuilder, stop_orientation_tracking_error: float) rby1_sdk.CartesianCommandBuilder#
Set the stop threshold on rotational tracking error.
- Parameters:
stop_orientation_tracking_error (float) – Threshold on orientation error [rad]. When the orientation error falls below this value, the controller may stop.
- Returns:
Self reference for method chaining.
- Return type:
- set_stop_position_tracking_error(self: rby1_sdk.CartesianCommandBuilder, stop_position_tracking_error: float) rby1_sdk.CartesianCommandBuilder#
Set the stop threshold on translational tracking error.
- Parameters:
stop_position_tracking_error (float) – Threshold on \(\|\Delta x\|\) [m]. When the position error falls below this value (and other conditions are met), the controller may stop.
- Returns:
Self reference for method chaining.
- Return type: