rby1_sdk.JointPositionCommandBuilder

class JointPositionCommandBuilder

Bases: pybind11_object

Joint position command builder.

Builds joint position commands with optional velocity/acceleration limits and a minimum execution time.

Notes

  • Vector length rule: For any vector argument (e.g., position, velocity_limit, acceleration_limit), the length N must equal the DOF of the component this builder commands. Examples: - set_right_arm_command(...) on model A → right arm N = 7 - set_body_command(...) on model A → body N = 20

Examples

Move the right arm to zero with limits and a 3-second minimum time:

>>> import numpy as np, rby1_sdk as rby
>>> jp = (
...     rby.JointPositionCommandBuilder()
...     .set_position(np.zeros(7))                      # N=7 (right arm)
...     .set_velocity_limit(np.full(7, np.pi))          # rad/s
...     .set_acceleration_limit(np.full(7, 1.0))        # rad/s^2
...     .set_minimum_time(3.0)
... )
>>> body = rby.BodyComponentBasedCommandBuilder().set_right_arm_command(
...     rby.ArmCommandBuilder().set_command(jp)
... )
>>> rc = rby.RobotCommandBuilder().set_command(
...     rby.ComponentBasedCommandBuilder().set_body_command(body)
... )
>>> # Send with priority 10
>>> # robot.send_command(rc, 10).get()
__init__(self: rby1_sdk.JointPositionCommandBuilder) None

Construct a JointPositionCommandBuilder instance.

Methods

__init__(self)

Construct a JointPositionCommandBuilder instance.

set_acceleration_limit(self, acceleration_limit)

Set joint acceleration limits.

set_command_header(self, command_header_builder)

Set the command header.

set_minimum_time(self, minimum_time)

Set the minimum execution time for the motion.

set_position(self, position)

Set the target joint positions in radians.

set_velocity_limit(self, velocity_limit)

Set joint velocity limits.