|
1 | 1 | # Admittance parameters. |
2 | | -# These are the parameters of a mass-spring-damper model that determines |
| 2 | +# These are the parameters of a mass-spring-damper model that determine |
3 | 3 | # the admittance behavior on each of the Cartesian axes of each tip. |
4 | | -# Each of the individual axis mass, spring, and damper vectors should be the same size as the end_effector_frames vector. |
| 4 | +# Each of the individual mass, spring, and damper vectors have 6 elements, one for each Cartesian axis. |
| 5 | +# They are given in the order: [X, Y, Z, RX, RY, RZ]. |
5 | 6 | # Use carefully. Certain choices may lead to unstable behavior. |
6 | | -float64[] mass_x |
7 | | -float64[] mass_y |
8 | | -float64[] mass_z |
9 | | -float64[] mass_rx |
10 | | -float64[] mass_ry |
11 | | -float64[] mass_rz |
12 | | -float64[] stiffness_x |
13 | | -float64[] stiffness_y |
14 | | -float64[] stiffness_z |
15 | | -float64[] stiffness_rx |
16 | | -float64[] stiffness_ry |
17 | | -float64[] stiffness_rz |
18 | | -float64[] damping_x |
19 | | -float64[] damping_y |
20 | | -float64[] damping_z |
21 | | -float64[] damping_rx |
22 | | -float64[] damping_ry |
23 | | -float64[] damping_rz |
24 | | -float64 joint_damping |
| 7 | +float64[6] mass |
| 8 | +float64[6] stiffness |
| 9 | +float64[6] damping |
| 10 | +bool[6] selected_axes # Axes in the control frame to control with admittance. |
25 | 11 |
|
26 | | -# End-effector frames, masses, and center of gravity (CoG) positions. |
27 | | -string[] end_effector_frames |
28 | | -float64[] end_effector_masses |
29 | | -float64[] end_effector_cogs_x |
30 | | -float64[] end_effector_cogs_y |
31 | | -float64[] end_effector_cogs_z |
32 | | -geometry_msgs/Pose[] ee_poses_control # Control frames w.r.t. end-effector frames. |
33 | | -# Specify which axes of the control frames to control with admittance for each tip. |
34 | | -bool[] x_on |
35 | | -bool[] y_on |
36 | | -bool[] z_on |
37 | | -bool[] rx_on |
38 | | -bool[] ry_on |
39 | | -bool[] rz_on |
| 12 | +# End-effector frame, mass, and center of gravity (CoG) position. |
| 13 | +string end_effector_frame |
| 14 | +float64 end_effector_mass |
| 15 | +float64 end_effector_cog[] # X,Y,Z center of gravity in the end-effector frame. If empty, will default to [0.0, 0.0, 0.0]. |
| 16 | +geometry_msgs/Pose ee_pose_control # Control frame w.r.t. end-effector frame. If empty, will default to identity pose. |
| 17 | + |
| 18 | +# The absolute force or torque threshold value for each Cartesian axis at which |
| 19 | +# the controller will stop executing if exceeded. |
| 20 | +# If the absolute value of an axis of the measured FTS wrench exceeds the corresponding |
| 21 | +# threshold, the trajectory goal is aborted with 'error_code' set to |
| 22 | +# FORCE_TORQUE_THRESHOLD_EXCEEDED. |
| 23 | +# If empty, default threshold values from configs will be used. |
| 24 | +float64[] absolute_force_torque_threshold |
0 commit comments