rby1_sdk.BodyCommandBuilder#

class BodyCommandBuilder#

Bases: pybind11_object

Body 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_command will 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.

  1. __init__(self: rby1_sdk.BodyCommandBuilder) -> None

Construct a BodyCommandBuilder instance.

  1. __init__(self: rby1_sdk.BodyCommandBuilder, joint_position_command_builder: rby1_sdk.JointPositionCommandBuilder) -> None

Construct from a joint position command.

  1. __init__(self: rby1_sdk.BodyCommandBuilder, optimal_control_command_builder: rby1_sdk.OptimalControlCommandBuilder) -> None

Construct from an optimal control command.

  1. __init__(self: rby1_sdk.BodyCommandBuilder, gravity_compensation_command_builder: rby1_sdk.GravityCompensationCommandBuilder) -> None

Construct from a gravity compensation command.

  1. __init__(self: rby1_sdk.BodyCommandBuilder, cartesian_command_builder: rby1_sdk.CartesianCommandBuilder) -> None

Construct from a Cartesian command.

  1. __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).

  1. __init__(self: rby1_sdk.BodyCommandBuilder, joint_impedance_control_command_builder: rby1_sdk.JointImpedanceControlCommandBuilder) -> None

Construct from a joint impedance control command.

  1. __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.

set_command(*args, **kwargs)#

Overloaded function.

  1. set_command(self: rby1_sdk.BodyCommandBuilder, joint_position_command_builder: rby1_sdk.JointPositionCommandBuilder) -> rby1_sdk.BodyCommandBuilder

Assign a joint position command.

Parameters:

joint_position_command_builder (JointPositionCommandBuilder) – Joint-space position command (vector length N = body DOF).

Returns:

Self reference for method chaining.

Return type:

BodyCommandBuilder

  1. set_command(self: rby1_sdk.BodyCommandBuilder, optimal_control_command_builder: rby1_sdk.OptimalControlCommandBuilder) -> rby1_sdk.BodyCommandBuilder

Assign an optimal control command.

Parameters:

optimal_control_command_builder (OptimalControlCommandBuilder) – Optimal control objective.

Returns:

Self reference for method chaining.

Return type:

BodyCommandBuilder

  1. set_command(self: rby1_sdk.BodyCommandBuilder, gravity_compensation_command_builder: rby1_sdk.GravityCompensationCommandBuilder) -> rby1_sdk.BodyCommandBuilder

Assign a gravity compensation command.

Parameters:

gravity_compensation_command_builder (GravityCompensationCommandBuilder) – Command enabling or disabling gravity compensation.

Returns:

Self reference for method chaining.

Return type:

BodyCommandBuilder

  1. set_command(self: rby1_sdk.BodyCommandBuilder, cartesian_command_builder: rby1_sdk.CartesianCommandBuilder) -> rby1_sdk.BodyCommandBuilder

Assign a Cartesian command.

Parameters:

cartesian_command_builder (CartesianCommandBuilder) – Cartesian trajectory command.

Returns:

Self reference for method chaining.

Return type:

BodyCommandBuilder

  1. set_command(self: rby1_sdk.BodyCommandBuilder, body_component_based_command_builder: rby1_sdk.BodyComponentBasedCommandBuilder) -> rby1_sdk.BodyCommandBuilder

Assign a body component–based command (arms, torso).

Parameters:

body_component_based_command_builder (BodyComponentBasedCommandBuilder) – Command composed of right arm, left arm, and torso subcommands.

Returns:

Self reference for method chaining.

Return type:

BodyCommandBuilder

  1. set_command(self: rby1_sdk.BodyCommandBuilder, joint_impedance_control_command_builder: rby1_sdk.JointImpedanceControlCommandBuilder) -> rby1_sdk.BodyCommandBuilder

Assign a joint impedance control command.

Parameters:

joint_impedance_control_command_builder (JointImpedanceControlCommandBuilder) – Joint-space impedance control command.

Returns:

Self reference for method chaining.

Return type:

BodyCommandBuilder

  1. set_command(self: rby1_sdk.BodyCommandBuilder, cartesian_impedance_control_command_builder: rby1_sdk.CartesianImpedanceControlCommandBuilder) -> rby1_sdk.BodyCommandBuilder

Assign a Cartesian impedance control command.

Parameters:

cartesian_impedance_control_command_builder (CartesianImpedanceControlCommandBuilder) – Cartesian impedance control command.

Returns:

Self reference for method chaining.

Return type:

BodyCommandBuilder