2023-04-12 08:11:46 +00:00
|
|
|
<?xml version="1.0"?>
|
|
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
|
|
|
|
|
|
<xacro:unless value="$(arg sim_mode)">
|
|
|
|
<ros2_control name="RealRobot" type="system">
|
|
|
|
<hardware>
|
|
|
|
<plugin>diffdrive_arduino/DiffDriveArduino</plugin>
|
|
|
|
<param name="left_wheel_name">left_wheel_joint</param>
|
|
|
|
<param name="right_wheel_name">right_wheel_joint</param>
|
|
|
|
<param name="loop_rate">30</param>
|
|
|
|
<param name="device">/dev/ttyUSB0</param>
|
|
|
|
<param name="baud_rate">57600</param>
|
|
|
|
<param name="timeout">1000</param>
|
|
|
|
<param name="enc_counts_per_rev">3436</param>
|
|
|
|
</hardware>
|
|
|
|
<joint name="left_wheel_joint">
|
|
|
|
<command_interface name="velocity">
|
|
|
|
<param name="min">-10</param>
|
|
|
|
<param name="max">10</param>
|
|
|
|
</command_interface>
|
|
|
|
<state_interface name="velocity"/>
|
|
|
|
<state_interface name="position"/>
|
|
|
|
</joint>
|
|
|
|
<joint name="right_wheel_joint">
|
|
|
|
<command_interface name="velocity">
|
|
|
|
<param name="min">-10</param>
|
|
|
|
<param name="max">10</param>
|
|
|
|
</command_interface>
|
|
|
|
<state_interface name="velocity"/>
|
|
|
|
<state_interface name="position"/>
|
|
|
|
</joint>
|
|
|
|
</ros2_control>
|
|
|
|
</xacro:unless>
|
|
|
|
|
|
|
|
<xacro:if value="$(arg sim_mode)">
|
|
|
|
<ros2_control name="GazeboSystem" type="system">
|
|
|
|
<hardware>
|
|
|
|
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
|
|
|
|
</hardware>
|
|
|
|
<joint name="left_wheel_joint">
|
|
|
|
<command_interface name="velocity">
|
|
|
|
<param name="min">-10</param>
|
|
|
|
<param name="max">10</param>
|
|
|
|
</command_interface>
|
|
|
|
<state_interface name="velocity"/>
|
|
|
|
<state_interface name="position"/>
|
|
|
|
</joint>
|
|
|
|
<joint name="right_wheel_joint">
|
|
|
|
<command_interface name="velocity">
|
|
|
|
<param name="min">-10</param>
|
|
|
|
<param name="max">10</param>
|
|
|
|
</command_interface>
|
|
|
|
<state_interface name="velocity"/>
|
|
|
|
<state_interface name="position"/>
|
|
|
|
</joint>
|
|
|
|
</ros2_control>
|
|
|
|
</xacro:if>
|
|
|
|
|
|
|
|
<gazebo>
|
|
|
|
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
|
2023-07-28 10:04:02 +00:00
|
|
|
<parameters>$(find cps_rmp220_support)/config/my_controllers.yaml</parameters>
|
|
|
|
<parameters>$(find cps_rmp220_support)/config/gaz_ros2_ctl_use_sim.yaml</parameters>
|
2023-04-12 08:11:46 +00:00
|
|
|
</plugin>
|
|
|
|
</gazebo>
|
|
|
|
|
|
|
|
</robot>
|