rby1_sdk.RobotCommandBuilder#
- class RobotCommandBuilder#
Bases:
pybind11_objectRobot command builder.
Top-level builder that aggregates all types of commands into a single robot command. It can wrap a WholeBodyCommandBuilder, ComponentBasedCommandBuilder, or JogCommandBuilder, and is the final object passed to
robot.send_command(...).Notes
Typically, you do not build this manually for each subsystem. Instead, construct subsystem builders (e.g., ComponentBasedCommandBuilder with body/head/mobility commands) and wrap them in RobotCommandBuilder.
Jog commands can also be wrapped directly for lightweight incremental motions.
Implicit casting is supported, so passing compatible builders automatically creates the appropriate wrapper.
Examples
>>> import numpy as np, rby1_sdk as rby >>> # Example 1: Full stop >>> stop = rby.StopCommandBuilder() >>> whole = rby.WholeBodyCommandBuilder().set_command(stop) >>> rc = rby.RobotCommandBuilder().set_command(whole) >>> # robot.send_command(rc, priority=0).get() >>> >>> # Example 2: Move right arm with a joint position command >>> jp = rby.JointPositionCommandBuilder().set_position(np.zeros(7)) >>> body = rby.BodyComponentBasedCommandBuilder().set_right_arm_command(jp) >>> comp = rby.ComponentBasedCommandBuilder().set_body_command(body) >>> rc = rby.RobotCommandBuilder().set_command(comp) >>> # robot.send_command(rc, priority=1).get() >>> >>> # Example 3: Send a jog command >>> jog = rby.JogCommandBuilder().set_joint_name("right_arm_0") \ ... .set_command(rby.JogCommandBuilder.RelativePosition(0.1)) >>> rc = rby.RobotCommandBuilder().set_command(jog) >>> # robot.send_command(rc, priority=1).get()
- __init__(*args, **kwargs)#
Overloaded function.
__init__(self: rby1_sdk.RobotCommandBuilder) -> None
Construct a RobotCommandBuilder instance.
__init__(self: rby1_sdk.RobotCommandBuilder, whole_body_command_builder: rby1_sdk.WholeBodyCommandBuilder) -> None
Construct a RobotCommandBuilder from a WholeBodyCommandBuilder.
- Parameters:
whole_body_command_builder (WholeBodyCommandBuilder) – Whole-body command wrapper.
__init__(self: rby1_sdk.RobotCommandBuilder, component_based_command_builder: rby1_sdk.ComponentBasedCommandBuilder) -> None
Construct a RobotCommandBuilder from a ComponentBasedCommandBuilder.
- Parameters:
component_based_command_builder (ComponentBasedCommandBuilder) – Component-based command wrapper (mobility, body, head).
__init__(self: rby1_sdk.RobotCommandBuilder, jog_command_builder: rby1_sdk.JogCommandBuilder) -> None
Construct a RobotCommandBuilder from a JogCommandBuilder.
- Parameters:
jog_command_builder (JogCommandBuilder) – Jog command wrapper for single-joint incremental motion.
Methods
__init__(*args, **kwargs)Overloaded function.
set_command(*args, **kwargs)Overloaded function.
- set_command(*args, **kwargs)#
Overloaded function.
set_command(self: rby1_sdk.RobotCommandBuilder, whole_body_command_builder: rby1_sdk.WholeBodyCommandBuilder) -> rby1_sdk.RobotCommandBuilder
Assign a whole-body command.
- Parameters:
whole_body_command_builder (WholeBodyCommandBuilder) – Command to apply to the entire robot.
- Returns:
Self reference for method chaining.
- Return type:
set_command(self: rby1_sdk.RobotCommandBuilder, component_based_command_builder: rby1_sdk.ComponentBasedCommandBuilder) -> rby1_sdk.RobotCommandBuilder
Assign a component-based command.
- Parameters:
component_based_command_builder (ComponentBasedCommandBuilder) – Command to apply to subsystems (mobility, body, head).
- Returns:
Self reference for method chaining.
- Return type:
set_command(self: rby1_sdk.RobotCommandBuilder, jog_command_builder: rby1_sdk.JogCommandBuilder) -> rby1_sdk.RobotCommandBuilder
Assign a jog command.
- Parameters:
jog_command_builder (JogCommandBuilder) – Jog command for single-joint incremental motion.
- Returns:
Self reference for method chaining.
- Return type: