rby1_sdk.TorsoCommandBuilder#
- class TorsoCommandBuilder#
Bases:
pybind11_objectTorso command builder.
Builds commands specifically for the torso component. Accepts different command types (joint position, impedance, Cartesian, etc.) and wraps them into a torso command.
Notes
You can pass a command builder (e.g., JointPositionCommandBuilder) directly into .set_torso_command(…) without explicitly creating a TorsoCommandBuilder. Implicit casting automatically wraps it: TorsoCommandBuilder(JointPositionCommandBuilder) is created internally. Therefore, directly using TorsoCommandBuilder is often unnecessary unless you want to explicitly wrap or extend torso-specific logic.
Examples
>>> import numpy as np, rby1_sdk as rby >>> torso_cmd = ( ... rby.TorsoCommandBuilder( ... rby.JointPositionCommandBuilder().set_position(np.zeros(6)) ... ) ... )
- __init__(*args, **kwargs)#
Overloaded function.
__init__(self: rby1_sdk.TorsoCommandBuilder) -> None
Construct an empty TorsoCommandBuilder.
__init__(self: rby1_sdk.TorsoCommandBuilder, joint_position_command_builder: rby1_sdk.JointPositionCommandBuilder) -> None
Construct from a joint position command.
- Parameters:
joint_position_command_builder (JointPositionCommandBuilder) – Command specifying torso joint positions.
__init__(self: rby1_sdk.TorsoCommandBuilder, gravity_compensation_command_builder: rby1_sdk.GravityCompensationCommandBuilder) -> None
Construct from a gravity compensation command.
- Parameters:
gravity_compensation_command_builder (GravityCompensationCommandBuilder) – Command enabling/disabling gravity compensation for the torso.
__init__(self: rby1_sdk.TorsoCommandBuilder, cartesian_command_builder: rby1_sdk.CartesianCommandBuilder) -> None
Construct from a Cartesian command.
- Parameters:
cartesian_command_builder (CartesianCommandBuilder) – Command specifying Cartesian targets for the torso.
__init__(self: rby1_sdk.TorsoCommandBuilder, impedance_control_command_builder: rby1_sdk.ImpedanceControlCommandBuilder) -> None
Construct from a Cartesian impedance control command.
- Parameters:
impedance_control_command_builder (ImpedanceControlCommandBuilder) – Command specifying Cartesian impedance for the torso.
__init__(self: rby1_sdk.TorsoCommandBuilder, optimal_control_command_builder: rby1_sdk.OptimalControlCommandBuilder) -> None
Construct from an optimal control command.
- Parameters:
optimal_control_command_builder (OptimalControlCommandBuilder) – Command specifying optimal control targets/costs for the torso.
__init__(self: rby1_sdk.TorsoCommandBuilder, joint_impedance_control_command_builder: rby1_sdk.JointImpedanceControlCommandBuilder) -> None
Construct from a joint impedance control command.
- Parameters:
joint_impedance_control_command_builder (JointImpedanceControlCommandBuilder) – Command specifying joint-space impedance for the torso.
__init__(self: rby1_sdk.TorsoCommandBuilder, cartesian_impedance_control_command_builder: rby1_sdk.CartesianImpedanceControlCommandBuilder) -> None
Construct from a Cartesian impedance control command.
- Parameters:
cartesian_impedance_control_command_builder (CartesianImpedanceControlCommandBuilder) – Command specifying Cartesian impedance control for the torso.
__init__(self: rby1_sdk.TorsoCommandBuilder, joint_group_position_command_builder: rby1_sdk.JointGroupPositionCommandBuilder) -> None
Construct from a joint group position command.
- Parameters:
joint_group_position_command_builder (JointGroupPositionCommandBuilder) – Command specifying joint positions for a named torso joint group.
Methods
__init__(*args, **kwargs)Overloaded function.
set_command(*args, **kwargs)Overloaded function.
- set_command(*args, **kwargs)#
Overloaded function.
set_command(self: rby1_sdk.TorsoCommandBuilder, joint_position_command_builder: rby1_sdk.JointPositionCommandBuilder) -> rby1_sdk.TorsoCommandBuilder
Set the torso command from a joint position builder.
- Parameters:
joint_position_command_builder (JointPositionCommandBuilder) – Command specifying torso joint positions.
- Returns:
Self reference for method chaining.
- Return type:
set_command(self: rby1_sdk.TorsoCommandBuilder, gravity_compensation_command_builder: rby1_sdk.GravityCompensationCommandBuilder) -> rby1_sdk.TorsoCommandBuilder
Set the torso command from a gravity compensation builder.
- Parameters:
gravity_compensation_command_builder (GravityCompensationCommandBuilder) – Command enabling/disabling torso gravity compensation.
- Returns:
Self reference for method chaining.
- Return type:
set_command(self: rby1_sdk.TorsoCommandBuilder, cartesian_command_builder: rby1_sdk.CartesianCommandBuilder) -> rby1_sdk.TorsoCommandBuilder
Set the torso command from a Cartesian builder.
- Parameters:
cartesian_command_builder (CartesianCommandBuilder) – Command specifying Cartesian pose targets for the torso.
- Returns:
Self reference for method chaining.
- Return type:
set_command(self: rby1_sdk.TorsoCommandBuilder, impedance_control_command_builder: rby1_sdk.ImpedanceControlCommandBuilder) -> rby1_sdk.TorsoCommandBuilder
Set the torso command from a Cartesian impedance builder.
- Parameters:
impedance_control_command_builder (ImpedanceControlCommandBuilder) – Command specifying Cartesian impedance for the torso.
- Returns:
Self reference for method chaining.
- Return type:
set_command(self: rby1_sdk.TorsoCommandBuilder, optimal_control_command_builder: rby1_sdk.OptimalControlCommandBuilder) -> rby1_sdk.TorsoCommandBuilder
Set the torso command from an optimal control builder.
- Parameters:
optimal_control_command_builder (OptimalControlCommandBuilder) – Command specifying optimal control targets/costs for the torso.
- Returns:
Self reference for method chaining.
- Return type:
set_command(self: rby1_sdk.TorsoCommandBuilder, joint_impedance_control_command_builder: rby1_sdk.JointImpedanceControlCommandBuilder) -> rby1_sdk.TorsoCommandBuilder
Set the torso command from a joint impedance builder.
- Parameters:
joint_impedance_control_command_builder (JointImpedanceControlCommandBuilder) – Command specifying joint-space impedance for the torso.
- Returns:
Self reference for method chaining.
- Return type:
set_command(self: rby1_sdk.TorsoCommandBuilder, cartesian_impedance_control_command_builder: rby1_sdk.CartesianImpedanceControlCommandBuilder) -> rby1_sdk.TorsoCommandBuilder
Set the torso command from a Cartesian impedance builder.
- Parameters:
cartesian_impedance_control_command_builder (CartesianImpedanceControlCommandBuilder) – Command specifying Cartesian impedance control for the torso.
- Returns:
Self reference for method chaining.
- Return type:
set_command(self: rby1_sdk.TorsoCommandBuilder, joint_group_position_command_builder: rby1_sdk.JointGroupPositionCommandBuilder) -> rby1_sdk.TorsoCommandBuilder
Set the torso command from a joint group position builder.
- Parameters:
joint_group_position_command_builder (JointGroupPositionCommandBuilder) – Command specifying joint positions for a named torso joint group.
- Returns:
Self reference for method chaining.
- Return type: