在上一节博客中我们系统的学习了如何在RVIZ中使用Arbotix实现对于使用URDF文件生成的机器人模型的运动控制,并通过一个简单的运动实例讲解了具体的仿真流程,本节内容主要聚焦于如何在Gazebo中集成URDF文件对应的机器人模型,为今后的联合仿真打下基础,也初步认识了Gazebo仿真软件该如何使用。
\qquad
第一步,创建功能包:
\qquad 依赖项:urdf、xacro、gazebo_ros、gazebo_ros_control、gazebo_plugins等
第二步,编写URDF文件组建机器人模型:
<robot name="mycar">
<link name="base_link">
<visual>
<geometry>
<box size="0.5 0.2 0.1" />
geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<material name="yellow">
<color rgba="0.5 0.3 0.0 1" />
material>
visual>
<collision>
<geometry>
<box size="0.5 0.2 0.1" />
geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="6" />
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1" />
inertial>
link>
<gazebo reference="base_link">
<material>Gazebo/Blackmaterial>
gazebo>
robot>
注意:在此处URDF文件有关键要求,对于标签的使用存在与Rviz外的额外要求,在集成相关设置中具体讲述;
第三步,启动Gazebo并显示模型:launch文件编写
<launch>
<param name="robot_description" textfile="$(find demo02_urdf_gazebo)/urdf/urdf01_helloworld.urdf" />
<include file="$(find gazebo_ros)/launch/empty_world.launch" />
<node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model mycar -param robot_description" />
launch>
第一项,必须添加 collision 标签
\qquad 当机器人的link属于标准几何体时,碰撞设置与link的visual属性一致即可;
第二项,必须添加 inertial 标签
原因:此标签标注了当前机器人某个刚体部分的惯性矩阵,用于一些力学相关的仿真计算,除了 base_footprint 外,机器人的每个刚体部分都需要设置惯性矩阵,且此矩阵必须准确得到,否则会出现抖动等现象;
设置方法:结合link的质量与外形参数动态生成,标准矩阵举例如下:
- 球体惯性矩阵
<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>
- 1
- 2
- 3
- 4
- 5
- 6
- 7
- 8
- 9
- 圆柱惯性矩阵
<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>
- 1
- 2
- 3
- 4
- 5
- 6
- 7
- 8
- 立方体惯性矩阵
<xacro:macro name="Box_inertial_matrix" params="m l w h"> <inertial> <mass value="${m}" /> <inertia ixx="${m*(h*h + l*l)/12}" ixy = "0" ixz = "0" iyy="${m*(w*w + l*l)/12}" iyz= "0" izz="${m*(w*w + h*h)/12}" /> inertial> xacro:macro>
- 1
- 2
- 3
- 4
- 5
- 6
- 7
- 8
第三项,使用gazebo标签重新标注颜色
<gazebo reference="link节点名称">
<material>Gazebo/Bluematerial>
gazebo>
第一步,编写惯性矩阵算法相关的xacro文件
<robot name="base" xmlns:xacro="http://wiki.ros.org/xacro">
<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 l w h">
<inertial>
<mass value="${m}" />
<inertia ixx="${m*(h*h + l*l)/12}" ixy = "0" ixz = "0"
iyy="${m*(w*w + l*l)/12}" iyz= "0"
izz="${m*(w*w + h*h)/12}" />
inertial>
xacro:macro>
robot>
第二步,对机器人模型中的各link添加相关设置(collision、inertial、颜色)
\qquad 1. 底盘Xacro文件
<robot name="my_base" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="PI" value="3.1415926"/>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
material>
<xacro:property name="base_footprint_radius" value="0.001" />
<xacro:property name="base_link_radius" value="0.1" />
<xacro:property name="base_link_length" value="0.08" />
<xacro:property name="earth_space" value="0.015" />
<xacro:property name="base_link_m" value="0.5" />
<link name="base_footprint">
<visual>
<geometry>
<sphere radius="${base_footprint_radius}" />
geometry>
visual>
link>
<link name="base_link">
<visual>
<geometry>
<cylinder radius="${base_link_radius}" length="${base_link_length}" />
geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="yellow">
<color rgba="0.5 0.3 0.0 0.5" />
material>
visual>
<collision>
<geometry>
<cylinder radius="${base_link_radius}" length="${base_link_length}" />
geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
collision>
<xacro:cylinder_inertial_matrix m="${base_link_m}" r="${base_link_radius}" h="${base_link_length}" />
link>
<joint name="base_link2base_footprint" type="fixed">
<parent link="base_footprint" />
<child link="base_link" />
<origin xyz="0 0 ${earth_space + base_link_length / 2 }" />
joint>
<gazebo reference="base_link">
<material>Gazebo/Yellowmaterial>
gazebo>
<xacro:property name="wheel_radius" value="0.0325" />
<xacro:property name="wheel_length" value="0.015" />
<xacro:property name="wheel_m" value="0.05" />
<xacro:macro name="add_wheels" params="name flag">
<link name="${name}_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}" />
geometry>
<origin xyz="0.0 0.0 0.0" rpy="${PI / 2} 0.0 0.0" />
<material name="black" />
visual>
<collision>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}" />
geometry>
<origin xyz="0.0 0.0 0.0" rpy="${PI / 2} 0.0 0.0" />
collision>
<xacro:cylinder_inertial_matrix m="${wheel_m}" r="${wheel_radius}" h="${wheel_length}" />
link>
<joint name="${name}_wheel2base_link" type="continuous">
<parent link="base_link" />
<child link="${name}_wheel" />
<origin xyz="0 ${flag * base_link_radius} ${-(earth_space + base_link_length / 2 - wheel_radius) }" />
<axis xyz="0 1 0" />
joint>
<gazebo reference="${name}_wheel">
<material>Gazebo/Redmaterial>
gazebo>
xacro:macro>
<xacro:add_wheels name="left" flag="1" />
<xacro:add_wheels name="right" flag="-1" />
<xacro:property name="support_wheel_radius" value="0.0075" />
<xacro:property name="support_wheel_m" value="0.03" />
<xacro:macro name="add_support_wheel" params="name flag" >
<link name="${name}_wheel">
<visual>
<geometry>
<sphere radius="${support_wheel_radius}" />
geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="black" />
visual>
<collision>
<geometry>
<sphere radius="${support_wheel_radius}" />
geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
collision>
<xacro:sphere_inertial_matrix m="${support_wheel_m}" r="${support_wheel_radius}" />
link>
<joint name="${name}_wheel2base_link" type="continuous">
<parent link="base_link" />
<child link="${name}_wheel" />
<origin xyz="${flag * (base_link_radius - support_wheel_radius)} 0 ${-(base_link_length / 2 + earth_space / 2)}" />
<axis xyz="1 1 1" />
joint>
<gazebo reference="${name}_wheel">
<material>Gazebo/Redmaterial>
gazebo>
xacro:macro>
<xacro:add_support_wheel name="front" flag="1" />
<xacro:add_support_wheel name="back" flag="-1" />
robot>
\qquad 2. 摄像头Xacro文件
<robot name="my_camera" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:property name="camera_length" value="0.01" />
<xacro:property name="camera_width" value="0.025" />
<xacro:property name="camera_height" value="0.025" />
<xacro:property name="camera_x" value="0.08" />
<xacro:property name="camera_y" value="0.0" />
<xacro:property name="camera_z" value="${base_link_length / 2 + camera_height / 2}" />
<xacro:property name="camera_m" value="0.01" />
<link name="camera">
<visual>
<geometry>
<box size="${camera_length} ${camera_width} ${camera_height}" />
geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<material name="black" />
visual>
<collision>
<geometry>
<box size="${camera_length} ${camera_width} ${camera_height}" />
geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
collision>
<xacro:Box_inertial_matrix m="${camera_m}" l="${camera_length}" w="${camera_width}" h="${camera_height}" />
link>
<joint name="camera2base_link" type="fixed">
<parent link="base_link" />
<child link="camera" />
<origin xyz="${camera_x} ${camera_y} ${camera_z}" />
joint>
<gazebo reference="camera">
<material>Gazebo/Bluematerial>
gazebo>
robot>
\qquad 3. 雷达Xacro文件
<robot name="my_laser" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:property name="support_length" value="0.15" />
<xacro:property name="support_radius" value="0.01" />
<xacro:property name="support_x" value="0.0" />
<xacro:property name="support_y" value="0.0" />
<xacro:property name="support_z" value="${base_link_length / 2 + support_length / 2}" />
<xacro:property name="support_m" value="0.02" />
<link name="support">
<visual>
<geometry>
<cylinder radius="${support_radius}" length="${support_length}" />
geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<material name="red">
<color rgba="0.8 0.2 0.0 0.8" />
material>
visual>
<collision>
<geometry>
<cylinder radius="${support_radius}" length="${support_length}" />
geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
collision>
<xacro:cylinder_inertial_matrix m="${support_m}" r="${support_radius}" h="${support_length}" />
link>
<joint name="support2base_link" type="fixed">
<parent link="base_link" />
<child link="support" />
<origin xyz="${support_x} ${support_y} ${support_z}" />
joint>
<gazebo reference="support">
<material>Gazebo/Whitematerial>
gazebo>
<xacro:property name="laser_length" value="0.05" />
<xacro:property name="laser_radius" value="0.03" />
<xacro:property name="laser_x" value="0.0" />
<xacro:property name="laser_y" value="0.0" />
<xacro:property name="laser_z" value="${support_length / 2 + laser_length / 2}" />
<xacro:property name="laser_m" value="0.1" />
<link name="laser">
<visual>
<geometry>
<cylinder radius="${laser_radius}" length="${laser_length}" />
geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<material name="black" />
visual>
<collision>
<geometry>
<cylinder radius="${laser_radius}" length="${laser_length}" />
geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
collision>
<xacro:cylinder_inertial_matrix m="${laser_m}" r="${laser_radius}" h="${laser_length}" />
link>
<joint name="laser2support" type="fixed">
<parent link="support" />
<child link="laser" />
<origin xyz="${laser_x} ${laser_y} ${laser_z}" />
joint>
<gazebo reference="laser">
<material>Gazebo/Blackmaterial>
gazebo>
robot>
\qquad 4. 组合Xacro文件
<robot name="my_car_camera" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="my_head.urdf.xacro" />
<xacro:include filename="my_base.urdf.xacro" />
<xacro:include filename="my_camera.urdf.xacro" />
<xacro:include filename="my_laser.urdf.xacro" />
robot>
第三步,编写launch文件,在gazebo中执行
<launch>
<param name="robot_description" command="$(find xacro)/xacro $(find demo02_urdf_gazebo)/urdf/xacro/my_base_camera_laser.urdf.xacro" />
<include file="$(find gazebo_ros)/launch/empty_world.launch" />
<node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model mycar -param robot_description" />
launch>
n" command="$(find xacro)/xacro $(find demo02_urdf_gazebo)/urdf/xacro/my_base_camera_laser.urdf.xacro" />
<include file="$(find gazebo_ros)/launch/empty_world.launch" />
<node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model mycar -param robot_description" />
launch>
显示效果如下:
<launch>
<param name="robot_description" command="$(find xacro)/xacro $(find demo02_urdf_gazebo)/urdf/xacro/my_base_camera_laser.urdf.xacro" />
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find demo02_urdf_gazebo)/worlds/hello.world" />
include>
<node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model mycar -param robot_description" />
launch>
这里以官方模型库为例,git下载较为耗时,可自行寻找目标文件
git clone https://github.com/osrf/gazebo_models
- 复制文件:
将gazebo_models文件夹内容复制到 /usr/share/gazebo-*/models- 重启gazebo,应用文件:
选择左侧菜单栏的 insert 可以选择并插入相关道具