mirror of
https://github.com/SHC-ASTRA/rover-ros2.git
synced 2026-02-11 09:20:40 +00:00
feat: add moveit2 configuration
This commit is contained in:
@@ -0,0 +1,78 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
<xacro:macro name="ASTRA_Arm_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="Axis_0_Joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Axis_0_Joint']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="Axis_1_Joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Axis_1_Joint']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="Axis_2_Joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Axis_2_Joint']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="Axis_3_Joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Axis_3_Joint']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="Wrist_Differential_Joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Wrist_Differential_Joint']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="Wrist-EF_Roll_Joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Wrist-EF_Roll_Joint']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="Gripper_Slider_Left">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Gripper_Slider_Left']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
<joint name="Gripper _Slider_Right">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="position">
|
||||
<param name="initial_value">${initial_positions['Gripper _Slider_Right']}</param>
|
||||
</state_interface>
|
||||
<state_interface name="velocity"/>
|
||||
</joint>
|
||||
|
||||
</ros2_control>
|
||||
</xacro:macro>
|
||||
</robot>
|
||||
Reference in New Issue
Block a user