# 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.
98 lines
4.4 KiB
XML
98 lines
4.4 KiB
XML
<?xml version="1.0"?>
|
||
<!--
|
||
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 xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||
<xacro:macro name="openarm_ros2_control" params="name initial_positions_file prefix:='' can_device='can0' use_mock_hardware:=false mock_sensor_commands:=false">
|
||
<xacro:property name="initial_positions" value="${xacro.load_yaml(initial_positions_file)['initial_positions']}"/>
|
||
|
||
<ros2_control name="${prefix}${name}" type="system">
|
||
<hardware>
|
||
<xacro:if value="${use_mock_hardware}">
|
||
<plugin>mock_components/GenericSystem</plugin>
|
||
<param name="mock_sensor_commands">${mock_sensor_commands}</param>
|
||
</xacro:if>
|
||
<xacro:unless value="${use_mock_hardware}">
|
||
<plugin>openarm_hardware/OpenArmHW</plugin>
|
||
<param name="prefix">${prefix}</param>
|
||
<param name="can_device">${can_device}</param>
|
||
</xacro:unless>
|
||
</hardware>
|
||
<joint name="${prefix}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="${prefix}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="${prefix}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="${prefix}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="${prefix}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="${prefix}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="${prefix}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="${prefix}left_pris1">
|
||
<command_interface name="position"/>
|
||
<state_interface name="position"/>
|
||
<state_interface name="velocity"/>
|
||
</joint>
|
||
|
||
</ros2_control>
|
||
</xacro:macro>
|
||
</robot>
|