环境:ubuntu18
创建gazebo仿真的功能包。
catkin_create_pkg mybot_gazebo gazebo_plugins gazebo_ros gazebo_ros_control roscpp rospy
src/
├── CMakeLists.txt -> /opt/ros/melodic/share/catkin/cmake/toplevel.cmake
├── mybot_description
│ ├── CMakeLists.txt
│ ├── config
│ │ ├── fake_mybot_arbotix.yaml
│ │ └── mybot_urdf.rviz
│ ├── launch
│ │ ├── arbotix
│ │ │ └── arbotix_mybot_with_laser.launch
│ │ └── xacro
│ │ ├── display_mybot_base_xacro.launch
│ │ └── display_mybot_with_laser.launch
│ ├── package.xml
│ └── urdf
│ ├── gazebo
│ │ ├── mybot_base.xacro
│ │ ├── mybot_with_laser.xacro
│ │ ├── mybot.xacro
│ │ └── sensors
│ │ └── laser_gazebo.xacro
│ ├── urdf
│ │ ├── mybot_base.urdf
│ │ └── mybot_with_laser.urdf
│ └── xacro
│ ├── laser.xacro
│ ├── mybot_base.xacro
│ ├── mybot_with_laser.xacro
│ └── mybot.xacro
└── mybot_gazebo
├── CMakeLists.txt
├── launch
│ ├── view_mybot_gazebo_empty_world.launch
│ └── view_mybot_with_laser_gazebo.launch
├── package.xml
└── worlds
└── playground.world
1 为link添加惯性参数和碰撞属性
inertial
:惯性参数
collision
:碰撞属性
visual
:可视化属性
碰撞属性一般和可视化属性一样的。除非模型很复杂,碰撞属性会简化成规则形状。
以下以轮子为例:
<xacro:macro name="cylinder_inertial_matrix" params="m r h">
<inertial>
<mass value="${m}" />
<inertia ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"
iyy="${m*(3*r*r+h*h)/12}" iyz = "0"
izz="${m*r*r/2}" />
</inertial>
</xacro:macro>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0 " />
<geometry>
<cylinder radius="${wheel_radius}" length = "${wheel_length}"/>
</geometry>
</collision>
<cylinder_inertial_matrix m="${wheel_mass}" r="${wheel_radius}" h="${wheel_length}" />
2 为link添加gazebo标签
这些标签主要与颜色有关
<gazebo reference="${prefix}_wheel_link">
<material>Gazebo/Black</material>
</gazebo>
base_footprint:
<gazebo reference="base_footprint">
<turnGravityOff>false</turnGravityOff>
</gazebo>
3 为joint添加传动装置
连接两个joint,让其做相对运动。
<!-- Transmission is important to link the joints and the controller -->
<transmission name="{prefix}_wheel_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_wheel_joint" />
<actuator name="${prefix}_motor_joint">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
4 添加gazebo控制器插件
<!-- controller -->
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<rosDebugLevel>Debug</rosDebugLevel>
<publishWheelTF>true</publishWheelTF>
<robotNamespace>/</robotNamespace>
<publishTf>1</publishTf>
<publishWheelJointState>true</publishWheelJointState>
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<legacyMode>true</legacyMode>
<leftJoint>left_wheel_joint</leftJoint>
<rightJoint>right_wheel_joint</rightJoint>
<wheelSeparation>${base_link_radius*2}</wheelSeparation>
<wheelDiameter>${2*wheel_radius}</wheelDiameter>
<broadcastTF>1</broadcastTF>
<wheelTorque>30</wheelTorque>
<wheelAcceleration>1.8</wheelAcceleration>
<commandTopic>cmd_vel</commandTopic>
<odometryFrame>odom</odometryFrame>
<odometryTopic>odom</odometryTopic>
<robotBaseFrame>base_footprint</robotBaseFrame>
</plugin>
</gazebo>
5 完整的模型文件
mybot.xacro
<?xml version="1.0"?>
<robot name="mybot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find mybot_description)/urdf/gazebo/mybot_base.xacro" />
<mybot_base/>
</robot>
mybot_base.xacro
<?xml version="1.0"?>
<robot name="mybot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- PROPERTY -->
<xacro:property name="M_PI" value="3.14159"/>
<xacro:property name="base_link_radius" value="0.13"/>
<xacro:property name="base_link_length" value="0.005"/>
<xacro:property name="base_mass" value="0.5" />
<xacro:property name="wheel_radius" value="0.033"/>
<xacro:property name="wheel_length" value="0.017"/>
<xacro:property name="wheel_mass" value="0.1" />
<xacro:property name="caster_radius" value="0.016" />
<xacro:property name="caster_joint_origin_x" value="-0.12" />
<xacro:property name="caster_mass" value="0.01" />
<xacro:property name="motor_radius" value="0.02"/>
<xacro:property name="motor_length" value="0.08"/>
<xacro:property name="motor_x" value="-0.055"/>
<xacro:property name="motor_y" value="0.075"/>
<xacro:property name="motor_mass" value="0.2" />
<xacro:property name="plate_height" value="0.07"/>
<xacro:property name="standoff_x" value="0.12"/>
<xacro:property name="standoff_y" value="0.10"/>
<xacro:property name="plate_mass" value="0.1"/>
<!-- COLORS -->
<material name="yellow">
<color rgba="1 0.4 0 1"/>
</material>
<material name="black">
<color rgba="0 0 0 0.95"/>
</material>
<material name="gray">
<color rgba="0.75 0.75 0.75 1"/>
</material>
<material name="white">
<color rgba="1 1 1 0.9"/>
</material>
<!-- Macro for inertia matrix -->
<xacro:macro name="sphere_inertial_matrix" params="m r">
<inertial>
<mass value="${m}" />
<inertia ixx="${2*m*r*r/5}" ixy="0" ixz="0"
iyy="${2*m*r*r/5}" iyz="0"
izz="${2*m*r*r/5}" />
</inertial>
</xacro:macro>
<xacro:macro name="cylinder_inertial_matrix" params="m r h">
<inertial>
<mass value="${m}" />
<inertia ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"
iyy="${m*(3*r*r+h*h)/12}" iyz = "0"
izz="${m*r*r/2}" />
</inertial>
</xacro:macro>
<xacro:macro name="box_inertial_matrix" params="m w h d">
<inertial>
<mass value="${m}" />
<inertia ixx="${m*(h*h+d*d)/12}" ixy = "0" ixz = "0"
iyy="${m*(w*w+d*d)/12}" iyz = "0"
izz="${m*(w*w+h*h)/12}" />
</inertial>
</xacro:macro>
<!-- MOTOR -->
<xacro:macro name="motor" params="prefix reflect">
<link name="${prefix}_motor_link">
<visual>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder radius="${motor_radius}" length = "${motor_length}"/>
</geometry>
<material name="gray" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0 " />
<geometry>
<cylinder radius="${motor_radius}" length = "${motor_length}"/>
</geometry>
</collision>
<cylinder_inertial_matrix m="${motor_mass}" r="${motor_radius}" h="${motor_length}" />
</link>
<gazebo reference="${prefix}_wheel_link">
<material>Gazebo/Black</material>
</gazebo>
<joint name="${prefix}_motor_joint" type="fixed">
<origin xyz="${motor_x} ${reflect*motor_y} 0" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="${prefix}_motor_link"/>
<axis xyz="0 1 0"/>
</joint>
</xacro:macro>
<!-- WHEEL -->
<xacro:macro name="wheel" params="prefix reflect">
<link name="${prefix}_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder radius="${wheel_radius}" length = "${wheel_length}"/>
</geometry>
<material name="while" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0 " />
<geometry>
<cylinder radius="${wheel_radius}" length = "${wheel_length}"/>
</geometry>
</collision>
<cylinder_inertial_matrix m="${wheel_mass}" r="${wheel_radius}" h="${wheel_length}" />
</link>
<gazebo reference="${prefix}_wheel_link">
<material>Gazebo/Black</material>
</gazebo>
<joint name="${prefix}_wheel_joint" type="continuous">
<origin xyz="0 ${reflect*(motor_length+wheel_length)/2} 0" rpy="0 0 0"/>
<parent link="${prefix}_motor_link"/>
<child link="${prefix}_wheel_link"/>
<axis xyz="0 1 0"/>
</joint>
<!-- Transmission is important to link the joints and the controller -->
<transmission name="{prefix}_wheel_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_wheel_joint" />
<actuator name="${prefix}_motor_joint">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
<!-- CASTER -->
<xacro:macro name="caster" params="prefix reflect">
<link name="${prefix}_caster_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<sphere radius="${caster_radius}"/>
</geometry>
<material name="black" />
</visual>
<collision>
<geometry>
<sphere radius="${caster_radius}" />
</geometry>
<origin xyz="0 0 0 " rpy="0 0 0" />
</collision>
<sphere_inertial_matrix m="${caster_mass}" r="${caster_radius}" />
</link>
<gazebo reference="${prefix}_caster_link">
<material>Gazebo/Black</material>
</gazebo>
<joint name="${prefix}_caster_joint" type="fixed">
<origin xyz="${reflect*caster_joint_origin_x} 0 -${caster_radius}" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="${prefix}_caster_link"/>
<axis xyz="0 1 0"/>
</joint>
</xacro:macro>
<!-- PLATE -->
<xacro:macro name="plate" params="prefix">
<link name="plate_${prefix}_link">
<visual>
<origin xyz=" 0 0 0 " rpy="0 0 0" />
<geometry>
<cylinder length="${base_link_length}" radius="${base_link_radius}"/>
</geometry>
<material name="yellow"/>
</visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
<geometry>
<cylinder length="${base_link_length}" radius="${base_link_radius}"/>
</geometry>
</collision>
<cylinder_inertial_matrix m="${plate_mass}" r="${base_link_radius}" h="${base_link_length}" />
</link>
<gazebo reference="plate_${prefix}_link">
<material>Gazebo/Blue</material>
</gazebo>
<joint name="plate_${prefix}_joint" type="fixed">
<origin xyz="0 0 ${prefix*plate_height}" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="plate_${prefix}_link"/>
<axis xyz="0 1 0"/>
</joint>
</xacro:macro>
<!-- mrobot_standoff_2in -->
<xacro:macro name="mrobot_standoff_2in" params="parent number x_loc y_loc z_loc">
<joint name="standoff_2in_${number}_joint" type="fixed">
<origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
<parent link="${parent}"/>
<child link="standoff_2in_${number}_link" />
</joint>
<link name="standoff_2in_${number}_link">
<visual>
<origin xyz=" 0 0 0 " rpy="0 0 0" />
<geometry>
<box size="0.01 0.01 0.07" />
</geometry>
<material name="black">
<color rgba="0.16 0.17 0.15 0.9"/>
</material>
</visual>
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" />
<inertia ixx="0.0001" ixy="0.0" ixz="0.0"
iyy="0.0001" iyz="0.0"
izz="0.0001" />
</inertial>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
<geometry>
<box size="0.01 0.01 0.07" />
</geometry>
</collision>
</link>
</xacro:macro>
<!-- BASE -->
<xacro:macro name="mybot_base">
<link name="base_footprint">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
</link>
<gazebo reference="base_footprint">
<turnGravityOff>false</turnGravityOff>
</gazebo>
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 ${wheel_radius}" rpy="0 0 0" />
<parent link="base_footprint"/>
<child link="base_link" />
</joint>
<link name="base_link">
<visual>
<origin xyz=" 0 0 0" rpy="0 0 0" />
<geometry>
<cylinder length="${base_link_length}" radius="${base_link_radius}"/>
</geometry>
<material name="yellow" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<cylinder length="${base_link_length}" radius="${base_link_radius}"/>
</geometry>
</collision>
<cylinder_inertial_matrix m="${base_mass}" r="${base_link_radius}" h="${base_link_length}" />
</link>
<gazebo reference="base_link">
<material>Gazebo/Blue</material>
</gazebo>
<motor prefix="left" reflect="-1"/>
<motor prefix="right" reflect="1"/>
<wheel prefix="left" reflect="-1"/>
<wheel prefix="right" reflect="1"/>
<caster prefix="back" reflect="-1"/>
<mrobot_standoff_2in parent="base_link" number="1" x_loc="-${standoff_x/2 + 0.03}" y_loc="-${standoff_y - 0.03}" z_loc="${plate_height/2}"/>
<mrobot_standoff_2in parent="base_link" number="2" x_loc="-${standoff_x/2 + 0.03}" y_loc="${standoff_y - 0.03}" z_loc="${plate_height/2}"/>
<mrobot_standoff_2in parent="base_link" number="3" x_loc="${standoff_x/2}" y_loc="-${standoff_y}" z_loc="${plate_height/2}"/>
<mrobot_standoff_2in parent="base_link" number="4" x_loc="${standoff_x/2}" y_loc="${standoff_y}" z_loc="${plate_height/2}"/>
<plate prefix="1"/>
<mrobot_standoff_2in parent="standoff_2in_1_link" number="5" x_loc="0" y_loc="0" z_loc="${plate_height}"/>
<mrobot_standoff_2in parent="standoff_2in_2_link" number="6" x_loc="0" y_loc="0" z_loc="${plate_height}"/>
<mrobot_standoff_2in parent="standoff_2in_3_link" number="7" x_loc="0" y_loc="0" z_loc="${plate_height}"/>
<mrobot_standoff_2in parent="standoff_2in_4_link" number="8" x_loc="0" y_loc="0" z_loc="${plate_height}"/>
<plate prefix="2"/>
<!-- controller -->
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<rosDebugLevel>Debug</rosDebugLevel>
<publishWheelTF>true</publishWheelTF>
<robotNamespace>/</robotNamespace>
<publishTf>1</publishTf>
<publishWheelJointState>true</publishWheelJointState>
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<legacyMode>true</legacyMode>
<leftJoint>left_wheel_joint</leftJoint>
<rightJoint>right_wheel_joint</rightJoint>
<wheelSeparation>${base_link_radius*2}</wheelSeparation>
<wheelDiameter>${2*wheel_radius}</wheelDiameter>
<broadcastTF>1</broadcastTF>
<wheelTorque>30</wheelTorque>
<wheelAcceleration>1.8</wheelAcceleration>
<commandTopic>cmd_vel</commandTopic>
<odometryFrame>odom</odometryFrame>
<odometryTopic>odom</odometryTopic>
<robotBaseFrame>base_footprint</robotBaseFrame>
</plugin>
</gazebo>
</xacro:macro>
</robot>
6 在gazebo中加载机器人模型
view_mybot_gazebo_empty_world.launch
<launch>
<!-- 设置launch文件的参数 -->
<!--arg name="world_name" value="$(find mybot_gazebo)/worlds/playground.world"/-->
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<!-- 运行gazebo仿真环境 -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<!--arg name="world_name" value="$(arg world_name)" /-->
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>
<!-- 加载机器人模型描述参数 -->
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find mybot_description)/urdf/gazebo/mybot.xacro'" />
<!-- 运行joint_state_publisher节点,发布机器人的关节状态 -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node>
<!-- 运行robot_state_publisher节点,发布tf -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" >
<param name="publish_frequency" type="double" value="50.0" />
</node>
<!-- 在gazebo中加载机器人模型-->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model mybot -param robot_description"/>
</launch>
7 添加传感器
mybot_with_laser.xacro
<?xml version="1.0"?>
<robot name="mybot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find mybot_description)/urdf/gazebo/mybot_base.xacro" />
<xacro:include filename="$(find mybot_description)/urdf/gazebo/sensors/laser_gazebo.xacro" />
<xacro:property name="rplidar_offset_x" value="0" />
<xacro:property name="rplidar_offset_y" value="0" />
<xacro:property name="rplidar_offset_z" value="0.028" />
<mybot_base/>
<!-- laser -->
<joint name="laser_joint" type="fixed">
<origin xyz="${rplidar_offset_x} ${rplidar_offset_y} ${rplidar_offset_z}" rpy="0 0 0" />
<parent link="plate_2_link"/>
<child link="laser_link"/>
</joint>
<xacro:laser prefix="laser"/>
</robot>
laser_gazebo.xacro
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="laser">
<xacro:macro name="laser" params="prefix:=laser">
<link name="${prefix}_link">
<inertial>
<mass value="0.1" />
<origin xyz="0 0 0" />
<inertia ixx="0.01" ixy="0.0" ixz="0.0"
iyy="0.01" iyz="0.0"
izz="0.01" />
</inertial>
<visual>
<origin xyz=" 0 0 0 " rpy="0 0 0" />
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
<geometry>
<cylinder length="0.06" radius="0.05"/>
</geometry>
</collision>
</link>
<gazebo reference="${prefix}_link">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="${prefix}_link">
<sensor type="ray" name="rplidar">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>5.5</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>-3</min_angle>
<max_angle>3</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>6.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_rplidar" filename="libgazebo_ros_laser.so">
<topicName>/scan</topicName>
<frameName>laser_link</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>
view_mybot_with_laser_gazebo.launch
<launch>
<!-- 设置launch文件的参数 -->
<arg name="world_name" value="$(find mybot_gazebo)/worlds/playground.world"/>
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<!-- 运行gazebo仿真环境 -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world_name)" />
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>
<!-- 加载机器人模型描述参数 -->
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find mybot_description)/urdf/gazebo/mybot_with_laser.xacro'" />
<!-- 运行joint_state_publisher节点,发布机器人的关节状态 -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node>
<!-- 运行robot_state_publisher节点,发布tf -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" >
<param name="publish_frequency" type="double" value="50.0" />
</node>
<!-- 在gazebo中加载机器人模型-->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model mybot -param robot_description"/>
</launch>