Bootstrap

【ROS+amcl+Movebase】多机器人导航

学过单机器人在已知地图中的导航后,想到如果有多个机器人在同一地图如何导航,于是在网上学习了下,主流方案即在单机器人导航的基础上引入命名空间。
参考文章1
参考文章2
参考文章3
实验效果录屏
 

一、实验环境

Ubuntu1804(虚拟机)
ROS(melodic)
Navigation(move_base+amcl)
gazebo(9.0.0)
vscode
 

二、目录结构

在这里插入图片描述

相比单机器人导航,改动主要集中在launch目录下,gazebo差速器仿真部分也需要修改,rviz下有少量插件配置变动不是学习重点。
 

三、launch文件

除了之前学过的单机器人导航的关键点,这里最重要的就是命名空间了。
我们之前只有一个机器人,所有的主题、节点、TF变换都是在全局空间下,都是默认的,不需要分辨谁从哪来到哪去给谁用,一旦加入了第二个同样的机器人,它的主题、TF等跟第一个机器人完全相同,这样就会乱套,为了将它们以及它们的种种属性区分开来,引入了命名空间。
 

carbot_group_navigation.launch

<launch>
    <arg name="verbose" default="false"/>
    <arg name="robot_namespace" default=""/>

    <include file="$(find gazebo_ros)/launch/empty_world.launch">
        <arg name="world_name" value="$(find carbot_multi_navi)/world/space.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="verbose" value="$(arg verbose)"/>
        <arg name="debug" value="false"/>
    </include>

    <!-- 运行地图服务器,并且加载设置的地图 -->
    <arg name="map" default="space.yaml" />
    <node name="map_server" pkg="map_server" type="map_server" args="$(find carbot_multi_navi)/maps/$(arg map)"/>

    <!-- 配置不同命名空间下的机器人 -->
    <group ns = "car1">
        <param name="robot_description" command="$(find xacro)/xacro '$(find carbot_multi_navi)/urdf/carbot_gazebo.urdf.xacro'"/>
        <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
            args="-urdf -model car1 -param robot_description -y 0.5"/> 

        <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher">
            <param name="publish_frequency" type="double" value="50.0" />
            <param name="tf_prefix" value="car1" />
        </node>
        <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"/>
    </group>

    <group ns = "car2">
        <param name="robot_description" command="$(find xacro)/xacro '$(find carbot_multi_navi)/urdf/carbot_gazebo.urdf.xacro'"/>

        <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
            args="-urdf -model car2 -param robot_description -y 0.0"/> 

        <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher">
            <param name="publish_frequency" type="double" value="50.0" />
            <param name="tf_prefix" value="car2" />
        </node>
        <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"/>
    </group>

    <group ns = "car3">
        <param name="robot_description" command="$(find xacro)/xacro '$(find carbot_multi_navi)/urdf/carbot_gazebo.urdf.xacro'"/>
        <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
            args="-urdf -model car3 -param robot_description -y -0.5"/> 

        <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher">
            <param name="publish_frequency" type="double" value="50.0" />
            <param name="tf_prefix" value="car3" />
        </node>      
        <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"/>
        <!-- <node pkg="tf" type="static_transform_publisher" name="map_odom_broadcaster" args="0 0 0 0 0 0 /map car3/odom 100" /> -->
    </group>

    <!-- move_base配置 -->
    <include file="$(find carbot_multi_navi)/launch/move_base.launch" >
        <arg name="robot_namespace" value="car1" />
    </include>
    <include file="$(find carbot_multi_navi)/launch/move_base.launch">
        <arg name="robot_namespace" value="car2" />
    </include>
    <include file="$(find carbot_multi_navi)/launch/move_base.launch" >
        <arg name="robot_namespace" value="car3" />
    </include>


    <!-- amcl配置 -->
    <include file="$(find carbot_multi_navi)/launch/amcl.launch">
        <arg name="robot_namespace" value="car1" />
        <arg name="initial_pose_x" value="0.0"/>
        <arg name="initial_pose_y" value="0.5"/>
        <arg name="initial_pose_a" value="0.0"/>
    </include>
    <include file="$(find carbot_multi_navi)/launch/amcl.launch">
        <arg name="robot_namespace" value="car2" />
        <arg name="initial_pose_x" value="0.0"/>
        <arg name="initial_pose_y" value="0.0"/>
        <arg name="initial_pose_a" value="0.0"/>
    </include>
    <include file="$(find carbot_multi_navi)/launch/amcl.launch">
        <arg name="robot_namespace" value="car3" />
        <arg name="initial_pose_x" value="0.0"/>
        <arg name="initial_pose_y" value="-0.5"/>
        <arg name="initial_pose_a" value="0.0"/>
    </include>
    
    <!-- 启动rviz -->
    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find carbot_multi_navi)/rviz/nav_multi.rviz"/>

