|
69 | 69 | <joint name="${tf_prefix}shoulder_pan_joint"> |
70 | 70 | <command_interface name="position"/> |
71 | 71 | <command_interface name="velocity"/> |
| 72 | + <command_interface name="effort"/> |
72 | 73 | <state_interface name="position"> |
73 | 74 | <!-- initial position for the FakeSystem and simulation --> |
74 | 75 | <param name="initial_value">${initial_positions['shoulder_pan_joint']}</param> |
|
79 | 80 | <joint name="${tf_prefix}shoulder_lift_joint"> |
80 | 81 | <command_interface name="position"/> |
81 | 82 | <command_interface name="velocity"/> |
| 83 | + <command_interface name="effort"/> |
82 | 84 | <state_interface name="position"> |
83 | 85 | <!-- initial position for the FakeSystem and simulation --> |
84 | 86 | <param name="initial_value">${initial_positions['shoulder_lift_joint']}</param> |
|
89 | 91 | <joint name="${tf_prefix}elbow_joint"> |
90 | 92 | <command_interface name="position"/> |
91 | 93 | <command_interface name="velocity"/> |
| 94 | + <command_interface name="effort"/> |
92 | 95 | <state_interface name="position"> |
93 | 96 | <!-- initial position for the FakeSystem and simulation --> |
94 | 97 | <param name="initial_value">${initial_positions['elbow_joint']}</param> |
|
99 | 102 | <joint name="${tf_prefix}wrist_1_joint"> |
100 | 103 | <command_interface name="position"/> |
101 | 104 | <command_interface name="velocity"/> |
| 105 | + <command_interface name="effort"/> |
102 | 106 | <state_interface name="position"> |
103 | 107 | <!-- initial position for the FakeSystem and simulation --> |
104 | 108 | <param name="initial_value">${initial_positions['wrist_1_joint']}</param> |
|
109 | 113 | <joint name="${tf_prefix}wrist_2_joint"> |
110 | 114 | <command_interface name="position"/> |
111 | 115 | <command_interface name="velocity"/> |
| 116 | + <command_interface name="effort"/> |
112 | 117 | <state_interface name="position"> |
113 | 118 | <!-- initial position for the FakeSystem and simulation --> |
114 | 119 | <param name="initial_value">${initial_positions['wrist_2_joint']}</param> |
|
119 | 124 | <joint name="${tf_prefix}wrist_3_joint"> |
120 | 125 | <command_interface name="position"/> |
121 | 126 | <command_interface name="velocity"/> |
| 127 | + <command_interface name="effort"/> |
122 | 128 | <state_interface name="position"> |
123 | 129 | <!-- initial position for the FakeSystem and simulation --> |
124 | 130 | <param name="initial_value">${initial_positions['wrist_3_joint']}</param> |
|
0 commit comments