rby1_sdk.JointImpedanceControlCommandBuilder

class JointImpedanceControlCommandBuilder

Bases: pybind11_object

Joint 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.