</launch>

这是总的启动文件,启用了gazebo,map-server,amcl,move_base,rviz。
其中gazebo又分加载世界和加载机器人,世界(即场景模型)只需要加载一个(因此不需要放在命名空间下),机器人在不同命名空间下分别加载一个,加了命名空间的机器人,其内部所订阅、发布的主题都会带命名空间前缀,比如在我们加载的第一个机器人,其命名空间为car1,那么它默认的运动控制主题/cmd_vel就会变成/car1/cmd_vel,它自身带的雷达发布的默认主题/scan也会相应的加上前缀变为/car1/scan
这里举例的机器人其实代表的是节点,在<group ns="xxx">标签内的所有节点都是这样,像joint_state_publisher节点发布的主题就变为/car1/joint_states,搞清楚了这个原理,就会省下很多麻烦。比如三个机器人对应的amcl定位节点的主题该如何指定呢?答案是,将amcl节点放在标签下,然后其主题就不需要再额外指定了,之前单机器人如何,现在就如何。同理,move_base节点的主题也是如此。

搞完上面的这些,兴奋地尝试了下,结果并不如愿。发现一直在报警告,大概的意思是找不到某base_footprint到map的转换关系,找不到xxx到xxx的转换关系,打开rqt_tf_tree一看,TF树并没有连在一起。有的frame都给加了命名空间前缀(如/car1/base_link),而有些却没有加前缀(如odom),明明所有需要加命名空间的节点都老老实实加了命名空间,为什么有些frame还是不能自动加前缀转换坐标呢。(给我自己问懵了,词穷。。。难以用文字语言解答)
这里直接针对问题给出方案,没有正确转换的坐标frame,我们要进行干预了,手动指定哪些要转换,如何转换。参考之前单机器人导航,我们就到amcl.launch中找到转换关系,发现了global_frame_id,odom_frame_id,base_frame_id这三个坐标系,首先map只有一个,所以global_frame_id是不需要加前缀的,而其余两个每个机器人都是不同的,也就是加上对应命名空间的前缀,

<arg name="odom_frame_id"   value="$(arg robot_namespace)/odom"/>
<arg name="base_frame_id"   value="$(arg robot_namespace)/base_footprint"/>

同样的,在move_base.launch中也如此指定,将所有的frame_id加上对应的命名空间前缀(注意改的是value)。
 

amcl.launch

