rby1_sdk.JointGroupPositionCommandBuilder#

class JointGroupPositionCommandBuilder#

Bases: pybind11_object

Joint group position command builder.

Builds joint position commands for a named subset (group) of joints.

Notes

  • Vector length rule: For vector arguments (e.g., position, velocity_limit, acceleration_limit), N equals the number of joint names set by set_joint_names(...).

Examples

Command 3 torso joints by name:

>>> import numpy as np, rby1_sdk as rby
>>> torso = (
...   rby.JointGroupPositionCommandBuilder()
...   .set_joint_names(["torso_3","torso_4","torso_5"])
...   .set_position(np.zeros(3))        # N=3
...   .set_minimum_time(2.0)
... )
__init__(self: rby1_sdk.JointGroupPositionCommandBuilder) None#

Methods

__init__(self)

set_acceleration_limit(self, acceleration_limit)

Set per-joint acceleration limits for the group.

set_command_header(self, command_header_builder)

set_joint_names(self, joint_names)

Set the joint names that this group command applies to.

set_minimum_time(self, minimum_time)

Set the minimum execution time for the motion.

set_position(self, position)

Set group joint target positions in radians.

set_velocity_limit(self, velocity_limit)

Set per-joint velocity limits for the group.

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

Set per-joint acceleration limits for the group.

Parameters:

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

Returns:

Self reference for method chaining.

Return type:

JointGroupPositionCommandBuilder

Notes

Vector length rule: N equals the number of joint names set by set_joint_names(...).

set_command_header(self: rby1_sdk.JointGroupPositionCommandBuilder, command_header_builder: rby1_sdk.CommandHeaderBuilder) rby1_sdk.JointGroupPositionCommandBuilder#
set_joint_names(self: rby1_sdk.JointGroupPositionCommandBuilder, joint_names: list[str]) rby1_sdk.JointGroupPositionCommandBuilder#

Set the joint names that this group command applies to.

Parameters:

joint_names (list of str) – List of joint name identifiers. The order defines the mapping for subsequent vector arguments such as position, velocity_limit, and acceleration_limit.

Returns:

Self reference for method chaining.

Return type:

JointGroupPositionCommandBuilder

Notes

  • Vector length rule: After calling set_joint_names([...]), the length N for all vector arguments must match the number of names provided. For example, if 6 joint names are given, position, velocity_limit, and acceleration_limit must all be length 6.

Examples

>>> import numpy as np, rby1_sdk as rby
>>> torso = (
...   rby.JointGroupPositionCommandBuilder()
...   .set_joint_names(["torso_0","torso_1","torso_2","torso_3","torso_4","torso_5"])
...   .set_position(np.zeros(6))                 # N=6
...   .set_velocity_limit(np.full(6, 1.0))
...   .set_acceleration_limit(np.full(6, 2.0))
...   .set_minimum_time(2.0)
... )
set_minimum_time(self: rby1_sdk.JointGroupPositionCommandBuilder, minimum_time: float) rby1_sdk.JointGroupPositionCommandBuilder#

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:

JointGroupPositionCommandBuilder

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

Set group joint target positions in radians.

Parameters:

position (numpy.ndarray, shape (N,), dtype=float64) – Target joint positions (radians) for the group.

Returns:

Self reference for method chaining.

Return type:

JointGroupPositionCommandBuilder

Notes

Vector length rule: N equals the number of joint names set by set_joint_names(...).

set_velocity_limit(self: rby1_sdk.JointGroupPositionCommandBuilder, velocity_limit: numpy.ndarray[numpy.float64[m, 1]]) rby1_sdk.JointGroupPositionCommandBuilder#

Set per-joint velocity limits for the group.

Parameters:

velocity_limit (numpy.ndarray, shape (N,), dtype=float64) – Velocity limits [rad/s].

Returns:

Self reference for method chaining.

Return type:

JointGroupPositionCommandBuilder

Notes

Vector length rule: N equals the number of joint names set by set_joint_names(...).