-
Notifications
You must be signed in to change notification settings - Fork 425
Description
Is your feature request related to a problem? Please describe.
I have an actuator that has a position command interface, as well as position and velocity state interfaces.
My robot description looks a bit like this:
<joint name="my_joint" type="prismatic">
<limits lower="-10.0" upper="10.0" velocity="0.1" effort="10" />
</joint>
<ros2_control name="MockJoint" type="system">
<hardware>
<plugin>mock_components/GenericSystem</plugin>
</hardware>
<joint name="my_joint">
<command_interface name="position" />
<state_interface name="position" />
<state_interface name="velocity" />
</joint>
</ros2_control>The controller manager's parameters:
controller_manager:
ros__parameters:
update_rate: 50
enforce_command_limits: true # because I'm using JazzyI want to enable limiting on the position command, however, this also sets has_velocity_limits (and all the others) to true.
Controller manager log:
[ros2_control_node-1] [INFO] [controller_manager]: Using JointLimiter for joint 'my_joint' in hardware 'MockJoint' : ' has position limits: true [-10.0, 10.0]
[ros2_control_node-1] has velocity limits: true [0.1]
[ros2_control_node-1] has acceleration limits: false [nan]
[ros2_control_node-1] has deceleration limits: false [nan]
[ros2_control_node-1] has jerk limits: false [nan]
[ros2_control_node-1] has effort limits: true [10]
[ros2_control_node-1] angle wraparound: false'
Because of this, when the position command changes too quickly (the command changes by more than max_velocity * 1/update_rate), I get spammed with log errors/warnings saying that the command is beyond the joint's limits.
I'm sure this behavior is helpful to others. Technically yes, the command is asking the actuator to move faster than physically possible in the span of a single update period. However, this is just going to happen since my actuator is so slow compared to the update rate, and I don't consider it a problem in my specific situation.
I can get around this by setting the max velocity to a really big number, however this "solution" is problematic during simulation in gazebo because the joint will be able to move much faster than in real life.
Describe the solution you'd like
I would like to have a way to disable joint limiting for specific interfaces. Preferably, this would be done within the ros2_control tag in the URDF.
I'm not sure exactly how that should be done, but maybe something like this (adding optional parameters like enable_velocity, enable_position, etc. to the <limits> tag):
<ros2_control>
<joint name="my_joint">
...
<limits enable="true" enable_velocity="false" />
...
</joint>
</ros2_control>Describe alternatives you've considered
A parameter in the controller manager like this could work too.
Something like:
controller_manager:
ros__parameters:
update_rate: 50
enforce_command_limits: true
joint_limits:
my_joint:
has_velocity_limits: falseAdditional context
Since #2262 is still open and there isn't much documentation for how joint limiting, I'm not entirely sure how it works.
If there is already a solution to this that doesn't require any changes, but just isn't documented yet, please let me know!
Metadata
Metadata
Assignees
Labels
Type
Projects
Status