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