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.

set_acceleration_limit(self: rby1_sdk.JointPositionCommandBuilder, acceleration_limit: numpy.ndarray[numpy.float64[m, 1]]) rby1_sdk.JointPositionCommandBuilder#

Set joint acceleration limits.

Parameters:

acceleration_limit (numpy.ndarray, shape (N,), dtype=float64) – Per-joint acceleration limits [rad/s²].

Returns:

Self reference for method chaining.

Return type:

JointPositionCommandBuilder

Notes

  • Vector length rule: N must equal the DOF of the commanded component (e.g., model A right arm N=7, full body N=20).

  • If not set, URDF limits for the current robot model are used (see get_robot_model).

  • Values beyond hardware limits may be accepted for profiling; actual tracking is not guaranteed.

Examples

>>> import numpy as np, rby1_sdk as rby
>>> jp = rby.JointPositionCommandBuilder().set_acceleration_limit(np.full(7, 1.0))
set_command_header(self: rby1_sdk.JointPositionCommandBuilder, command_header_builder: rby1_sdk.CommandHeaderBuilder) rby1_sdk.JointPositionCommandBuilder#

Set the command header.

Parameters:

command_header_builder (CommandHeaderBuilder) – Command header builder.

Returns:

Self reference for method chaining.

Return type:

JointPositionCommandBuilder

set_minimum_time(self: rby1_sdk.JointPositionCommandBuilder, minimum_time: float) rby1_sdk.JointPositionCommandBuilder#

Set the minimum execution time for the motion.

Parameters:

minimum_time (float) –

The shortest allowed duration (in seconds) to reach the target.

  • If the motion profile based on velocity/acceleration limits would finish earlier, the motion is slowed down to take exactly minimum_time.

  • If the natural motion takes longer than minimum_time, this parameter is ignored.

This parameter provides an additional degree of freedom to control arrival time. Instead of relying solely on velocity and acceleration limits, you can set high limits and then enforce the desired duration using minimum_time.

For streaming commands, this prevents the robot from arriving too early and waiting idly, thereby ensuring smooth and continuous motion.

Returns:

Self reference for method chaining.

Return type:

JointPositionCommandBuilder

set_position(self: rby1_sdk.JointPositionCommandBuilder, position: numpy.ndarray[numpy.float64[m, 1]]) rby1_sdk.JointPositionCommandBuilder#

Set the target joint positions in radians.

Parameters:

position (numpy.ndarray, shape (N,), dtype=float64) – Target joint positions [rad]

Returns:

Self reference for method chaining.

Return type:

JointPositionCommandBuilder

Notes

Vector length rule: N must equal the DOF of the commanded component. Examples on model A: right arm → N=7; full body → N=20.

Examples

>>> import numpy as np, rby1_sdk as rby
>>> jp = rby.JointPositionCommandBuilder().set_position(np.zeros(7))  # right arm
set_velocity_limit(self: rby1_sdk.JointPositionCommandBuilder, velocity_limit: numpy.ndarray[numpy.float64[m, 1]]) rby1_sdk.JointPositionCommandBuilder#

Set joint velocity limits.

Parameters:

velocity_limit (numpy.ndarray, shape (N,), dtype=float64) – Per-joint velocity limits [rad/s].

Returns:

Self reference for method chaining.

Return type:

JointPositionCommandBuilder

Notes

  • Vector length rule: N must equal the DOF of the commanded component (e.g., model A right arm N=7, full body N=20).

  • If not set, URDF limits for the current robot model are used (see get_robot_model).

  • Values beyond hardware limits may be accepted for profiling; actual tracking is not guaranteed.

Examples

>>> import numpy as np, rby1_sdk as rby
>>> jp = rby.JointPositionCommandBuilder().set_velocity_limit(np.full(7, np.pi))