<launch>
    <arg name="use_map_topic" default="false"/>
    <arg name="robot_namespace" default=""/>
    <arg name="global_frame_id" default="map"/>
    <arg name="scan_topic" value="scan"/>
    <arg name="odom_frame_id"   value="$(arg robot_namespace)/odom"/>
    <arg name="base_frame_id"   value="$(arg robot_namespace)/base_footprint"/>

    <arg name="initial_pose_x" default="0"/>
    <arg name="initial_pose_y" default="0"/>
    <arg name="initial_pose_a" default="0"/>
    <group ns="$(arg robot_namespace)">

      <node pkg="amcl" type="amcl" name="amcl">
          <param name="use_map_topic" value="$(arg use_map_topic)"/>
          <!-- Publish scans from best pose at a max of 10 Hz -->
          <param name="odom_model_type" value="diff"/>
          <param name="odom_alpha5" value="0.05"/>
          <param name="gui_publish_rate" value="10.0"/>
          <param name="laser_max_beams" value="180"/>
          <param name="laser_max_range" value="6.0"/>
          <param name="min_particles" value="300"/>
          <param name="max_particles" value="1000"/>
          <param name="kld_err" value="0.05"/>
          <param name="kld_z" value="0.99"/>
          <param name="odom_alpha1" value="0.05"/>
          <param name="odom_alpha2" value="0.05"/>
          <!-- translation std dev, m -->
          <param name="odom_alpha3" value="0.05"/>
          <param name="odom_alpha4" value="0.05"/>
          <param name="laser_z_hit" value="0.5"/>
          <param name="laser_z_short" value="0.05"/>
          <param name="laser_z_max" value="0.05"/>
          <param name="laser_z_rand" value="0.5"/>
          <param name="laser_sigma_hit" value="0.2"/>
          <param name="laser_lambda_short" value="0.1"/>
          <param name="laser_model_type" value="likelihood_field"/>
          <!-- <param name="laser_model_type" value="beam"/> -->
          <param name="laser_likelihood_max_dist" value="2.0"/>
          <param name="update_min_d" value="0.25"/>
          <param name="update_min_a" value="0.2"/>
          <param name="resample_interval" value="1"/>
          <!-- Increase tolerance because the computer can get quite busy -->
          <param name="transform_tolerance" value="0.5"/>
          <param name="recovery_alpha_slow" value="0.0"/>
          <param name="recovery_alpha_fast" value="0.0"/>

          <param name="global_frame_id"  value="$(arg global_frame_id)"/>
          <param name="odom_frame_id"  value="$(arg odom_frame_id)"/>
          <param name="base_frame_id"  value="$(arg base_frame_id)"/>

          <param name="initial_pose_x" value="$(arg initial_pose_x)"/>
          <param name="initial_pose_y" value="$(arg initial_pose_y)"/>
          <param name="initial_pose_a" value="$(arg initial_pose_a)"/>
          
          <remap from="scan" to="$(arg scan_topic)"/>
          <remap from="static_map" to="/static_map"/>
          <remap from="map" to="/map" />
      </node>  
    </group>
</launch>

 

move_base.launch

<launch>
    <arg name="robot_namespace" default=""/>

    <arg name="laser_topic" default="scan" />
    <arg name="odom_topic" default="odom" />
    <arg name="cmd_topic" default="cmd_vel" />
    <arg name="global_frame_id" default="map"/>
    <arg name="odom_frame_id"   value="$(arg robot_namespace)/odom"/>
    <arg name="base_frame_id"   value="$(arg robot_namespace)/base_footprint"/>


    <group ns="$(arg robot_namespace)">
        <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
            <!-- Default configs -->
            <rosparam file="$(find carbot_multi_navi)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
            <rosparam file="$(find carbot_multi_navi)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
            <rosparam file="$(find carbot_multi_navi)/config/local_costmap_params.yaml" command="load" />
            <rosparam file="$(find carbot_multi_navi)/config/global_costmap_params.yaml" command="load" />
            <rosparam file="$(find carbot_multi_navi)/config/base_local_planner_params.yaml" command="load" />
    
            <!-- Set tf_prefix for frames explicity, overwriting defaults -->
            <!-- 注意下面sensor_frame的id改为自己机器人实际的传感器id,这里我的是雷达,在rplidar.xacro中为laser_link -->
            <param name="global_costmap/scan/sensor_frame" value="$(arg robot_namespace)/laser_link"/>
            <param name="global_costmap/obstacle_layer/scan/sensor_frame" value="$(arg robot_namespace)/laser_link"/>
            <param name="global_costmap/global_frame" value="$(arg global_frame_id)"/>
            <param name="global_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
            <param name="global_costmap/obstacle_layer/scan/topic" value="$(arg laser_topic)"/>
        
            <param name="local_costmap/scan/sensor_frame" value="$(arg robot_namespace)/laser_link"/>
            <param name="local_costmap/obstacle_layer/scan/sensor_frame" value="$(arg robot_namespace)/laser_link"/>
            <param name="local_costmap/global_frame" value="$(arg odom_frame_id)"/>
            <param name="local_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
            <param name="local_costmap/obstacle_layer/scan/topic" value="$(arg laser_topic)"/>
        
            <!-- 主题重映射 -->
            <remap from="cmd_vel" to="$(arg cmd_topic)"/>
            <remap from="odom" to="$(arg odom_topic)"/>
            <remap from="scan" to="$(arg laser_topic)"/>
            <remap from="map" to="/map"/>
        </node>
      </group>
