rby1_sdk.JointImpedanceControlCommandBuilder#
- class JointImpedanceControlCommandBuilder#
Bases:
pybind11_objectJoint impedance control command builder.
Creates joint-space impedance commands with position targets, stiffness, damping ratio, optional velocity/acceleration limits, and per-joint torque limits.
Notes
Vector length rule: All vector arguments (
position,stiffness,torque_limit,velocity_limit,acceleration_limit) must have length \(N\) equal to the DOF of the component where this builder is applied.Examples (Model
A):set_right_arm_command(...)→ right arm has \(N=7\)set_body_command(...)→ whole body has \(N=20\)
Impedance control model:
\[\tau = K (q_d - q) + D (\dot{q}_d - \dot{q}) + \tau_{ff}\]with \(K\) (stiffness), \(D\) (damping), and \(\tau_{ff}\) the feed-forward torque.
Damping from damping ratio \(\zeta\):
\[D = \zeta \left( \sqrt{M}\sqrt{K} + \sqrt{K}\sqrt{M} \right)\]where \(M\) is the (joint) inertia matrix.
Feed-forward torque \(\tau_{ff}\) is the gravity compensation torque. The final applied torque is saturated by the per-joint limits:
\[\tau_{applied} = \mathrm{clip}(\tau,\; -\tau_{max},\; \tau_{max})\]
Examples
Compliant positioning on one arm (Model A):
>>> import numpy as np, rby1_sdk as rby >>> imp = ( ... rby.JointImpedanceControlCommandBuilder() ... .set_position(np.zeros(7)) # N=7 ... .set_stiffness(np.full(7, 50.0)) # Nm/rad ... .set_damping_ratio(0.7) # ζ ... .set_torque_limit(np.full(7, 60.0)) # Nm ... .set_velocity_limit(np.full(7, np.pi)) # rad/s ... .set_acceleration_limit(np.full(7, 2.0)) # rad/s² ... .set_minimum_time(1.0) # s ... )
- __init__(self: rby1_sdk.JointImpedanceControlCommandBuilder) None#
Methods
__init__(self)set_acceleration_limit(self, acceleration_limit)Set per-joint acceleration limits.
set_command_header(self, command_header_builder)Attach a command header to this builder.
set_damping_ratio(self, damping_ratio)Set the damping ratio.
set_minimum_time(self, minimum_time)Set the minimum execution time for the motion.
set_position(self, position)Set target joint positions.
set_stiffness(self, stiffness)Set per-joint stiffness values.
set_torque_limit(self, torque_limit)Set per-joint torque limits.
set_velocity_limit(self, velocity_limit)Set per-joint velocity limits.
- set_acceleration_limit(self: rby1_sdk.JointImpedanceControlCommandBuilder, acceleration_limit: numpy.ndarray[numpy.float64[m, 1]]) rby1_sdk.JointImpedanceControlCommandBuilder#
Set per-joint acceleration limits.
- Parameters:
acceleration_limit (numpy.ndarray, shape (N,), dtype=float64) – Acceleration limits [rad/s²].
- Returns:
Self reference for method chaining.
- Return type:
Notes
Vector length \(N\) must match the component DOF.
If not set, limits from the current robot URDF are used (see
get_robot_model).Values beyond hardware capability may be accepted for profiling; actual tracking is not guaranteed.
- set_command_header(self: rby1_sdk.JointImpedanceControlCommandBuilder, command_header_builder: rby1_sdk.CommandHeaderBuilder) rby1_sdk.JointImpedanceControlCommandBuilder#
Attach a command header to this builder.
- Parameters:
command_header_builder (CommandHeaderBuilder) – Command header configuration (e.g., control hold time).
- Returns:
Self reference for method chaining.
- Return type:
Examples
>>> header = rby.CommandHeaderBuilder().set_control_hold_time(3.0) >>> imp = rby.JointImpedanceControlCommandBuilder().set_command_header(header)
- set_damping_ratio(self: rby1_sdk.JointImpedanceControlCommandBuilder, damping_ratio: float) rby1_sdk.JointImpedanceControlCommandBuilder#
Set the damping ratio.
- Parameters:
damping_ratio (float) – Damping ratio \(\zeta\) (dimensionless) in [0, 1].
- Returns:
Self reference for method chaining.
- Return type:
Notes
The damping matrix is computed from \(\zeta\), stiffness \(K\), and inertia \(M\):
\[D = \zeta \left( \sqrt{M}\sqrt{K} + \sqrt{K}\sqrt{M} \right)\]
- set_minimum_time(self: rby1_sdk.JointImpedanceControlCommandBuilder, minimum_time: float) rby1_sdk.JointImpedanceControlCommandBuilder#
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_position(self: rby1_sdk.JointImpedanceControlCommandBuilder, position: numpy.ndarray[numpy.float64[m, 1]]) rby1_sdk.JointImpedanceControlCommandBuilder#
Set target joint positions.
- Parameters:
position (numpy.ndarray, shape (N,), dtype=float64) – Desired joint positions \(q_d\) [rad]
- Returns:
Self reference for method chaining.
- Return type:
Notes
Vector length \(N\) must match the DOF of the target component (e.g., Model A arm \(N=7\), whole body \(N=20\)).
- set_stiffness(self: rby1_sdk.JointImpedanceControlCommandBuilder, stiffness: numpy.ndarray[numpy.float64[m, 1]]) rby1_sdk.JointImpedanceControlCommandBuilder#
Set per-joint stiffness values.
- Parameters:
stiffness (numpy.ndarray, shape (N,), dtype=float64) – Per-joint stiffness values, interpreted as the diagonal elements of the stiffness matrix \(K \in \mathbb{R}^{N \times N}\) (Nm/rad).
- Returns:
Self reference for method chaining.
- Return type:
Notes
Vector length \(N\) must match the component DOF.
The full stiffness matrix is assumed to be diagonal:
\[K = \mathrm{diag}(k_1, k_2, \ldots, k_N)\]Stiffness contributes torque as:
\[\tau_K = K (q_d - q)\]
- set_torque_limit(self: rby1_sdk.JointImpedanceControlCommandBuilder, torque_limit: numpy.ndarray[numpy.float64[m, 1]]) rby1_sdk.JointImpedanceControlCommandBuilder#
Set per-joint torque limits.
- Parameters:
torque_limit (numpy.ndarray, shape (N,), dtype=float64) – Maximum allowable torque \(\tau_{max}\) [Nm].
- Returns:
Self reference for method chaining.
- Return type:
Notes
The controller torque is:
\[\tau = K (q_d - q) + D (\dot{q}_d - \dot{q}) + \tau_{ff}\]where \(\tau_{ff}\) is the feed-forward gravity compensation torque.
The applied torque is saturated per joint:
\[\tau_{applied} = \mathrm{clip}(\tau,\; -\tau_{max},\; \tau_{max})\]
- set_velocity_limit(self: rby1_sdk.JointImpedanceControlCommandBuilder, velocity_limit: numpy.ndarray[numpy.float64[m, 1]]) rby1_sdk.JointImpedanceControlCommandBuilder#
Set per-joint velocity limits.
- Parameters:
velocity_limit (numpy.ndarray, shape (N,), dtype=float64) – Velocity limits [rad/s].
- Returns:
Self reference for method chaining.
- Return type:
Notes
Vector length \(N\) must match the component DOF.
If not set, limits from the current robot URDF are used (see
get_robot_model).Values beyond hardware capability may be accepted for profiling; actual tracking is not guaranteed.