87 lines
3.9 KiB
Plaintext
87 lines
3.9 KiB
Plaintext
|
|
<?xml version="1.0"?>
|
||
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||
|
|
<xacro:macro name="openarm_grip_ros2_control" params="name initial_positions_file">
|
||
|
|
<xacro:property name="initial_positions" value="${xacro.load_yaml(initial_positions_file)['initial_positions']}"/>
|
||
|
|
|
||
|
|
<ros2_control name="${name}" type="system">
|
||
|
|
<hardware>
|
||
|
|
<!-- By default, set up controllers for simulation. This won't work on real hardware -->
|
||
|
|
<plugin>mock_components/GenericSystem</plugin>
|
||
|
|
</hardware>
|
||
|
|
<joint name="rev1">
|
||
|
|
<command_interface name="position"/>
|
||
|
|
<command_interface name="velocity"/>
|
||
|
|
<state_interface name="position">
|
||
|
|
<param name="initial_value">${initial_positions['rev1']}</param>
|
||
|
|
</state_interface>
|
||
|
|
<state_interface name="velocity"/>
|
||
|
|
</joint>
|
||
|
|
<joint name="rev2">
|
||
|
|
<command_interface name="position"/>
|
||
|
|
<command_interface name="velocity"/>
|
||
|
|
<state_interface name="position">
|
||
|
|
<param name="initial_value">${initial_positions['rev2']}</param>
|
||
|
|
</state_interface>
|
||
|
|
<state_interface name="velocity"/>
|
||
|
|
</joint>
|
||
|
|
<joint name="rev3">
|
||
|
|
<command_interface name="position"/>
|
||
|
|
<command_interface name="velocity"/>
|
||
|
|
<state_interface name="position">
|
||
|
|
<param name="initial_value">${initial_positions['rev3']}</param>
|
||
|
|
</state_interface>
|
||
|
|
<state_interface name="velocity"/>
|
||
|
|
</joint>
|
||
|
|
<joint name="rev4">
|
||
|
|
<command_interface name="position"/>
|
||
|
|
<command_interface name="velocity"/>
|
||
|
|
<state_interface name="position">
|
||
|
|
<param name="initial_value">${initial_positions['rev4']}</param>
|
||
|
|
</state_interface>
|
||
|
|
<state_interface name="velocity"/>
|
||
|
|
</joint>
|
||
|
|
<joint name="rev5">
|
||
|
|
<command_interface name="position"/>
|
||
|
|
<command_interface name="velocity"/>
|
||
|
|
<state_interface name="position">
|
||
|
|
<param name="initial_value">${initial_positions['rev5']}</param>
|
||
|
|
</state_interface>
|
||
|
|
<state_interface name="velocity"/>
|
||
|
|
</joint>
|
||
|
|
<joint name="rev6">
|
||
|
|
<command_interface name="position"/>
|
||
|
|
<command_interface name="velocity"/>
|
||
|
|
<state_interface name="position">
|
||
|
|
<param name="initial_value">${initial_positions['rev6']}</param>
|
||
|
|
</state_interface>
|
||
|
|
<state_interface name="velocity"/>
|
||
|
|
</joint>
|
||
|
|
<joint name="rev7">
|
||
|
|
<command_interface name="position"/>
|
||
|
|
<command_interface name="velocity"/>
|
||
|
|
<state_interface name="position">
|
||
|
|
<param name="initial_value">${initial_positions['rev7']}</param>
|
||
|
|
</state_interface>
|
||
|
|
<state_interface name="velocity"/>
|
||
|
|
</joint>
|
||
|
|
<joint name="slider_left">
|
||
|
|
<command_interface name="position"/>
|
||
|
|
<command_interface name="velocity"/>
|
||
|
|
<state_interface name="position">
|
||
|
|
<param name="initial_value">${initial_positions['slider_left']}</param>
|
||
|
|
</state_interface>
|
||
|
|
<state_interface name="velocity"/>
|
||
|
|
</joint>
|
||
|
|
<joint name="slider_right">
|
||
|
|
<command_interface name="position"/>
|
||
|
|
<command_interface name="velocity"/>
|
||
|
|
<state_interface name="position">
|
||
|
|
<param name="initial_value">${initial_positions['slider_right']}</param>
|
||
|
|
</state_interface>
|
||
|
|
<state_interface name="velocity"/>
|
||
|
|
</joint>
|
||
|
|
|
||
|
|
</ros2_control>
|
||
|
|
</xacro:macro>
|
||
|
|
</robot>
|