rby1_sdk.JointVelocityCommandBuilder#
- class JointVelocityCommandBuilder#
Bases:
pybind11_objectJoint velocity command builder.
Builds a joint-space velocity command with optional acceleration limits. When a target velocity vector \(v_d\) is set, the command generates a linear ramp from the current velocity \(v_{curr}\) to \(v_d\), considering both acceleration limits and the specified minimum time.
The controller’s objective is to reach the target velocity. If you need the robot to hold the target velocity after reaching it, you must specify a control hold time in the command header.
Examples
>>> import numpy as np, rby1_sdk as rby >>> # Ramp torso joints to 0.5 rad/s with acceleration limits >>> cmd = ( ... rby.JointVelocityCommandBuilder() ... .set_velocity(np.full(6, 0.5)) ... .set_acceleration_limit(np.full(6, 2.0)) ... .set_minimum_time(1.0) ... ) >>> # To maintain the velocity after reaching 0.5 rad/s, >>> # add a CommandHeader with control_hold_time. >>> header = rby.CommandHeaderBuilder().set_control_hold_time(5.0) >>> cmd.set_command_header(header)
- __init__(self: rby1_sdk.JointVelocityCommandBuilder) None#
Methods
__init__(self)set_acceleration_limit(self, acceleration_limit)Set per-joint acceleration limits.
set_command_header(self, command_header_builder)Attach a command header.
set_minimum_time(self, minimum_time)Set the minimum execution time.
set_velocity(self, velocity)Set desired joint velocities.
- set_acceleration_limit(self: rby1_sdk.JointVelocityCommandBuilder, acceleration_limit: numpy.ndarray[numpy.float64[m, 1]]) rby1_sdk.JointVelocityCommandBuilder#
Set per-joint acceleration limits.
- Parameters:
acceleration_limit (numpy.ndarray, shape (N,), dtype=float64) – Maximum allowable accelerations [rad/s²]. Length \(N\) must equal the number of joints in the targeted component.
- Returns:
Self reference for method chaining.
- Return type:
Notes
These limits shape the linear ramp profile toward the target velocity.
If not set, URDF defaults are used (see
get_robot_model).
- set_command_header(self: rby1_sdk.JointVelocityCommandBuilder, command_header_builder: rby1_sdk.CommandHeaderBuilder) rby1_sdk.JointVelocityCommandBuilder#
Attach a command header.
- Parameters:
command_header_builder (CommandHeaderBuilder) – Command header configuration (e.g., control hold time).
- Returns:
Self reference for method chaining.
- Return type:
Notes
Use
control_hold_timeto maintain the commanded velocity once reached.
- set_minimum_time(self: rby1_sdk.JointVelocityCommandBuilder, minimum_time: float) rby1_sdk.JointVelocityCommandBuilder#
Set the minimum execution time.
- Parameters:
minimum_time (float) – Minimum execution time in seconds. Ensures the ramping process to the target velocity is stretched at least over this duration.
- Returns:
Self reference for method chaining.
- Return type:
- set_velocity(self: rby1_sdk.JointVelocityCommandBuilder, velocity: numpy.ndarray[numpy.float64[m, 1]]) rby1_sdk.JointVelocityCommandBuilder#
Set desired joint velocities.
- Parameters:
velocity (numpy.ndarray, shape (N,), dtype=float64) – Per-joint target velocities [rad/s]. Length \(N\) must equal the number of joints in the targeted component.
- Returns:
Self reference for method chaining.
- Return type:
Notes
The command ramps linearly from the current velocity to the target velocity.
To hold the target velocity after reaching it, add a command header with a control hold time.