上一篇博客:ros机器人编程实践(16.2)- 仿真SmartCar之模型“飞起来“
上一章我们将模型导入到rviz中并成功的动起来了,但是rviz软件环境主要是用于数据可视化的,处理数据比较方便,真实环境的模型仿真还是需要在gazebo中进行。
我们之前在16.1中配置的urdf文件只配置了模型的链接方式和形状颜色,只有这些在gazebo物理引擎中是没法进行运动的,需要给模型的各个部分加上gazebo属性。因为还不是很熟悉xarco文件格式,我这里还是在16.1的urdf文件上修改,这一章重点讲解下urdf文件的内容,为了方便大家修改模型。
标签
标签
标签
中设置连杆的可视化,惯性,碰撞属性
标签
<link name="base_link">
<visual>
</visual>
</link>
标签
声明立方体和圆柱体 <link name="base_link">
<visual>
<geometry>
<box size="0.25 .16 .05"/>
</geometry>
</visual>
</link>
标签
<link name="base_link">
<visual>
<geometry>
<box size="0.25 .16 .05"/>
</geometry>
<origin rpy="0 0 1.57075" xyz="0 0 0"/>
</visual>
</link>
标签
<link name="base_link">
<visual>
<geometry>
<box size="0.25 .16 .05"/>
</geometry>
<origin rpy="0 0 1.57075" xyz="0 0 0"/>
<material name="blue">
<color rgba="0 .5 .8 1"/>
</material>
</visual>
</link>
上述的标签是模型搭建的基本,可以看到主要创建了模型的形状、大小、颜色、连接关系等,这也就足够在rviz中动起来了,但是在gazebo中还需要配置模型相应的物理属性,如:质量、转动惯量、材质、碰撞等。
标签
<collision>
<geometry>
<box size="0.25 .16 .05"/>
</geometry>
</collision>
标签
,声明质量;
,声明转动惯量矩阵<inertial>
<mass value="1.0"/>
<inertia ixx="0.0054" iyy="0.0073" izz="0.0023" ixy="0" ixz="0" iyz="0"/>
</inertial>
Tips:转动惯量公式可以看看大学物理的课本或者自己推导下,这里贴上部分
圆柱体:
立方体:
标签下的
<gazebo reference="base_link">
<material>Gazebo/Yellow</material>
</gazebo>
标签下的
<gazebo>
<!--驱动方式这里是差速驱动-->
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<leftJoint>left_back_wheel_joint</leftJoint>
<rightJoint>right_back_wheel_joint</rightJoint>
<robotBaseFrame>base_link</robotBaseFrame>
<wheelSeparation>0.14</wheelSeparation><!--轮距-->
<wheelDiameter>0.05</wheelDiameter><!--轮子直径-->
<legacyMode>true</legacyMode>
<publishWheelJointState>true</publishWheelJointState>
</plugin>
</gazebo>
标签下的
<gazebo reference="camera_link">
<!--摄像头节点-->
<sensor type="camera" name="camera_node">
<!--发布频率-->
<update_rate>30.0</update_rate>
<!--摄像头名字-->
<camera name="head">
<!--水平视场角-->
<horizontal_fov>1.3962634</horizontal_fov>
<!--图片参数-->
<image>
<width>1280</width>
<height>720</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="gazebo_camera" filename="libgazebo_ros_camera.so">
<!--摄像头常开-->
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>/camera</cameraName>
<!--摄像头发布的话题-->
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
根据上述所有的说明,我们可以把之前的SmartCar.urdf文件修改成支持gazebo的文件,如下:
<robot name="smartcar">
<link name="base_link">
<visual>
<geometry>
<box size="0.25 .16 .05"/>
geometry>
<origin rpy="0 0 1.57075" xyz="0 0 0"/>
<material name="blue">
<color rgba="0 .5 .8 1"/>
material>
visual>
<collision>
<geometry>
<box size="0.25 .16 .05"/>
geometry>
collision>
<inertial>
<mass value="1.0"/>
<inertia ixx="0.0054" iyy="0.0073" izz="0.0023" ixy="0" ixz="0" iyz="0"/>
inertial>
link>
<gazebo reference="base_link">
<material>Gazebo/Yellowmaterial>
gazebo>
<link name="right_front_wheel">
<visual>
<geometry>
<cylinder length=".02" radius="0.025"/>
geometry>
<material name="black">
<color rgba="0 0 0 1"/>
material>
visual>
<collision>
<geometry>
<cylinder length=".02" radius="0.025"/>
geometry>
collision>
<inertial>
<mass value="0.1"/>
<inertia ixx="0.0000189" iyy=".0000189583" izz="0.00003125" ixy="0" ixz="0" iyz="0"/>
inertial>
link>
<joint name="right_front_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="right_front_wheel"/>
<origin rpy="0 1.57075 0" xyz="0.08 0.1 -0.03"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
joint>
<gazebo reference="right_front_wheel">
<material>Gazebo/Blackmaterial>
gazebo>
<link name="right_back_wheel">
<visual>
<geometry>
<cylinder length=".02" radius="0.025"/>
geometry>
<material name="black">
<color rgba="0 0 0 1"/>
material>
visual>
<collision>
<geometry>
<cylinder length=".02" radius="0.025"/>
geometry>
collision>
<inertial>
<mass value="0.1"/>
<inertia ixx="0.0000189" iyy=".0000189583" izz="0.00003125" ixy="0" ixz="0" iyz="0"/>
inertial>
link>
<joint name="right_back_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="right_back_wheel"/>
<origin rpy="0 1.57075 0" xyz="0.08 -0.1 -0.03"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
joint>
<gazebo reference="right_back_wheel">
<material>Gazebo/Blackmaterial>
gazebo>
<link name="left_front_wheel">
<visual>
<geometry>
<cylinder length=".02" radius="0.025"/>
geometry>
<material name="black">
<color rgba="0 0 0 1"/>
material>
visual>
<collision>
<geometry>
<cylinder length=".02" radius="0.025"/>
geometry>
collision>
<inertial>
<mass value="0.1"/>
<inertia ixx="0.0000189" iyy=".0000189583" izz="0.00003125" ixy="0" ixz="0" iyz="0"/>
inertial>
link>
<joint name="left_front_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="left_front_wheel"/>
<origin rpy="0 1.57075 0" xyz="-0.08 0.1 -0.03"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
joint>
<gazebo reference="left_front_wheel">
<material>Gazebo/Blackmaterial>
gazebo>
<link name="left_back_wheel">
<visual>
<geometry>
<cylinder length=".02" radius="0.025"/>
geometry>
<material name="black">
<color rgba="0 0 0 1"/>
material>
visual>
<collision>
<geometry>
<cylinder length=".02" radius="0.025"/>
geometry>
collision>
<inertial>
<mass value="0.1"/>
<inertia ixx="0.0000189" iyy=".0000189583" izz="0.00003125" ixy="0" ixz="0" iyz="0"/>
inertial>
link>
<joint name="left_back_wheel_joint" type="continuous">
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="left_back_wheel"/>
<origin rpy="0 1.57075 0" xyz="-0.08 -0.1 -0.03"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
joint>
<gazebo reference="left_back_wheel">
<material>Gazebo/Blackmaterial>
gazebo>
<link name="camera_link">
<visual>
<geometry>
<box size=".02 .03 .03"/>
geometry>
<material name="white">
<color rgba="1 1 1 1"/>
material>
visual>
<collision>
<geometry>
<box size="0.02 .03 .03"/>
geometry>
collision>
<inertial>
<mass value="0.1"/>
<inertia ixx="0.000010833" iyy="0.000010833" izz="0.000015" ixy="0" ixz="0" iyz="0"/>
inertial>
link>
<joint name="tobox" type="fixed">
<parent link="base_link"/>
<child link="camera_link"/>
<origin xyz="0 0.08 0.025" rpy="0 0 1.57"/>
joint>
<gazebo reference="camera">
<material>Gazebo/Bluematerial>
gazebo>
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<leftJoint>left_back_wheel_jointleftJoint>
<rightJoint>right_back_wheel_jointrightJoint>
<robotBaseFrame>base_linkrobotBaseFrame>
<wheelSeparation>0.14wheelSeparation>
<wheelDiameter>0.05wheelDiameter>
<legacyMode>truelegacyMode>
<publishWheelJointState>truepublishWheelJointState>
plugin>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<leftJoint>left_front_wheel_jointleftJoint>
<rightJoint>right_front_wheel_jointrightJoint>
<robotBaseFrame>base_linkrobotBaseFrame>
<wheelSeparation>0.14wheelSeparation>
<wheelDiameter>0.05wheelDiameter>
<legacyMode>truelegacyMode>
<publishWheelJointState>truepublishWheelJointState>
plugin>
gazebo>
<gazebo reference="camera_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>
在launch下创建smartcar_display_gazebo.launch文件
cd ~/SmartCar_ws/src/smartcar_description/launch
gedit smartcar_display_gazebo.launch
smartcar_display_gazebo.launch如下:
<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 smartcar_description)/urdf/SmartCar.urdf'"/>
<param name="publish_frequency" type="double" value="20.0" />
node>
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model shcrobot -param robot_description"/>
launch>
cd ~/SmartCar_ws
source ./devel/setup.bash
roslaunch smartcar_description smartcar_display_gazebo.launch
rqt_image_view
rostopic pub -r 10 /cmd_vel geometry_msgs/Twist '{linear: {x: 5, y: 0, z: 0}, angular: {x: 0, y: 0, z: 0}}'
这里不知道是摩擦力的原因还是啥,四轮车在转向上表现的并不理想。。。下一章改成三轮小车吧,后两个轮子驱动,前面一个轮子转向。