|
8 | 8 | <joint name="${tf_prefix}shoulder_pan_joint"> |
9 | 9 | <command_interface name="position"/> |
10 | 10 | <command_interface name="velocity"/> |
11 | | - <command_interface name="passthrough_position"/> |
12 | | - <command_interface name="passthrough_velocity"/> |
13 | | - <command_interface name="passthrough_acceleration"/> |
14 | 11 | <state_interface name="position"> |
15 | 12 | <!-- initial position for the mock system and simulation --> |
16 | 13 | <param name="initial_value">${initial_positions['shoulder_pan_joint']}</param> |
|
25 | 22 | <joint name="${tf_prefix}shoulder_lift_joint"> |
26 | 23 | <command_interface name="position"/> |
27 | 24 | <command_interface name="velocity"/> |
28 | | - <command_interface name="passthrough_position"/> |
29 | | - <command_interface name="passthrough_velocity"/> |
30 | | - <command_interface name="passthrough_acceleration"/> |
31 | 25 | <state_interface name="position"> |
32 | 26 | <!-- initial position for the mock system and simulation --> |
33 | 27 | <param name="initial_value">${initial_positions['shoulder_lift_joint']}</param> |
|
42 | 36 | <joint name="${tf_prefix}elbow_joint"> |
43 | 37 | <command_interface name="position"/> |
44 | 38 | <command_interface name="velocity"/> |
45 | | - <command_interface name="passthrough_position"/> |
46 | | - <command_interface name="passthrough_velocity"/> |
47 | | - <command_interface name="passthrough_acceleration"/> |
48 | 39 | <state_interface name="position"> |
49 | 40 | <!-- initial position for the mock system and simulation --> |
50 | 41 | <param name="initial_value">${initial_positions['elbow_joint']}</param> |
|
59 | 50 | <joint name="${tf_prefix}wrist_1_joint"> |
60 | 51 | <command_interface name="position"/> |
61 | 52 | <command_interface name="velocity"/> |
62 | | - <command_interface name="passthrough_position"/> |
63 | | - <command_interface name="passthrough_velocity"/> |
64 | | - <command_interface name="passthrough_acceleration"/> |
65 | 53 | <state_interface name="position"> |
66 | 54 | <!-- initial position for the mock system and simulation --> |
67 | 55 | <param name="initial_value">${initial_positions['wrist_1_joint']}</param> |
|
76 | 64 | <joint name="${tf_prefix}wrist_2_joint"> |
77 | 65 | <command_interface name="position"/> |
78 | 66 | <command_interface name="velocity"/> |
79 | | - <command_interface name="passthrough_position"/> |
80 | | - <command_interface name="passthrough_velocity"/> |
81 | | - <command_interface name="passthrough_acceleration"/> |
82 | 67 | <state_interface name="position"> |
83 | 68 | <!-- initial position for the mock system and simulation --> |
84 | 69 | <param name="initial_value">${initial_positions['wrist_2_joint']}</param> |
|
93 | 78 | <joint name="${tf_prefix}wrist_3_joint"> |
94 | 79 | <command_interface name="position"/> |
95 | 80 | <command_interface name="velocity"/> |
96 | | - <command_interface name="passthrough_position"/> |
97 | | - <command_interface name="passthrough_velocity"/> |
98 | | - <command_interface name="passthrough_acceleration"/> |
99 | 81 | <state_interface name="position"> |
100 | 82 | <!-- initial position for the mock system and simulation --> |
101 | 83 | <param name="initial_value">${initial_positions['wrist_3_joint']}</param> |
|
0 commit comments