rby1_sdk.ComponentBasedCommandBuilder#

class ComponentBasedCommandBuilder#

Bases: pybind11_object

Component-based command builder.

Provides a unified builder interface to compose commands for the robot’s main subsystems: mobility, body, and head. Each setter accepts either the corresponding CommandBuilder wrapper (e.g., MobilityCommandBuilder, BodyCommandBuilder, HeadCommandBuilder) or lower-level builders (e.g., JointVelocityCommandBuilder, JointPositionCommandBuilder), which are automatically cast into the appropriate wrapper.

Notes

  • This is typically used inside a RobotCommandBuilder to assemble subsystem-level commands into a single robot command.

  • Automatic casting removes the need to explicitly wrap builders, simplifying code.

Examples

>>> import numpy as np, rby1_sdk as rby
>>> comp = rby.ComponentBasedCommandBuilder()
>>> # Mobility: send SE2 velocity
>>> comp.set_mobility_command(
...     rby.SE2VelocityCommandBuilder().set_velocity(np.array([0.1, 0.0]), 0.2)
... )
>>> # Body: send a joint position command to the right arm
>>> comp.set_body_command(
...     rby.BodyComponentBasedCommandBuilder().set_right_arm_command(
...         rby.JointPositionCommandBuilder().set_position(np.zeros(7))
...     )
... )
>>> # Head: send a joint position command to head joints
>>> comp.set_head_command(
...     rby.JointPositionCommandBuilder().set_position(np.zeros(2))
... )
>>> cmd = rby.RobotCommandBuilder().set_command(comp)
>>> # robot.send_command(cmd, priority=1).get()
__init__(self: rby1_sdk.ComponentBasedCommandBuilder) None#

Construct a ComponentBasedCommandBuilder instance.

Methods

__init__(self)

Construct a ComponentBasedCommandBuilder instance.

set_body_command(self, body_command_builder)

Assign a body command.

set_head_command(self, head_command_builder)

Assign a head command.

set_mobility_command(self, ...)

Assign a mobility command.

set_body_command(self: rby1_sdk.ComponentBasedCommandBuilder, body_command_builder: rby1_sdk.BodyCommandBuilder) rby1_sdk.ComponentBasedCommandBuilder#

Assign a body command.

Parameters:

body_command_builder (BodyCommandBuilder or compatible builder) – Command for the body subsystem. If a lower-level builder is provided (e.g., BodyComponentBasedCommandBuilder, JointPositionCommandBuilder), it will be automatically wrapped into a BodyCommandBuilder.

Returns:

Self reference for method chaining.

Return type:

ComponentBasedCommandBuilder

set_head_command(self: rby1_sdk.ComponentBasedCommandBuilder, head_command_builder: rby1_sdk.HeadCommandBuilder) rby1_sdk.ComponentBasedCommandBuilder#

Assign a head command.

Parameters:

head_command_builder (HeadCommandBuilder or compatible builder) – Command for the head subsystem. If a lower-level builder is provided (e.g., JointPositionCommandBuilder), it will be automatically wrapped into a HeadCommandBuilder.

Returns:

Self reference for method chaining.

Return type:

ComponentBasedCommandBuilder

set_mobility_command(self: rby1_sdk.ComponentBasedCommandBuilder, mobility_command_builder: rby1_sdk.MobilityCommandBuilder) rby1_sdk.ComponentBasedCommandBuilder#

Assign a mobility command.

Parameters:

mobility_command_builder (MobilityCommandBuilder or compatible builder) – Command for the mobility subsystem. If a lower-level builder is provided (e.g., SE2VelocityCommandBuilder, JointVelocityCommandBuilder), it will be automatically wrapped into a MobilityCommandBuilder.

Returns:

Self reference for method chaining.

Return type:

ComponentBasedCommandBuilder