updated robot description
This commit is contained in:
52
src/sherpa/urdf/sherpa.xacro
Executable file → Normal file
52
src/sherpa/urdf/sherpa.xacro
Executable file → Normal file
@@ -1,5 +1,11 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="sherpa">
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="sherpa">
|
||||
<gazebo>
|
||||
<plugin name="gz_ros2_control::GazeboSimROS2ControlPlugin" filename="libgz_ros2_control-system.so">
|
||||
<parameters>$(find sherpa)/config/mecanum_controller.yaml</parameters>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<link name="base_link">
|
||||
<inertial>
|
||||
<mass value="15"/>
|
||||
@@ -14,9 +20,11 @@
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:include filename="components/imu.xacro"/>
|
||||
<xacro:include filename="components/mecanum_wheel.xacro"/>
|
||||
<xacro:include filename="components/ouster_lidar.xacro"/>
|
||||
|
||||
<xacro:imu name="imu" parent="base" xyz="0 0 0.156" rpy="0 0 0" frequency="300"/>
|
||||
<xacro:ouster_lidar name="lidar" parent="base" xyz="0 0 0.15" rpy="0 0 0" model="vlp16" frequency="10" topic="/points"/>
|
||||
|
||||
<xacro:mecanum_wheel name="wheel_fr" parent="base" xyz=" 0.11 -0.11 0" rpy="0 0 0" direction="r" radius="0.04" mass="0.25"/>
|
||||
@@ -24,17 +32,33 @@
|
||||
<xacro:mecanum_wheel name="wheel_br" parent="base" xyz="-0.11 -0.11 0" rpy="0 0 0" direction="l" radius="0.04" mass="0.25"/>
|
||||
<xacro:mecanum_wheel name="wheel_bl" parent="base" xyz="-0.11 0.11 0" rpy="0 0 0" direction="r" radius="0.04" mass="0.25"/>
|
||||
|
||||
<gazebo>
|
||||
<plugin filename="gz-sim-mecanum-drive-system" name="gz::sim::systems::MecanumDrive">
|
||||
<front_left_joint>wheel_fl_joint</front_left_joint>
|
||||
<front_right_joint>wheel_fr_joint</front_right_joint>
|
||||
<back_left_joint>wheel_bl_joint</back_left_joint>
|
||||
<back_right_joint>wheel_br_joint</back_right_joint>
|
||||
<wheel_separation>0.22</wheel_separation>
|
||||
<wheelbase>0.22</wheelbase>
|
||||
<wheel_radius>0.04</wheel_radius>
|
||||
<min_acceleration>-5</min_acceleration>
|
||||
<max_acceleration>5</max_acceleration>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
<ros2_control name="SherpaSystem" type="system">
|
||||
<hardware>
|
||||
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||
</hardware>
|
||||
|
||||
<joint name="wheel_fl_joint">
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="position"/>
|
||||
</joint>
|
||||
|
||||
<joint name="wheel_fr_joint">
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="position"/>
|
||||
</joint>
|
||||
|
||||
<joint name="wheel_bl_joint">
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="position"/>
|
||||
</joint>
|
||||
|
||||
<joint name="wheel_br_joint">
|
||||
<command_interface name="velocity"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="position"/>
|
||||
</joint>
|
||||
</ros2_control>
|
||||
</robot>
|
||||
Reference in New Issue
Block a user