rby1_sdk.BodyComponentBasedCommandBuilder#
- class BodyComponentBasedCommandBuilder#
Bases:
pybind11_objectBody component-based command builder.
Provides methods to assign commands to specific body parts: right arm, left arm, and torso. Each setter accepts either the corresponding CommandBuilder wrapper (e.g., ArmCommandBuilder, TorsoCommandBuilder) or a lower-level builder like JointPositionCommandBuilder, which will be automatically cast.
Notes
For convenience, you can directly pass a JointPositionCommandBuilder (or other valid builders) without explicitly wrapping it in an ArmCommandBuilder or TorsoCommandBuilder. The system will automatically perform the conversion.
This avoids redundant wrapping and makes usage more concise.
Examples
>>> import numpy as np, rby1_sdk as rby >>> body = rby.BodyComponentBasedCommandBuilder() >>> # Implicitly wraps into ArmCommandBuilder >>> body.set_right_arm_command( ... rby.JointPositionCommandBuilder().set_position(np.zeros(7)) ... ) >>> # Implicitly wraps into TorsoCommandBuilder >>> body.set_torso_command( ... rby.JointPositionCommandBuilder().set_position(np.zeros(6)) ... ) >>> cmd = rby.RobotCommandBuilder().set_command(body) >>> # robot.send_command(cmd, priority=1).get()
- __init__(self: rby1_sdk.BodyComponentBasedCommandBuilder) None#
Construct a BodyComponentBasedCommandBuilder instance.
Methods
__init__(self)Construct a BodyComponentBasedCommandBuilder instance.
set_left_arm_command(self, arm_command_builder)Assign a command to the left arm.
set_right_arm_command(self, arm_command_builder)Assign a command to the right arm.
set_torso_command(self, torso_command_builder)Assign a command to the torso.
- set_left_arm_command(self: rby1_sdk.BodyComponentBasedCommandBuilder, arm_command_builder: rby1_sdk.ArmCommandBuilder) rby1_sdk.BodyComponentBasedCommandBuilder#
Assign a command to the left arm.
- Parameters:
arm_command_builder (ArmCommandBuilder or compatible builder) – Command for the left arm. If a lower-level builder is provided (e.g., JointPositionCommandBuilder), it will be automatically wrapped into an ArmCommandBuilder.
- Returns:
Self reference for method chaining.
- Return type:
- set_right_arm_command(self: rby1_sdk.BodyComponentBasedCommandBuilder, arm_command_builder: rby1_sdk.ArmCommandBuilder) rby1_sdk.BodyComponentBasedCommandBuilder#
Assign a command to the right arm.
- Parameters:
arm_command_builder (ArmCommandBuilder or compatible builder) – Command for the right arm. If a lower-level builder is provided (e.g., JointPositionCommandBuilder), it will be automatically wrapped into an ArmCommandBuilder.
- Returns:
Self reference for method chaining.
- Return type:
- set_torso_command(self: rby1_sdk.BodyComponentBasedCommandBuilder, torso_command_builder: rby1_sdk.TorsoCommandBuilder) rby1_sdk.BodyComponentBasedCommandBuilder#
Assign a command to the torso.
- Parameters:
torso_command_builder (TorsoCommandBuilder or compatible builder) – Command for the torso. If a lower-level builder is provided (e.g., JointPositionCommandBuilder, OptimalControlCommandBuilder), it will be automatically wrapped into a TorsoCommandBuilder.
- Returns:
Self reference for method chaining.
- Return type: