refactor: separate robot and control xacros (#22)

# Summary
The previous URDF directory structure used has a chained call from
**openarm.urdf.xacro** -> **openarm.xacro** ->
**openarm.ros2_control.xacro**.
**openarm.xacro** takes both robot hardware description and
control/communication configuration arguments but the file content is
only about robot description.

# Changes Made
- Renamed **openarm.xacro** to **openarm.robot.xacro**. This file now
contains only the robot's hardware description, including links, joints,
visuals, and inertial properties.
- **openarm.control.xacro** handles all ROS 2 control configurations,
including hardware interfaces, joint interfaces, and CAN device setup.
- Updated openarm.urdf.xacro (entry point)Calls both
**openarm.robot.xacro** and **openarm.control.xacro**.

This change should separates responsibilities and arguments for each
subsystem.
Have tested with bringup scripts for both single-arm and bimanual
configurations.
This commit is contained in:
Yue Yin 2025-06-08 21:21:10 +09:00 committed by GitHub
parent 2206a7bf95
commit 5bbe23cf28
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
6 changed files with 582 additions and 556 deletions

View File

@ -1,8 +1,23 @@
<?xml version="1.0" ?> <?xml version="1.0" ?>
<!-- =================================================================================== --> <!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from openarm_bimanual.urdf.xacro | --> <!-- | This document was autogenerated by xacro from openarm_bimanual_description/urdf/openarm_bimanual.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== --> <!-- =================================================================================== -->
<!--
 Copyright 2025 Reazon Holdings, Inc.
 Licensed under the Apache License, Version 2.0 (the "License");
 you may not use this file except in compliance with the License.
 You may obtain a copy of the License at
  http://www.apache.org/licenses/LICENSE-2.0
 Unless required by applicable law or agreed to in writing, software
 distributed under the License is distributed on an "AS IS" BASIS,
 WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 See the License for the specific language governing permissions and
 limitations under the License.
-->
<robot name="openarm_bimanual"> <robot name="openarm_bimanual">
<material name="gray"> <material name="gray">
<color rgba="0.4117647058823529 0.4117647058823529 0.4117647058823529 1.0"/> <color rgba="0.4117647058823529 0.4117647058823529 0.4117647058823529 1.0"/>
@ -156,81 +171,6 @@
<!-- side right, left --> <!-- side right, left -->
<!-- recommended prefixes left_, right_, etc. --> <!-- recommended prefixes left_, right_, etc. -->
<!-- zero_pos up, arm --> <!-- zero_pos up, arm -->
<ros2_control name="right_OpenArmHW" type="system">
<hardware>
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
<!-- <plugin>mock_components/GenericSystem</plugin> -->
<plugin>openarm_hardware/OpenArmHW</plugin>
<param name="prefix">right_</param>
<param name="can_device">can0</param>
</hardware>
<joint name="right_rev1">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_rev2">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_rev3">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_rev4">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_rev5">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_rev6">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_rev7">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_left_pris1">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<!-- <joint name="${prefix}right_pris2">
<state_interface name="position">
<param name="initial_value">${initial_positions['right_pris2']}</param>
</state_interface>
</joint> -->
</ros2_control>
<link name="right_dummy_link"/> <link name="right_dummy_link"/>
<joint name="right_dummy_joint" type="fixed"> <joint name="right_dummy_joint" type="fixed">
<parent link="right_dummy_link"/> <parent link="right_dummy_link"/>
@ -514,81 +454,6 @@
<!-- side right, left --> <!-- side right, left -->
<!-- recommended prefixes left_, right_, etc. --> <!-- recommended prefixes left_, right_, etc. -->
<!-- zero_pos up, arm --> <!-- zero_pos up, arm -->
<ros2_control name="left_OpenArmHW" type="system">
<hardware>
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
<!-- <plugin>mock_components/GenericSystem</plugin> -->
<plugin>openarm_hardware/OpenArmHW</plugin>
<param name="prefix">left_</param>
<param name="can_device">can1</param>
</hardware>
<joint name="left_rev1">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_rev2">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_rev3">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_rev4">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_rev5">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_rev6">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_rev7">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_left_pris1">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<!-- <joint name="${prefix}right_pris2">
<state_interface name="position">
<param name="initial_value">${initial_positions['right_pris2']}</param>
</state_interface>
</joint> -->
</ros2_control>
<link name="left_dummy_link"/> <link name="left_dummy_link"/>
<joint name="left_dummy_joint" type="fixed"> <joint name="left_dummy_joint" type="fixed">
<parent link="left_dummy_link"/> <parent link="left_dummy_link"/>
@ -869,4 +734,140 @@
<child link="left_dummy_link"/> <child link="left_dummy_link"/>
<origin rpy="3.0144791747751833 -1.5707963267948324 0.12689401604101067" xyz="0.09 0.0 0.893"/> <origin rpy="3.0144791747751833 -1.5707963267948324 0.12689401604101067" xyz="0.09 0.0 0.893"/>
</joint> </joint>
<ros2_control name="right_RightOpenArmHW" type="system">
<hardware>
<plugin>openarm_hardware/OpenArmHW</plugin>
<param name="prefix">right_</param>
<param name="can_device">can0</param>
</hardware>
<joint name="right_rev1">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_rev2">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_rev3">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_rev4">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_rev5">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_rev6">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_rev7">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="right_left_pris1">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
<ros2_control name="left_LeftOpenArmHW" type="system">
<hardware>
<plugin>openarm_hardware/OpenArmHW</plugin>
<param name="prefix">left_</param>
<param name="can_device">can1</param>
</hardware>
<joint name="left_rev1">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_rev2">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_rev3">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_rev4">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_rev5">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_rev6">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_rev7">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_left_pris1">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
</robot> </robot>

View File

@ -16,7 +16,16 @@
--> -->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_bimanual"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm_bimanual">
<xacro:include filename="$(find openarm_description)/urdf/openarm.xacro"/> <!-- Robot description parameters -->
<xacro:arg name="prefix" default="" />
<!-- Control-related parameters -->
<xacro:arg name="right_can_device" default="can0" />
<xacro:arg name="left_can_device" default="can1" />
<xacro:arg name="use_mock_hardware" default="false" />
<xacro:arg name="mock_sensor_commands" default="false" />
<xacro:include filename="$(find openarm_description)/urdf/openarm.robot.xacro"/>
<xacro:include filename="$(find openarm_bimanual_description)/urdf/openarm_pedestal.urdf"/> <xacro:include filename="$(find openarm_bimanual_description)/urdf/openarm_pedestal.urdf"/>
<xacro:include filename="openarm_bimanual_sensors.xacro"/> <xacro:include filename="openarm_bimanual_sensors.xacro"/>
@ -27,18 +36,26 @@
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/> <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</joint> </joint>
<xacro:openarm prefix="right_" side="right" zero_pos="arm" can_device="can0"/> <xacro:openarm_robot prefix="right_" side="right" zero_pos="arm"/>
<joint name="right_fixed1" type="fixed"> <joint name="right_fixed1" type="fixed">
<parent link="pedestal_link"/> <parent link="pedestal_link"/>
<child link="right_dummy_link"/> <child link="right_dummy_link"/>
<origin rpy="${3.0186531925068127 + pi} -1.5707963267948268 0.12293946108298068" xyz="-0.09 0.0 0.893"/> <origin rpy="${3.0186531925068127 + pi} -1.5707963267948268 0.12293946108298068" xyz="-0.09 0.0 0.893"/>
</joint> </joint>
<xacro:openarm prefix="left_" side="left" zero_pos="arm" can_device="can1"/> <xacro:openarm_robot prefix="left_" side="left" zero_pos="arm"/>
<joint name="left_fixed1" type="fixed"> <joint name="left_fixed1" type="fixed">
<parent link="pedestal_link"/> <parent link="pedestal_link"/>
<child link="left_dummy_link"/> <child link="left_dummy_link"/>
<origin rpy="3.0144791747751833 -1.5707963267948324 0.12689401604101067" xyz="0.09 0.0 0.893"/> <origin rpy="3.0144791747751833 -1.5707963267948324 0.12689401604101067" xyz="0.09 0.0 0.893"/>
</joint> </joint>
<!-- Include control configuration for both arms -->
<xacro:include filename="$(find openarm_description)/urdf/openarm.ros2_control.xacro"/>
<xacro:arg name="right_initial_positions_file" default="$(find openarm_description)/config/initial_positions.yaml" />
<xacro:arg name="left_initial_positions_file" default="$(find openarm_description)/config/initial_positions.yaml" />
<xacro:openarm_ros2_control name="RightOpenArmHW" prefix="right_" initial_positions_file="$(arg right_initial_positions_file)" can_device="$(arg right_can_device)" use_mock_hardware="$(arg use_mock_hardware)" mock_sensor_commands="$(arg mock_sensor_commands)"/>
<xacro:openarm_ros2_control name="LeftOpenArmHW" prefix="left_" initial_positions_file="$(arg left_initial_positions_file)" can_device="$(arg left_can_device)" use_mock_hardware="$(arg use_mock_hardware)" mock_sensor_commands="$(arg mock_sensor_commands)"/>
</robot> </robot>

View File

@ -23,19 +23,14 @@
<color rgba="${50/255} ${50/255} ${50/255} 1.0"/> <color rgba="${50/255} ${50/255} ${50/255} 1.0"/>
</material> </material>
<xacro:macro name="openarm" params="side:='right' prefix:='' zero_pos='up' can_device='can0' use_mock_hardware:=false mock_sensor_commands:=false"> <xacro:macro name="openarm_robot" params="side:='right' prefix:='' zero_pos='up'">
<!-- side right, left --> <!-- side right, left -->
<!-- recommended prefixes left_, right_, etc. --> <!-- recommended prefixes left_, right_, etc. -->
<!-- zero_pos up, arm --> <!-- zero_pos up, arm -->
<xacro:property name="reflect" value="${1 if side=='right' else -1}"/> <xacro:property name="reflect" value="${1 if side=='right' else -1}"/>
<xacro:property name="rotate" value="${0 if side=='right' else pi}"/> <xacro:property name="rotate" value="${0 if side=='right' else pi}"/>
<xacro:include filename="$(find openarm_description)/urdf/openarm.ros2_control.xacro" />
<xacro:arg name="initial_positions_file" default="$(find openarm_description)/config/initial_positions.yaml" />
<xacro:openarm_ros2_control name="OpenArmHW" prefix="${prefix}" initial_positions_file="$(arg initial_positions_file)" can_device="${can_device}" use_mock_hardware="${use_mock_hardware}" mock_sensor_commands="${mock_sensor_commands}"/>
<link name="${prefix}dummy_link"/> <link name="${prefix}dummy_link"/>
<joint name="${prefix}dummy_joint" type="fixed"> <joint name="${prefix}dummy_joint" type="fixed">

View File

@ -92,12 +92,6 @@
<state_interface name="velocity"/> <state_interface name="velocity"/>
</joint> </joint>
<!-- <joint name="${prefix}right_pris2">
<state_interface name="position">
<param name="initial_value">${initial_positions['right_pris2']}</param>
</state_interface>
</joint> -->
</ros2_control> </ros2_control>
</xacro:macro> </xacro:macro>
</robot> </robot>

View File

@ -1,8 +1,23 @@
<?xml version="1.0" ?> <?xml version="1.0" ?>
<!-- =================================================================================== --> <!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from openarm.urdf.xacro | --> <!-- | This document was autogenerated by xacro from openarm_description/urdf/openarm.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> <!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== --> <!-- =================================================================================== -->
<!--
 Copyright 2025 Reazon Holdings, Inc.
 Licensed under the Apache License, Version 2.0 (the "License");
 you may not use this file except in compliance with the License.
 You may obtain a copy of the License at
  http://www.apache.org/licenses/LICENSE-2.0
 Unless required by applicable law or agreed to in writing, software
 distributed under the License is distributed on an "AS IS" BASIS,
 WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 See the License for the specific language governing permissions and
 limitations under the License.
-->
<robot name="openarm"> <robot name="openarm">
<material name="gray"> <material name="gray">
<color rgba="0.4117647058823529 0.4117647058823529 0.4117647058823529 1.0"/> <color rgba="0.4117647058823529 0.4117647058823529 0.4117647058823529 1.0"/>
@ -13,81 +28,6 @@
<!-- side right, left --> <!-- side right, left -->
<!-- recommended prefixes left_, right_, etc. --> <!-- recommended prefixes left_, right_, etc. -->
<!-- zero_pos up, arm --> <!-- zero_pos up, arm -->
<ros2_control name="OpenArmHW" type="system">
<hardware>
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
<!-- <plugin>mock_components/GenericSystem</plugin> -->
<plugin>openarm_hardware/OpenArmHW</plugin>
<param name="prefix"></param>
<param name="can_device">can0</param>
</hardware>
<joint name="rev1">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev2">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev3">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev4">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev5">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev6">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev7">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_pris1">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<!-- <joint name="${prefix}right_pris2">
<state_interface name="position">
<param name="initial_value">${initial_positions['right_pris2']}</param>
</state_interface>
</joint> -->
</ros2_control>
<link name="dummy_link"/> <link name="dummy_link"/>
<joint name="dummy_joint" type="fixed"> <joint name="dummy_joint" type="fixed">
<parent link="dummy_link"/> <parent link="dummy_link"/>
@ -363,4 +303,71 @@
<child link="gripper_center"/> <child link="gripper_center"/>
<origin rpy="0 0 0" xyz="-0.13 0.00 0.0132053"/> <origin rpy="0 0 0" xyz="-0.13 0.00 0.0132053"/>
</joint> </joint>
<ros2_control name="OpenArmHW" type="system">
<hardware>
<plugin>mock_components/GenericSystem</plugin>
<param name="mock_sensor_commands">False</param>
</hardware>
<joint name="rev1">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev2">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev3">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev4">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev5">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev6">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="rev7">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="left_pris1">
<command_interface name="position"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
</robot> </robot>

View File

@ -15,11 +15,23 @@
 limitations under the License.  limitations under the License.
--> -->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="openarm">
<!-- Robot description parameters -->
<xacro:arg name="prefix" default="" /> <xacro:arg name="prefix" default="" />
<xacro:arg name="side" default="right" />
<xacro:arg name="zero_pos" default="up" />
<!-- Control-related parameters -->
<xacro:arg name="can_device" default="can0" />
<xacro:arg name="use_mock_hardware" default="false" /> <xacro:arg name="use_mock_hardware" default="false" />
<xacro:arg name="mock_sensor_commands" default="false" /> <xacro:arg name="mock_sensor_commands" default="false" />
<xacro:include filename="openarm.xacro"/> <!-- Include robot description (without control parameters) -->
<xacro:openarm prefix="$(arg prefix)" use_mock_hardware="$(arg use_mock_hardware)" mock_sensor_commands="$(arg mock_sensor_commands)"/> <xacro:include filename="openarm.robot.xacro"/>
<xacro:include filename="$(find openarm_description)/urdf/openarm_sensors.xacro"/> <xacro:openarm_robot prefix="$(arg prefix)" side="$(arg side)" zero_pos="$(arg zero_pos)"/>
<!-- Include control configuration (with only control parameters) -->
<xacro:include filename="$(find openarm_description)/urdf/openarm.ros2_control.xacro"/>
<xacro:arg name="initial_positions_file" default="$(find openarm_description)/config/initial_positions.yaml" />
<xacro:openarm_ros2_control name="OpenArmHW" prefix="$(arg prefix)" initial_positions_file="$(arg initial_positions_file)" can_device="$(arg can_device)" use_mock_hardware="$(arg use_mock_hardware)" mock_sensor_commands="$(arg mock_sensor_commands)"/>
</robot> </robot>