Skip to content

Commit

Permalink
Split limits into speed_limit and deviation_limit
Browse files Browse the repository at this point in the history
Having different domains in one field seems like an anti-pattern.
  • Loading branch information
fmauch committed Nov 7, 2024
1 parent fa6d784 commit 2d411aa
Showing 1 changed file with 5 additions and 2 deletions.
7 changes: 5 additions & 2 deletions srv/SetForceMode.srv
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,13 @@ uint8 TCP_TO_ORIGIN=1
uint8 NO_TRANSFORM=2
uint8 TCP_VELOCITY_TO_X_Y=3

# For compliant axes, these values are the maximum allowed tcp speed along/about the axis.
# Maximum allowed tcp speed (relative to the task frame).
# PLEASE NOTE: This is only relevant for axes marked as compliant in the selection_vector
geometry_msgs/Twist speed_limit

# For non-compliant axes, these values are the maximum allowed deviation along/about an axis
# between the actual tcp position and the one set by the program.
float32[6] limits [0.01, 0.01, 0.01, 0.01, 0.01, 0.01]
float32[6] deviation_limits [0.01, 0.01, 0.01, 0.01, 0.01, 0.01]

# Force mode damping factor. Sets the damping parameter in force mode. In range [0;1], default value is 0.025
# A value of 1 is full damping, so the robot will decelerate quickly if no force is present. A value of 0
Expand Down

0 comments on commit 2d411aa

Please sign in to comment.