rby1_sdk.BodyCommandBuilder¶
- class BodyCommandBuilder¶
Bases:
pybind11_objectBody command builder.
Wraps commands for the robot’s body subsystem (torso + both arms). It can hold a variety of command types including joint position, optimal control, gravity compensation, Cartesian motion, and impedance control.
Notes
Typically used with
set_body_command(...)of a ComponentBasedCommandBuilder.You do not need to explicitly wrap commands in BodyCommandBuilder; passing a supported builder (e.g., JointPositionCommandBuilder) into
set_body_commandwill automatically cast it to BodyCommandBuilder.
Examples
>>> import numpy as np, rby1_sdk as rby >>> # Example 1: Joint position body command >>> jp = rby.JointPositionCommandBuilder().set_position(np.zeros(20)) # full body, N=20 >>> body = rby.BodyCommandBuilder().set_command(jp) >>> comp = rby.ComponentBasedCommandBuilder().set_body_command(body) >>> rc = rby.RobotCommandBuilder().set_command(comp) >>> # robot.send_command(rc, priority=1).get() >>> >>> # Example 2: Gravity compensation >>> gc = rby.GravityCompensationCommandBuilder().set_on(True) >>> comp = rby.ComponentBasedCommandBuilder().set_body_command(gc) # implicit wrap >>> rc = rby.RobotCommandBuilder().set_command(comp)
- __init__(*args, **kwargs)¶
Overloaded function.
__init__(self: rby1_sdk.BodyCommandBuilder) -> None
Construct a BodyCommandBuilder instance.
__init__(self: rby1_sdk.BodyCommandBuilder, joint_position_command_builder: rby1_sdk.JointPositionCommandBuilder) -> None
Construct from a joint position command.
__init__(self: rby1_sdk.BodyCommandBuilder, optimal_control_command_builder: rby1_sdk.OptimalControlCommandBuilder) -> None
Construct from an optimal control command.
__init__(self: rby1_sdk.BodyCommandBuilder, gravity_compensation_command_builder: rby1_sdk.GravityCompensationCommandBuilder) -> None
Construct from a gravity compensation command.
__init__(self: rby1_sdk.BodyCommandBuilder, cartesian_command_builder: rby1_sdk.CartesianCommandBuilder) -> None
Construct from a Cartesian command.
__init__(self: rby1_sdk.BodyCommandBuilder, body_component_based_command_builder: rby1_sdk.BodyComponentBasedCommandBuilder) -> None
Construct from a body component–based command (right/left arms, torso).
__init__(self: rby1_sdk.BodyCommandBuilder, joint_impedance_control_command_builder: rby1_sdk.JointImpedanceControlCommandBuilder) -> None
Construct from a joint impedance control command.
__init__(self: rby1_sdk.BodyCommandBuilder, cartesian_impedance_control_command_builder: rby1_sdk.CartesianImpedanceControlCommandBuilder) -> None
Construct from a Cartesian impedance control command.
Methods
__init__(*args, **kwargs)Overloaded function.
set_command(*args, **kwargs)Overloaded function.