urdf: Pass can_fd parameter to openarm_arm_ros2_control macro (#23)
GitHub fixes GH-21 `can_fd` option can be specified on the command line.
This commit is contained in:
parent
6148297241
commit
ab816fc11c
@ -35,6 +35,7 @@
|
||||
right_can_interface:='can0'
|
||||
left_arm_prefix:='left_'
|
||||
right_arm_prefix:='right_'
|
||||
can_fd:='true'
|
||||
"
|
||||
>
|
||||
|
||||
@ -164,7 +165,8 @@
|
||||
use_fake_hardware="${use_fake_hardware}"
|
||||
fake_sensor_commands="${fake_sensor_commands}"
|
||||
hand="${hand}"
|
||||
bimanual="false"/>
|
||||
bimanual="false"
|
||||
can_fd="${can_fd}"/>
|
||||
</xacro:if>
|
||||
|
||||
<xacro:if value="${hand and ee_type == 'openarm_hand'}">
|
||||
|
||||
@ -47,6 +47,8 @@
|
||||
<xacro:arg name="left_arm_base_xyz" default="0.0 0.031 0.698" />
|
||||
<xacro:arg name="left_arm_base_rpy" default="-1.5708 0 0" />
|
||||
|
||||
<xacro:arg name="can_fd" default="true" />
|
||||
|
||||
<xacro:openarm_robot
|
||||
arm_type="v10"
|
||||
body_type="v10"
|
||||
@ -79,6 +81,7 @@
|
||||
left_arm_base_xyz="$(arg left_arm_base_xyz)"
|
||||
right_arm_base_rpy="$(arg right_arm_base_rpy)"
|
||||
left_arm_base_rpy="$(arg left_arm_base_rpy)"
|
||||
can_fd="$(arg can_fd)"
|
||||
/>
|
||||
|
||||
</robot>
|
||||
|
||||
Loading…
Reference in New Issue
Block a user