Migrate to Gazebo Fortress

This commit is contained in:
Ilya Uraev 2023-02-03 07:04:12 +00:00 committed by Igor Brylyov
parent b34c00a9b9
commit e46c7bef74
113 changed files with 2751 additions and 25450 deletions

View file

@ -4,74 +4,60 @@
<!-- arg for control mode -->
<ros2_control name="rasmt_single_hi" type="system">
<xacro:if value="${sim}">
<!-- <xacro:if value="${sim == 'gazebo'}">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
</xacro:if> -->
<xacro:if value="${sim == 'ignition'}">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware>
</xacro:if>
<xacro:unless value="${sim}">
<xacro:if value="${sim == 'fake'}">
<hardware>
<plugin>fake_components/GenericSystem</plugin>
</hardware>
</xacro:unless>
</xacro:if>
<joint name="${prefix}_Rot_Z_1">
<command_interface name="position">
<!-- better to use radians as min max first -->
<param name="min">-1</param>
<param name="max"> 1</param>
</command_interface>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}_Rot_Y_1">
<command_interface name="position">
<param name="min">-1</param>
<param name="max"> 1</param>
</command_interface>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}_Rot_Z_2">
<command_interface name="position">
<param name="min">-1</param>
<param name="max"> 1</param>
</command_interface>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}_Rot_Y_2">
<command_interface name="position">
<param name="min">-1</param>
<param name="max"> 1</param>
</command_interface>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}_Rot_Z_3">
<command_interface name="position">
<param name="min">-1</param>
<param name="max"> 1</param>
</command_interface>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="${prefix}_Rot_Y_4">
<command_interface name="position">
<param name="min">-1</param>
<param name="max"> 1</param>
</command_interface>
<command_interface name="effort"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>

View file

@ -1,63 +1,26 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="rasmt_single_gazebo" params="prefix">
<xacro:macro name="rasmt_single_gazebo" params="prefix sim">
<!-- ros_control-plugin -->
<gazebo>
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
<!--robot_sim_type>gazebo_ros2_control/GazeboSystem</robot_sim_type-->
<parameters>$(find rasmt_support)/config/rasmt_ros2_controllers.yaml</parameters>
<robotNamespace>/${prefix}</robotNamespace>
</plugin>
</gazebo>
<!-- <xacro:if value="${sim == 'gazebo'}">
<gazebo>
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
<parameters>$(find rasmt_support)/config/rasmt_position_velocity_controllers.yaml</parameters>
<robotNamespace>/${prefix}</robotNamespace>
</plugin>
</gazebo>
</xacro:if> -->
<!-- link 0 -->
<gazebo reference="${prefix}_Base_Link">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<xacro:if value="${sim == 'ignition'}">
<gazebo reference="world"/>
<gazebo>
<plugin filename="ign_ros2_control-system" name="ign_ros2_control::IgnitionROS2ControlPlugin">
<parameters>$(find rasmt_support)/config/rasmt_effort_controllers.yaml</parameters>
<!--controller_manager_node_name>controller_manager</controller_manager_node_name-->
</plugin>
</gazebo>
</xacro:if>
<!-- link 1 -->
<gazebo reference="${prefix}_Fork_1">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<!-- link 2 -->
<gazebo reference="${prefix}_Link_1">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<!-- link 3 -->
<gazebo reference="${prefix}_Fork_2">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<!-- link 4 -->
<gazebo reference="${prefix}_Link_2">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<!-- link 5 -->
<gazebo reference="${prefix}_Fork_3">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<turnGravityOff>true</turnGravityOff>
</gazebo>
<!-- link 6 -->
<gazebo reference="${prefix}_Dock_Link">
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<turnGravityOff>true</turnGravityOff>
</gazebo>
</xacro:macro>
</robot>

View file

@ -398,7 +398,7 @@
effort="5.149"
velocity="0.99903" />
</joint>
<xacro:rasmt_single_gazebo prefix="${prefix}"/>
<xacro:rasmt_single_gazebo prefix="${prefix}" sim="${sim}"/>
<xacro:rasmt_single_control prefix="${prefix}" sim="${sim}"/>
<link name="${prefix}_tool0"/>