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.