rby1_sdk.ArmCommandBuilder#

class ArmCommandBuilder#

Bases: pybind11_object

Arm command builder.

Wraps a command for an arm component. This builder accepts multiple command types, such as joint position, gravity compensation, Cartesian impedance, or joint impedance commands, and provides a unified interface to send them to an arm.

Notes

  • In practice, you often do not need to explicitly construct an ArmCommandBuilder. Functions like set_right_arm_command(...) or set_left_arm_command(...) automatically cast and wrap a command (e.g., JointPositionCommandBuilder) into an ArmCommandBuilder. For example:

    >>> body.set_right_arm_command(rby.JointPositionCommandBuilder().set_position(...))
    

    is equivalent to:

    >>> body.set_right_arm_command(rby.ArmCommandBuilder(
    ...     rby.JointPositionCommandBuilder().set_position(...)))
    
  • Therefore, explicitly constructing ArmCommandBuilder is usually unnecessary unless you want to be explicit; repeatedly wrapping it is inefficient.

Examples

>>> import numpy as np, rby1_sdk as rby
>>> # Send a joint position command to the right arm
>>> jp = (
...     rby.JointPositionCommandBuilder()
...     .set_position(np.zeros(7))
...     .set_minimum_time(2.0)
... )
>>> body = rby.BodyComponentBasedCommandBuilder()
>>> # Implicit wrapping into ArmCommandBuilder
>>> body.set_right_arm_command(jp)
>>> cmd = rby.RobotCommandBuilder().set_command(body)
>>> # robot.send_command(cmd, priority=1).get()
__init__(*args, **kwargs)#

Overloaded function.

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

Construct an empty ArmCommandBuilder instance.

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

Construct an ArmCommandBuilder with a joint position command.

Parameters:

joint_position_command_builder (JointPositionCommandBuilder) – Joint position command to wrap.

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

Construct an ArmCommandBuilder with a gravity compensation command.

Parameters:

gravity_compensation_command_builder (GravityCompensationCommandBuilder) – Gravity compensation command to wrap.

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

Construct an ArmCommandBuilder with a Cartesian command.

Parameters:

cartesian_command_builder (CartesianCommandBuilder) – Cartesian command to wrap.

  1. __init__(self: rby1_sdk.ArmCommandBuilder, impedance_control_command_builder: rby1_sdk.ImpedanceControlCommandBuilder) -> None

Construct an ArmCommandBuilder with an impedance control command.

Parameters:

impedance_control_command_builder (ImpedanceControlCommandBuilder) – Cartesian impedance command to wrap.

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

Construct an ArmCommandBuilder with a joint impedance control command.

Parameters:

joint_impedance_control_command_builder (JointImpedanceControlCommandBuilder) – Joint impedance control command to wrap.

  1. __init__(self: rby1_sdk.ArmCommandBuilder, cartesian_impedance_control_command_builder: rby1_sdk.CartesianImpedanceControlCommandBuilder) -> None

Construct an ArmCommandBuilder with a Cartesian impedance control command.

Parameters:

cartesian_impedance_control_command_builder (CartesianImpedanceControlCommandBuilder) – Cartesian impedance control command to wrap.

Methods

__init__(*args, **kwargs)

Overloaded function.

set_command(*args, **kwargs)

Overloaded function.

set_command(*args, **kwargs)#

Overloaded function.

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

Set a joint position command for the arm.

Parameters:

joint_position_command_builder (JointPositionCommandBuilder) – Joint position command to wrap.

Returns:

Self reference for method chaining.

Return type:

ArmCommandBuilder

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

Set a gravity compensation command for the arm.

Parameters:

gravity_compensation_command_builder (GravityCompensationCommandBuilder) – Gravity compensation command to wrap.

Returns:

Self reference for method chaining.

Return type:

ArmCommandBuilder

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

Set a Cartesian command for the arm.

Parameters:

cartesian_command_builder (CartesianCommandBuilder) – Cartesian command to wrap.

Returns:

Self reference for method chaining.

Return type:

ArmCommandBuilder

  1. set_command(self: rby1_sdk.ArmCommandBuilder, impedance_control_command_builder: rby1_sdk.ImpedanceControlCommandBuilder) -> rby1_sdk.ArmCommandBuilder

Set an impedance control command for the arm.

Parameters:

impedance_control_command_builder (ImpedanceControlCommandBuilder) – Cartesian impedance control command to wrap.

Returns:

Self reference for method chaining.

Return type:

ArmCommandBuilder

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

Set a joint impedance control command for the arm.

Parameters:

joint_impedance_control_command_builder (JointImpedanceControlCommandBuilder) – Joint impedance control command to wrap.

Returns:

Self reference for method chaining.

Return type:

ArmCommandBuilder

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

Set a Cartesian impedance control command for the arm.

Parameters:

cartesian_impedance_control_command_builder (CartesianImpedanceControlCommandBuilder) – Cartesian impedance control command to wrap.

Returns:

Self reference for method chaining.

Return type:

ArmCommandBuilder