|
69 | 69 | <joint name="${tf_prefix}shoulder_pan_joint"> |
70 | 70 | <command_interface name="position"/> |
71 | 71 | <command_interface name="velocity"/> |
72 | | - <xacro:unless value="$(arg sim_ignition)"> |
| 72 | + <xacro:unless value="${sim_ignition}"> |
73 | 73 | <command_interface name="effort"/> |
74 | 74 | </xacro:unless> |
75 | 75 | <state_interface name="position"> |
|
82 | 82 | <joint name="${tf_prefix}shoulder_lift_joint"> |
83 | 83 | <command_interface name="position"/> |
84 | 84 | <command_interface name="velocity"/> |
85 | | - <xacro:unless value="$(arg sim_ignition)"> |
| 85 | + <xacro:unless value="${sim_ignition}"> |
86 | 86 | <command_interface name="effort"/> |
87 | 87 | </xacro:unless> |
88 | 88 | <state_interface name="position"> |
|
95 | 95 | <joint name="${tf_prefix}elbow_joint"> |
96 | 96 | <command_interface name="position"/> |
97 | 97 | <command_interface name="velocity"/> |
98 | | - <xacro:unless value="$(arg sim_ignition)"> |
| 98 | + <xacro:unless value="${sim_ignition}"> |
99 | 99 | <command_interface name="effort"/> |
100 | 100 | </xacro:unless> |
101 | 101 | <state_interface name="position"> |
|
108 | 108 | <joint name="${tf_prefix}wrist_1_joint"> |
109 | 109 | <command_interface name="position"/> |
110 | 110 | <command_interface name="velocity"/> |
111 | | - <xacro:unless value="$(arg sim_ignition)"> |
| 111 | + <xacro:unless value="${sim_ignition}"> |
112 | 112 | <command_interface name="effort"/> |
113 | 113 | </xacro:unless> |
114 | 114 | <state_interface name="position"> |
|
121 | 121 | <joint name="${tf_prefix}wrist_2_joint"> |
122 | 122 | <command_interface name="position"/> |
123 | 123 | <command_interface name="velocity"/> |
124 | | - <xacro:unless value="$(arg sim_ignition)"> |
| 124 | + <xacro:unless value="${sim_ignition}"> |
125 | 125 | <command_interface name="effort"/> |
126 | 126 | </xacro:unless> |
127 | 127 | <state_interface name="position"> |
|
134 | 134 | <joint name="${tf_prefix}wrist_3_joint"> |
135 | 135 | <command_interface name="position"/> |
136 | 136 | <command_interface name="velocity"/> |
137 | | - <xacro:unless value="$(arg sim_ignition)"> |
| 137 | + <xacro:unless value="${sim_ignition}"> |
138 | 138 | <command_interface name="effort"/> |
139 | 139 | </xacro:unless> |
140 | 140 | <state_interface name="position"> |
|
0 commit comments