在前面属性声明处 增加了各link的质量(mass)属性声明 为计算惯性参数
<xacro:property name="M_PI" value="3.1415926"/>
<xacro:property name="base_mass" value="20" />
<xacro:property name="base_radius" value="0.20"/>
<xacro:property name="base_length" value="0.16"/>
<xacro:property name="wheel_mass" value="2" />
<xacro:property name="wheel_radius" value="0.06"/>
<xacro:property name="wheel_length" value="0.025"/>
<xacro:property name="wheel_joint_y" value="0.19"/>
<xacro:property name="wheel_joint_z" value="0.05"/>
<xacro:property name="caster_mass" value="0.5" />
<xacro:property name="caster_radius" value="0.015"/>
<xacro:property name="caster_joint_x" value="0.18"/>
颜色属性声明
这里得颜色在gazebo中是识别不出来得
rivz得颜色显示不一样
<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>
宏定义 球体惯性矩阵计算宏定义
宏定义 圆柱体惯性矩阵计算宏定义
此部分惯性矩阵的计算规则刚体是有统一的计算公式,
不规则的刚体可以通过solid work等三维软件得到
<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}" />
inertial>
xacro:macro>
下面是主要添加部分 在各模块里添加
1、增加惯性属性和碰撞属性
<xacro:macro name="wheel" params="prefix reflect">
<joint name="${prefix}_wheel_joint" type="continuous">
<origin xyz="0 ${reflect*wheel_joint_y} ${-wheel_joint_z}" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="${prefix}_wheel_link"/>
<axis xyz="0 1 0"/>
joint>
<link name="${prefix}_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
geometry>
<material name="gray" />
visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
geometry>
collision>
<cylinder_inertial_matrix m="${wheel_mass}" r="${wheel_radius}" h="${wheel_length}" />
link>
2、添加gazebo标签
为各link配颜色 ,gazebo与rivz颜色设置不兼容
<gazebo reference="${prefix}_wheel_link">
<material>Gazebo/Graymaterial>
gazebo>
3、为joint添加传动装置
用得 transmission 标签
小车轮子用速度控制接口
除此之外还有位置控制接口和力控制接口
<transmission name="${prefix}_wheel_joint_trans">
<type>transmission_interface/SimpleTransmissiontype>
<joint name="${prefix}_wheel_joint" >
<hardwareInterface>hardware_interface/VelocityJointInterfacehardwareInterface>
joint>
<actuator name="${prefix}_wheel_joint_motor">
<hardwareInterface>hardware_interface/VelocityJointInterfacehardwareInterface>
<mechanicalReduction>1mechanicalReduction>
actuator>
transmission>
xacro:macro>
同理为前后支撑轮加入内容
1、增加惯性属性和碰撞属性
<xacro:macro name="caster" params="prefix reflect">
<joint name="${prefix}_caster_joint" type="continuous">
<origin xyz="${reflect*caster_joint_x} 0 ${-(base_length/2 + caster_radius)}" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="${prefix}_caster_link"/>
<axis xyz="0 1 0"/>
joint>
<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>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="${caster_radius}" />
geometry>
collision>
<sphere_inertial_matrix m="${caster_mass}" r="${caster_radius}" />
link>
2、添加gazebo标签
为各link配颜色
<gazebo reference="${prefix}_caster_link">
<material>Gazebo/Blackmaterial>
gazebo>
xacro:macro>
3、由于不用驱动支撑轮
所以 不用 为joint添加传动装置
为base_link添加内容
给 base_footprint 添加标签
<xacro:macro name="mbot_base_gazebo">
<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>falseturnGravityOff>
gazebo>
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 ${base_length/2 + caster_radius*2}" rpy="0 0 0" />
<parent link="base_footprint"/>
<child link="base_link" />
joint>
为base_link添加碰撞属性和惯性属性
<link name="base_link">
<visual>
<origin xyz=" 0 0 0" rpy="0 0 0" />
<geometry>
<cylinder length="${base_length}" radius="${base_radius}"/>
geometry>
<material name="yellow" />
visual>
<collision>
<origin xyz=" 0 0 0" rpy="0 0 0" />
<geometry>
<cylinder length="${base_length}" radius="${base_radius}"/>
geometry>
collision>
<cylinder_inertial_matrix m="${base_mass}" r="${base_radius}" h="${base_length}" />
link>
为base_link添加gazebo标签
<gazebo reference="base_link">
<material>Gazebo/Bluematerial>
gazebo>
小车需要差速控制器,gazebo里得差速控制器得插件是现成得
libgazebo_ros_diff_drive.so
插件需要如下参数
<gazebo>
<plugin name="differential_drive_controller"
filename="libgazebo_ros_diff_drive.so">
<rosDebugLevel>DebugrosDebugLevel>
<publishWheelTF>truepublishWheelTF>
<robotNamespace>/robotNamespace>
<publishTf>1publishTf>
<publishWheelJointState>truepublishWheelJointState>
<alwaysOn>truealwaysOn>
<updateRate>100.0updateRate>
<legacyMode>truelegacyMode>
<leftJoint>left_wheel_jointleftJoint>
<rightJoint>right_wheel_jointrightJoint>
<wheelSeparation>${wheel_joint_y*2}wheelSeparation>
<wheelDiameter>${2*wheel_radius}wheelDiameter>
<broadcastTF>1broadcastTF>
<wheelTorque>30wheelTorque>
<wheelAcceleration>1.8wheelAcceleration>
<commandTopic>cmd_velcommandTopic>
<odometryFrame>odomodometryFrame>
<odometryTopic>odomodometryTopic>
<robotBaseFrame>base_footprintrobotBaseFrame>
plugin>
gazebo>
<launch>
<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"/>
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<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 mbot_description)/urdf/xacro/gazebo/mbot_gazebo.xacro'" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" >node>
<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>
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model mrobot -param robot_description"/>
launch>
运行launch得到gazebo中的机器人仿真模型
可以选择insert
先坐标系中加入已有的模型
也可以通过edit的下拉菜单中的building editor创建一个环境
创建完成后在file下拉菜单中选择save world as 将环境以.world文件形式保存。
在launch文件中
设置launch文件的参数处加如.world文件的路径即可
<arg name="world_name" value="$(find mbot_gazebo)/worlds/playground.world"/>
<arg name="world_name" value="$(find mbot_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"/>
新建一个xacro文件,方便机器人更换传感器
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="camera">
宏定义摄像头
<xacro:macro name="usb_camera" params="prefix:=camera">
为摄像头link添加碰撞属性和惯性属性
<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>
<box size="0.01 0.04 0.04" />
geometry>
<material name="black"/>
visual>
<collision>
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
<geometry>
<box size="0.01 0.04 0.04" />
geometry>
collision>
link>
<gazebo reference="${prefix}_link">
<material>Gazebo/Blackmaterial>
gazebo>
用gazebo标签去描述,因为用某个link去代表摄像头插件,所以要用reference去指定是哪个link,$ {prefix}_link这个一定要与上面的 < link name="${prefix}_link">一致
<gazebo reference="${prefix}_link">
在里面用< sensor >标签来描述传感器信息 type指定传感器类型name自己去定义
<sensor type="camera" name="camera_node">
sensor里面就是传感器参数的设置
具体参数含义在注释中
<gazebo reference="${prefix}_link">
<sensor type="camera" name="camera_node">
<update_rate>30.0update_rate>
<camera name="head">
<horizontal_fov>1.3962634horizontal_fov>
<image>
<width>1280width>
<height>720height>
<format>R8G8B8format>
image>
<clip>
<near>0.02near>
<far>300far>
clip>
<noise>
<type>gaussiantype>
<mean>0.0mean>
<stddev>0.007stddev>
noise>
camera>
<plugin name="gazebo_camera" filename="libgazebo_ros_camera.so">
<alwaysOn>truealwaysOn>
<updateRate>0.0updateRate>
<cameraName>/cameracameraName>
<imageTopicName>image_rawimageTopicName>
<cameraInfoTopicName>camera_infocameraInfoTopicName>
<frameName>camera_linkframeName>
<hackBaseline>0.07hackBaseline>
<distortionK1>0.0distortionK1>
<distortionK2>0.0distortionK2>
<distortionK3>0.0distortionK3>
<distortionT1>0.0distortionT1>
<distortionT2>0.0distortionT2>
plugin>
sensor>
gazebo>
<robot name="arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find mbot_description)/urdf/xacro/gazebo/mbot_base_gazebo.xacro" />
<xacro:include filename="$(find mbot_description)/urdf/xacro/sensors/camera_gazebo.xacro" />
<xacro:property name="camera_offset_x" value="0.17" />
<xacro:property name="camera_offset_y" value="0" />
<xacro:property name="camera_offset_z" value="0.10" />
<joint name="camera_joint" type="fixed">
<origin xyz="${camera_offset_x} ${camera_offset_y} ${camera_offset_z}" rpy="0 0 0" />
<parent link="base_link"/>
<child link="camera_link"/>
joint>
<xacro:usb_camera prefix="camera"/>
<mbot_base_gazebo/>
robot>
其它的都不动,只是改变机器人模型文件和仿真环境文件路径即可
<launch>
<arg name="world_name" value="$(find mbot_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"/>
<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 mbot_description)/urdf/xacro/gazebo/mbot_with_camera_gazebo.xacro'" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" >node>
<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>
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model mrobot -param robot_description"/>
launch>
$roslaunch mbot_gazebo view_mbot_with_camera_gazebo.launch
$ rqt_image_view
$ roslaunch mbot_teleop mbot_teleop.launch
新建一个xacro文件,方便机器人更换传感器
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="laser">
对激光雷达进行宏定义 方便在其它文件中调用
<xacro:macro name="rplidar" params="prefix:=laser">
为激光雷达link添加碰撞属性和惯性属性
<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/Blackmaterial>
gazebo>
用gazebo标签去描述,因为用某个link去代表激光雷达插件,所以要用reference去指定是哪个link,$ {prefix}_link这个一定要与上面的 < link name="${prefix}_link">一致
<gazebo reference="${prefix}_link">
在里面用< sensor >标签来描述传感器信息 type指定传感器类型name自己去定义
<sensor type="ray" name="rplidar">
sensor里面就是传感器参数的设置
具体参数含义在注释中
<gazebo reference="${prefix}_link">
<sensor type="ray" name="rplidar">
<pose>0 0 0 0 0 0pose>
<visualize>falsevisualize>
<update_rate>5.5update_rate>
<ray>
<scan>
<horizontal>
<samples>360samples>
<resolution>1resolution>
<min_angle>-3min_angle>
<max_angle>3max_angle>
horizontal>
scan>
<range>
<min>0.10min>
<max>6.0max>
<resolution>0.01resolution>
range>
<noise>
<type>gaussiantype>
<mean>0.0mean>
<stddev>0.01stddev>
noise>
ray>
<plugin name="gazebo_rplidar" filename="libgazebo_ros_laser.so">
<topicName>/scantopicName>
<frameName>laser_linkframeName>
plugin>
sensor>
gazebo>
<robot name="arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find mbot_description)/urdf/xacro/gazebo/mbot_base_gazebo.xacro" />
<xacro:include filename="$(find mbot_description)/urdf/xacro/sensors/lidar_gazebo.xacro" />
<xacro:property name="lidar_offset_x" value="0" />
<xacro:property name="lidar_offset_y" value="0" />
<xacro:property name="lidar_offset_z" value="0.105" />
<joint name="lidar_joint" type="fixed">
<origin xyz="${lidar_offset_x} ${lidar_offset_y} ${lidar_offset_z}" rpy="0 0 0" />
<parent link="base_link"/>
<child link="laser_link"/>
joint>
<xacro:rplidar prefix="laser"/>
<mbot_base_gazebo/>
robot>
其它的都不动,只是改变机器人模型文件和仿真环境文件路径即可
<launch>
<arg name="world_name" value="$(find mbot_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"/>
<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 mbot_description)/urdf/xacro/gazebo/mbot_with_laser_gazebo.xacro'" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" >node>
<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>
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model mrobot -param robot_description"/>
launch>
运行launch文件
$ roslaunch mbot_gazebo view_mbot_with_laser_gazebo.launch
$ rosrun rviz rviz
添加 add
机器人模型 RobotModel 选择坐标系 画面出现机器人
雷达信息 LaserScan 选择topic /scan出现雷达信息
雷达仿真完成