</launch>

这样应该就没什么大问题了,有问题的继续往下看,也可以评论区留言交流。
 

四、趟坑指南

1.命名空间值如何传递

<param name="robot_description" command="$(find xacro)/xacro '$(find carbot_multi_navi)/urdf/carbot_gazebo.urdf.xacro' ns:=xxx "/>
最初是不了解命名空间下的节点主题的规则,以为要手动添加前缀,于是想法设法想把ns值传递进urdf.xacro中,就是上面这条语句中的ns:=xxx,最终没能成功,也希望正在尝试的朋友不要这样做了,这在节点启动语句如rosrun node_xx ns:=xxx时确实可以传ns值进节点,但进urdf.xacro我是没成功过。
 

2.local_costmap/global_frame

这是move_base.launch中的某个参数param,刚开始因为到处搜教程cv过快,将其设置为 <param name="local_costmap/global_frame" value="$(arg global_frame_id)"/>,也就是map坐标(正确应是odom),到后面TF树死活连不起来,也是运气好吧,最终发现这个地方不对劲,哪里不对劲呢,你看这个参数就明白了<param name="global_costmap/global_frame" value="$(arg global_frame_id)"/>
 

3.机器人初始位置

在一个机器人导航的时候,我们可以地图选点初始化机器人,但在三个机器人一起导航的情况下,如果还是手动选点的话雷达扫描与实际地图误差会比较大,所以建议还是在amcl.launch中直接指定初始位置(注意第三个参数末尾是a),即

<param name="initial_pose_x" value="$(arg initial_pose_x)"/>
<param name="initial_pose_y" value="$(arg initial_pose_y)"/>
<param name="initial_pose_a" value="$(arg initial_pose_a)"/>

经过再次实验,机器人运动后哪怕初始位置不准,随着它的运动,会逐渐矫正雷达扫描,直到契合实际地图,但与其让它自己矫正为什么不直接给它一个初始定位呢。
 

4.gazebo仿真差速器

差速器的功能很重要,但它做的事有点过多了,不需要的我们最好关闭。
在这里插入图片描述
这里圈出了四个标签。其中rootnamespace一定要注释掉;publishWheelTF一定要设为false;publishTf不能关闭,必须设置为1或true。否则可能导致以下问题
publishWheelJointState我们有专门的joint_state_publisher节点,所以不需要这里再次发布。
 

5.rviz插件配置

rviz的配置文件是从别人代码里抄来的,没有注意,在点击2D Nav Goal地图选点后发布的主题带着别人原来预设的命名空间,跟自己的命名空间不同,也就无法正常导航,想在rviz中自己添加却发现找不到地方,最终在rviz配置文件中修改主题(搜索rviz/SetGoal)
在这里插入图片描述
在这里插入图片描述

五、缺陷

实测在小车导航到同一位置时会出现相撞,可能是小车模型同高,雷达监测不到的原因,待验证和改善。

;