updated robot description
This commit is contained in:
34
src/sherpa/urdf/components/imu.xacro
Normal file
34
src/sherpa/urdf/components/imu.xacro
Normal file
@@ -0,0 +1,34 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||||
|
|
||||||
|
<xacro:macro name="imu" params="name parent xyz rpy frequency">
|
||||||
|
|
||||||
|
<link name="${name}_link">
|
||||||
|
<inertial>
|
||||||
|
<mass value="0.01"/>
|
||||||
|
<inertia
|
||||||
|
ixx="0.001828"
|
||||||
|
ixy="0.0"
|
||||||
|
ixz="0.0"
|
||||||
|
iyy="0.001828"
|
||||||
|
iyz="0.0"
|
||||||
|
izz="0.003528"
|
||||||
|
/>
|
||||||
|
</inertial>
|
||||||
|
</link>
|
||||||
|
<joint name="${name}_joint" type="fixed">
|
||||||
|
<parent link="${parent}_link"/>
|
||||||
|
<child link="${name}_link"/>
|
||||||
|
<origin xyz="${xyz}" rpy="${rpy}"/>
|
||||||
|
</joint>
|
||||||
|
<gazebo reference="${name}_link">
|
||||||
|
<sensor name="${name}" type="imu">
|
||||||
|
<always_on>1</always_on>
|
||||||
|
<update_rate>${frequency}</update_rate>
|
||||||
|
<gz_frame_id>${name}_link</gz_frame_id>
|
||||||
|
<visualize>true</visualize>
|
||||||
|
<topic>/imu</topic>
|
||||||
|
</sensor>
|
||||||
|
</gazebo>
|
||||||
|
</xacro:macro>
|
||||||
|
</robot>
|
||||||
@@ -13,11 +13,11 @@
|
|||||||
|
|
||||||
<!-- get left or right wheel -->
|
<!-- get left or right wheel -->
|
||||||
<xacro:if value="${direction == 'l'}">
|
<xacro:if value="${direction == 'l'}">
|
||||||
<xacro:property name="mesh" value="https://fuel.gazebosim.org/1.0/OpenRobotics/models/Mecanum lift/tip/files/meshes/mecanum_wheel_left.STL"/>
|
<xacro:property name="mesh" value="package://sherpa/urdf/meshes//mecanum_wheel_left.STL"/>
|
||||||
<xacro:property name="friction_dir" value="-1"/>
|
<xacro:property name="friction_dir" value="-1"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
<xacro:if value="${direction == 'r'}">
|
<xacro:if value="${direction == 'r'}">
|
||||||
<xacro:property name="mesh" value="https://fuel.gazebosim.org/1.0/OpenRobotics/models/Mecanum lift/tip/files/meshes/mecanum_wheel_right.STL"/>
|
<xacro:property name="mesh" value="package://sherpa/urdf/meshes//mecanum_wheel_right.STL"/>
|
||||||
<xacro:property name="friction_dir" value="1"/>
|
<xacro:property name="friction_dir" value="1"/>
|
||||||
</xacro:if>
|
</xacro:if>
|
||||||
|
|
||||||
@@ -46,18 +46,18 @@
|
|||||||
<material name="mecanum_wheel_material"/>
|
<material name="mecanum_wheel_material"/>
|
||||||
</visual>
|
</visual>
|
||||||
<collision name='collision'>
|
<collision name='collision'>
|
||||||
<geometry>
|
<geometry>
|
||||||
<sphere radius="${radius}"/>
|
<sphere radius="${radius}"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<surface>
|
<surface>
|
||||||
<friction>
|
<friction>
|
||||||
<ode>
|
<ode>
|
||||||
<mu>1.2</mu>
|
<mu>1.2</mu>
|
||||||
<mu2>0</mu2>
|
<mu2>0</mu2>
|
||||||
<fdir1 gz:expressed_in="${parent}">1 ${friction_dir} 0</fdir1>
|
<fdir1 gz:expressed_in="${parent}_link">1 ${friction_dir} 0</fdir1>
|
||||||
</ode>
|
</ode>
|
||||||
</friction>
|
</friction>
|
||||||
</surface>
|
</surface>
|
||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
<joint name='${name}_joint' type='continuous'>
|
<joint name='${name}_joint' type='continuous'>
|
||||||
|
|||||||
@@ -140,11 +140,6 @@
|
|||||||
</joint>
|
</joint>
|
||||||
<gazebo reference="${name}_link">
|
<gazebo reference="${name}_link">
|
||||||
<sensor name="${name}" type="gpu_lidar">
|
<sensor name="${name}" type="gpu_lidar">
|
||||||
<plugin
|
|
||||||
filename="gz-sim-sensors-system"
|
|
||||||
name="gz::sim::systems::Sensors">
|
|
||||||
<render_engine>ogre2</render_engine>
|
|
||||||
</plugin>
|
|
||||||
<update_rate>${frequency}</update_rate>
|
<update_rate>${frequency}</update_rate>
|
||||||
<topic>/velodyne_points</topic>
|
<topic>/velodyne_points</topic>
|
||||||
<gz_frame_id>${name}_link</gz_frame_id>
|
<gz_frame_id>${name}_link</gz_frame_id>
|
||||||
|
|||||||
BIN
src/sherpa/urdf/meshes/mecanum_wheel_left.STL
Normal file
BIN
src/sherpa/urdf/meshes/mecanum_wheel_left.STL
Normal file
Binary file not shown.
BIN
src/sherpa/urdf/meshes/mecanum_wheel_right.STL
Normal file
BIN
src/sherpa/urdf/meshes/mecanum_wheel_right.STL
Normal file
Binary file not shown.
50
src/sherpa/urdf/sherpa.xacro
Executable file → Normal file
50
src/sherpa/urdf/sherpa.xacro
Executable file → Normal file
@@ -1,5 +1,11 @@
|
|||||||
<?xml version="1.0"?>
|
<?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">
|
<link name="base_link">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="15"/>
|
<mass value="15"/>
|
||||||
@@ -14,9 +20,11 @@
|
|||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
|
<xacro:include filename="components/imu.xacro"/>
|
||||||
<xacro:include filename="components/mecanum_wheel.xacro"/>
|
<xacro:include filename="components/mecanum_wheel.xacro"/>
|
||||||
<xacro:include filename="components/ouster_lidar.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: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"/>
|
<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_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"/>
|
<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>
|
<ros2_control name="SherpaSystem" type="system">
|
||||||
<plugin filename="gz-sim-mecanum-drive-system" name="gz::sim::systems::MecanumDrive">
|
<hardware>
|
||||||
<front_left_joint>wheel_fl_joint</front_left_joint>
|
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
|
||||||
<front_right_joint>wheel_fr_joint</front_right_joint>
|
</hardware>
|
||||||
<back_left_joint>wheel_bl_joint</back_left_joint>
|
|
||||||
<back_right_joint>wheel_br_joint</back_right_joint>
|
<joint name="wheel_fl_joint">
|
||||||
<wheel_separation>0.22</wheel_separation>
|
<command_interface name="velocity"/>
|
||||||
<wheelbase>0.22</wheelbase>
|
<state_interface name="velocity"/>
|
||||||
<wheel_radius>0.04</wheel_radius>
|
<state_interface name="position"/>
|
||||||
<min_acceleration>-5</min_acceleration>
|
</joint>
|
||||||
<max_acceleration>5</max_acceleration>
|
|
||||||
</plugin>
|
<joint name="wheel_fr_joint">
|
||||||
</gazebo>
|
<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>
|
</robot>
|
||||||
Reference in New Issue
Block a user