openarm_ros2/openarm_description/urdf/openarm.ros2_control.xacro
Yue Yin 14f160bba4
fix: malfunctioning launch script (#19)
## Issue
- **openarm_bringup/openarm.launch.py** was launching rviz2 with an
incorrect configuration file.
- The same launch script is intended to execute xacro with a
configurable prefix and support mock hardware. However, these features
were not functioning as the required arguments and plugin initialization
were missing from the xacro files.

## Fix
- Updated the rviz configuration path to the correct file.
- Added the necessary arguments and plugin setup to the relevant xacro
files to enable prefix configuration and mock hardware support.
2025-06-02 14:57:49 +09:00

104 lines
4.6 KiB
XML
Raw Blame History

This file contains invisible Unicode characters

This file contains invisible Unicode characters that are indistinguishable to humans but may be processed differently by a computer. If you think that this is intentional, you can safely ignore this warning. Use the Escape button to reveal them.

<?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>
<!-- <joint name="${prefix}right_pris2">
<state_interface name="position">
<param name="initial_value">${initial_positions['right_pris2']}</param>
</state_interface>
</joint> -->
</ros2_control>
</xacro:macro>
</robot>