- openarm_bringup: ros2_control bringup - openarm_hardware: hardware interface for ros2_control
99 lines
4.6 KiB
XML
99 lines
4.6 KiB
XML
<?xml version="1.0"?>
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
<xacro:macro name="openarm_ros2_control" params="name initial_positions_file prefix:=''">
|
|
<xacro:property name="initial_positions" value="${xacro.load_yaml(initial_positions_file)['initial_positions']}"/>
|
|
|
|
<ros2_control name="${prefix}${name}" 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>
|
|
</hardware>
|
|
<joint name="${prefix}rev1">
|
|
<command_interface name="position"/>
|
|
<command_interface name="velocity"/>
|
|
<command_interface name="effort"/>
|
|
<state_interface name="position">
|
|
<param name="initial_value">${initial_positions['rev1']}</param>
|
|
</state_interface>
|
|
<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">
|
|
<param name="initial_value">${initial_positions['rev2']}</param>
|
|
</state_interface>
|
|
<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">
|
|
<param name="initial_value">${initial_positions['rev3']}</param>
|
|
</state_interface>
|
|
<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">
|
|
<param name="initial_value">${initial_positions['rev4']}</param>
|
|
</state_interface>
|
|
<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">
|
|
<param name="initial_value">${initial_positions['rev5']}</param>
|
|
</state_interface>
|
|
<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">
|
|
<param name="initial_value">${initial_positions['rev6']}</param>
|
|
</state_interface>
|
|
<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">
|
|
<param name="initial_value">${initial_positions['rev7']}</param>
|
|
</state_interface>
|
|
<state_interface name="velocity"/>
|
|
<state_interface name="effort"/>
|
|
</joint>
|
|
<joint name="${prefix}left_pris1">
|
|
<command_interface name="position"/>
|
|
<state_interface name="position">
|
|
<param name="initial_value">${initial_positions['left_pris1']}</param>
|
|
</state_interface>
|
|
<state_interface name="velocity"/>
|
|
</joint>
|
|
|
|
<joint name="${prefix}right_pris2">
|
|
<state_interface name="position">
|
|
<param name="initial_value">${initial_positions['left_pris1']}</param>
|
|
</state_interface>
|
|
</joint>
|
|
|
|
</ros2_control>
|
|
</xacro:macro>
|
|
</robot>
|