|
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 | + <xacro:unless value="$(arg sim_ignition)"> |
| 73 | + <command_interface name="effort"/> |
| 74 | + </xacro:unless> |
73 | 75 | <state_interface name="position"> |
74 | 76 | <!-- initial position for the FakeSystem and simulation --> |
75 | 77 | <param name="initial_value">${initial_positions['shoulder_pan_joint']}</param> |
|
80 | 82 | <joint name="${tf_prefix}shoulder_lift_joint"> |
81 | 83 | <command_interface name="position"/> |
82 | 84 | <command_interface name="velocity"/> |
83 | | - <command_interface name="effort"/> |
| 85 | + <xacro:unless value="$(arg sim_ignition)"> |
| 86 | + <command_interface name="effort"/> |
| 87 | + </xacro:unless> |
84 | 88 | <state_interface name="position"> |
85 | 89 | <!-- initial position for the FakeSystem and simulation --> |
86 | 90 | <param name="initial_value">${initial_positions['shoulder_lift_joint']}</param> |
|
91 | 95 | <joint name="${tf_prefix}elbow_joint"> |
92 | 96 | <command_interface name="position"/> |
93 | 97 | <command_interface name="velocity"/> |
94 | | - <command_interface name="effort"/> |
| 98 | + <xacro:unless value="$(arg sim_ignition)"> |
| 99 | + <command_interface name="effort"/> |
| 100 | + </xacro:unless> |
95 | 101 | <state_interface name="position"> |
96 | 102 | <!-- initial position for the FakeSystem and simulation --> |
97 | 103 | <param name="initial_value">${initial_positions['elbow_joint']}</param> |
|
102 | 108 | <joint name="${tf_prefix}wrist_1_joint"> |
103 | 109 | <command_interface name="position"/> |
104 | 110 | <command_interface name="velocity"/> |
105 | | - <command_interface name="effort"/> |
| 111 | + <xacro:unless value="$(arg sim_ignition)"> |
| 112 | + <command_interface name="effort"/> |
| 113 | + </xacro:unless> |
106 | 114 | <state_interface name="position"> |
107 | 115 | <!-- initial position for the FakeSystem and simulation --> |
108 | 116 | <param name="initial_value">${initial_positions['wrist_1_joint']}</param> |
|
113 | 121 | <joint name="${tf_prefix}wrist_2_joint"> |
114 | 122 | <command_interface name="position"/> |
115 | 123 | <command_interface name="velocity"/> |
116 | | - <command_interface name="effort"/> |
| 124 | + <xacro:unless value="$(arg sim_ignition)"> |
| 125 | + <command_interface name="effort"/> |
| 126 | + </xacro:unless> |
117 | 127 | <state_interface name="position"> |
118 | 128 | <!-- initial position for the FakeSystem and simulation --> |
119 | 129 | <param name="initial_value">${initial_positions['wrist_2_joint']}</param> |
|
124 | 134 | <joint name="${tf_prefix}wrist_3_joint"> |
125 | 135 | <command_interface name="position"/> |
126 | 136 | <command_interface name="velocity"/> |
127 | | - <command_interface name="effort"/> |
| 137 | + <xacro:unless value="$(arg sim_ignition)"> |
| 138 | + <command_interface name="effort"/> |
| 139 | + </xacro:unless> |
128 | 140 | <state_interface name="position"> |
129 | 141 | <!-- initial position for the FakeSystem and simulation --> |
130 | 142 | <param name="initial_value">${initial_positions['wrist_3_joint']}</param> |
|
0 commit comments