前言
单个机器人的各项仿真实验都基本完成,也实现了远程控制,接下来主要对多机器人编队进行仿真实验,在进行多机器人编队控制前,先要在gazebo仿真中加载多个机器人。
一、基本概念
在gazebo中添加多个机器人需要写或修改launch文件,通过在网上翻看别人的代码,大致明白了调用gazebo仿真launch文件中各部分代码的意思。下面是一些最最基本的概念,在修改launch前稍微了解一下。
1、xacro
类似于函数实现,提高代码复用率,优化代码结构,提高安全性
(1)宏定义
<xacro:macro name="宏名称" params="参数列表(多参数之前使用空格分隔)">
....
参数调用格式:${参数名}
</xacro:macro>
(2)宏调用
<xacro:宏名称 参数1=xxx 参数2=xxx/>
(3)文件包含
机器人由多部件组成,不同部件可能封装为单独的xacro文件,最后再将不同的文件集成,组合为完整机器人,可以使用文件包含实现。
<robot name="xxx" xmls:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="my_base.xacro">
<xacro:include filename="my_camera.xacro">
<xacro:include filename="my_laser.xacro">
....
</robot>
在launch文件中直接加载xacro的方法
command="$(find xacro)/xacro $(find 文件名)/urdf/.urdf.xacro(文件名)"
2、Gazebo 加载单个机器人模型
<launch>
<!-- 将Urdf文件的内容加载到参数服务器-->
<param name="robot_description"textfile=“$(find文件夹名)/urdf/.urdf文件“>
<!--启动gazebo-->
<include file="$(find gazebo_ros)/launch/empty_world.launch"/>
<!--在gazebo中显示机器人模型-->
<node pkg="gazebo_ros"type="spawn_model"name="model"args="-urdf-model mycar-param robot_description"/>
</launch>
二、原先launch文件代码
在大致看了上述的说明后就能看懂,在gazebo仿真环境中加载一个机器人的launch文件了。
复制粘贴如下:根据上面的基本概念可以大概的明白代码所描述的内容。
(如我在图中添加的注释)
<launch>
<!--在所提供的burger, waffle, waffle_pi三种机器人呢模型中选择要加载的类型-->
<arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
<!--设置机器人的x,y,z坐标,相当于宏定义方面下面使用和后面的修改-->
<arg name="x_pos" default="-2.0"/>
<arg name="y_pos" default="-0.5"/>
<arg name="z_pos" default="0.0"/>
<!-- 运行gazebo仿真环境 -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find turtlebot3_gazebo)/worlds/turtlebot3_world.world"/>
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="true"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
</include>
<!--在launch文件中直接加载机器人xacro模型描述文件-->
<param name="robot_description" command="$(find xacro)/xacro --inorder $(find turtlebot3_description)/urdf/turtlebot3_$(arg model).urdf.xacro" />
<!--在gazeb中显示机器人模型,并设置初始的坐标位置-->
<node pkg="gazebo_ros" type="spawn_model" name="spawn_urdf" args="-urdf -model turtlebot3_$(arg model) -x $(arg x_pos) -y $(arg y_pos) -z $(arg z_pos) -param robot_description" />
</launch>
gazebo启动结果如下:
三、 修改launch文件加载多个机器人
在理解了launch调用和加载的各项指令后,接下来实现在gazebo中加载多个机器人,相比于单机器人,多机器人仿真需要在原基础上加入标签,做到用同样的descripion配置文件加载多个独立的机器人。
具有ns属性,可以将节点组推送到单独的命名空间中。在前面的基础上,我通过指令touch + test(文件名).launch
创建了新的test.launch文件在launch文件中改写成以下内容:
<launch>
<!--首先我将原先选择机器人模型,全部设置为了waffle机器人模型-->
<arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type turtlebot3_waffle"/>
<!--因为需要给每个机器人设置初始位置,我将原先的宏定义删除,选择直接在加载的时候定义机器人的初始位置-->
<!-- 运行gazebo仿真环境 --> <!-- 没有变化 -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find turtlebot3_gazebo)/worlds/turtlebot3_world.world"/>
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="true"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
</include>
<!-- 加载多个机器人时需要加入<group>标签 -->
<!-- 注意每个机器人都要有一个命名空间,且名字不同-->
<!--在.urdf.xacro后要声明且在下面显示模型后面也要跟上命名空间的名字 -->
<group ns="1">
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find turtlebot3_description)/urdf/turtlebot3_waffle.urdf.xacro' ns:=1" />
<!--在-param robot_description后可以指定机器人的初始位置,类似于默认参数,如果不传入数据默认机器人的初始位置是(0,0,0),传入实参后会改变初始位置 -->
<node pkg="gazebo_ros" type="spawn_model" name="spawn_urdf" args="-urdf -model 1 -param robot_description -x -2.0" />
</group>
<group ns="2">
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find turtlebot3_description)/urdf/turtlebot3_waffle.urdf.xacro' ns:=2" />
<node pkg="gazebo_ros" type="spawn_model" name="spawn_urdf" args="-urdf -model 2 -param robot_description -x -1.5" />
</group>
<group ns="3">
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find turtlebot3_description)/urdf/turtlebot3_waffle.urdf.xacro' ns:=3" />
<node pkg="gazebo_ros" type="spawn_model" name="spawn_urdf" args="-urdf -model 3 -param robot_description -x -2.0 -y 0.7" />
</group>
<group ns="4">
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find turtlebot3_description)/urdf/turtlebot3_waffle.urdf.xacro' ns:=4" />
<node pkg="gazebo_ros" type="spawn_model" name="spawn_urdf" args="-urdf -model 4 -param robot_description -x -1.5 -y 0.7" />
</group>
</launch>
运行test.launch文件,即可在Gazebo仿真环境中加载多个机器人模型。
总结
在Gazebo仿真环境中成功加载了多个机器人模型,接下来想办法实现在Gazebo中实现多机器人的编队控制。