rby1_sdk.MobilityCommandBuilder#
- class MobilityCommandBuilder#
Bases:
pybind11_objectMobility command builder.
Wraps commands for the robot’s mobility subsystem. It supports both joint-space velocity commands (e.g., differential/mecanum wheels) and planar SE(2) velocity commands.
Notes
Typically used inside
set_mobility_command(...)of a ComponentBasedCommandBuilder.You do not need to explicitly construct MobilityCommandBuilder if passing a JointVelocityCommandBuilder or SE2VelocityCommandBuilder, as implicit casting will wrap them automatically.
Examples
>>> import numpy as np, rby1_sdk as rby >>> # Example 1: Joint velocity mobility (e.g., wheel joints) >>> vel = rby.JointVelocityCommandBuilder().set_velocity(np.full(4, 1.0)) >>> mobility = rby.MobilityCommandBuilder().set_command(vel) >>> comp = rby.ComponentBasedCommandBuilder().set_mobility_command(mobility) >>> rc = rby.RobotCommandBuilder().set_command(comp) >>> # robot.send_command(rc, priority=1).get() >>> >>> # Example 2: SE(2) velocity mobility >>> se2 = rby.SE2VelocityCommandBuilder().set_velocity(np.array([0.2, 0.0]), 0.1) # vx=0.2 m/s, yaw=0.1 rad/s >>> comp = rby.ComponentBasedCommandBuilder().set_mobility_command(se2) # implicit wrap >>> rc = rby.RobotCommandBuilder().set_command(comp)
- __init__(*args, **kwargs)#
Overloaded function.
__init__(self: rby1_sdk.MobilityCommandBuilder) -> None
Construct a MobilityCommandBuilder instance.
__init__(self: rby1_sdk.MobilityCommandBuilder, joint_velocity_command_builder: rby1_sdk.JointVelocityCommandBuilder) -> None
Construct a MobilityCommandBuilder from a joint velocity command.
- Parameters:
joint_velocity_command_builder (JointVelocityCommandBuilder) – Joint-space velocity command (e.g., wheel joint velocities).
__init__(self: rby1_sdk.MobilityCommandBuilder, se2_velocity_command_builder: rby1_sdk.SE2VelocityCommandBuilder) -> None
Construct a MobilityCommandBuilder from an SE(2) velocity command.
- Parameters:
se2_velocity_command_builder (SE2VelocityCommandBuilder) – Planar velocity command in SE(2).
Methods
__init__(*args, **kwargs)Overloaded function.
set_command(*args, **kwargs)Overloaded function.
- set_command(*args, **kwargs)#
Overloaded function.
set_command(self: rby1_sdk.MobilityCommandBuilder, joint_velocity_command_builder: rby1_sdk.JointVelocityCommandBuilder) -> rby1_sdk.MobilityCommandBuilder
Assign a joint velocity command.
- Parameters:
joint_velocity_command_builder (JointVelocityCommandBuilder) – Joint-space velocity command (rad/s for each mobility joint).
- Returns:
Self reference for method chaining.
- Return type:
set_command(self: rby1_sdk.MobilityCommandBuilder, se2_velocity_command_builder: rby1_sdk.SE2VelocityCommandBuilder) -> rby1_sdk.MobilityCommandBuilder
Assign an SE(2) velocity command.
- Parameters:
se2_velocity_command_builder (SE2VelocityCommandBuilder) – Planar velocity command with linear [m/s] and angular [rad/s] components.
- Returns:
Self reference for method chaining.
- Return type: