ROS实战之多turtlebot2导航
多机器人的主从机配置可以参考我的上一个博客,接下来实现多机器人在同一地图下的导航。
1.配置launch文件
不同机器人应具有不同的命名空间,这样使得发布话题不会紊乱,就比如两个turtlebot发布的一样,到底控制哪个呢?因此命名空间的配置在多机器人建图和导航的过程中非常重要,具体配置可以参考上一个博客。
多机器人导航的launch文件(multi_navigation.launch)如下:
<launch>
<!-- Arguments -->
<arg name="open_rviz" default="true"/>
<arg name="move_forward_only" default="false"/>
<arg name="first_tb2" default="tb2_0"/>
<arg name="second_tb2" default="tb2_1"/>
<!-- Map server -->
<arg name="map_file" default="$(find turtlebot_navigation)/maps/cloister_gmapping.yaml"/>
<node pkg="map_server" name="map_server" type="map_server" args="$(arg map_file)"/>
<group ns = "$(arg first_tb2)">
<!-- Map server -->
<node pkg="map_server" name="map_server" type="map_server" args="$(arg map_file)"/>
<!-- Turtlebot2 -->
<include file="$(find turtlebot_bringup)/launch/m_turtlebot_remote.launch">
<arg name="model" value="$(arg model)" />
<arg name="multi_robot_name" value="$(arg first_tb2)" />
</include>
<arg name="first_tb2_x_pos" default="2.0"/>
<arg name="first_tb2_y_pos" default="-0.5"/>
<arg name="first_tb2_z_pos" default="0.0"/>
<!-- AMCL -->
<include file="$(find turtlebot_navigation)/launch/multi_amcl.launch">
<arg name="global_frame_id" value="map"/>
<arg name="odom_frame_id" value="$(arg first_tb2)/odom"/>
<arg name="base_frame_id" value="$(arg first_tb2)/base_footprint"/>
<arg name="initial_pose_x" value="$(arg first_tb2_x_pos)"/>
<arg name="initial_pose_y" value="$(arg first_tb2_y_pos)"/>
<arg name="initial_pose_a" value="$(arg first_tb2_z_pos)"/>
</include>
<!-- move_base -->
<include file="$(find turtlebot_navigation)/launch/multi_move_base.launch">
<arg name="global_frame_id" value="map"/>
<arg name="odom_frame_id" value="$(arg first_tb2)/odom"/>
<arg name="base_frame_id" value="$(arg first_tb2)/base_footprint"/>
<arg name="odom_topic" value="/$(arg first_tb2)/odom" />
<arg name="laser_topic" value="/$(arg first_tb2)/scan" />
<arg name="cmd_vel_topic" value="/$(arg first_tb2)/cmd_vel" />
<arg name="model" value="$(arg model)" />
<arg name="move_forward_only" value="$(arg move_forward_only)"/>
</include>
</group>
<group ns = "$(arg second_tb2)">
<!-- Map server -->
<node pkg="map_server" name="map_server" type="map_server" args="$(arg map_file)"/>
<!-- Turtlebot3 -->
<include file="$(find turtlebot_bringup)/launch/m_turtlebot_remote.launch">
<arg name="model" value="$(arg model)" />
<arg name="multi_robot_name" value="$(arg second_tb2)" />
</include>
<arg name="second_tb2_x_pos" default="2.0"/>
<arg name="second_tb2_y_pos" default="0.5"/>
<arg name="second_tb2_z_pos" default="0.0"/>
<!-- AMCL -->
<include file="$(find turtlebot_navigation)/launch/multi_amcl.launch">
<arg name="global_frame_id" value="map"/>
<arg name="odom_frame_id" value="$(arg second_tb2)/odom"/>
<arg name="base_frame_id" value="$(arg second_tb2)/base_footprint"/>
<arg name="initial_pose_x" value="$(arg second_tb2_x_pos)"/>
<arg name="initial_pose_y" value="$(arg second_tb2_y_pos)"/>
<arg name="initial_pose_a" value="$(arg second_tb2_z_pos)"/>
</include>
<!-- move_base -->
<include file="$(find turtlebot_navigation)/launch/multi_move_base.launch">
<arg name="global_frame_id" value="map"/>
<arg name="odom_frame_id" value="$(arg second_tb2)/odom"/>
<arg name="base_frame_id" value="$(arg second_tb2)/base_footprint"/>
<arg name="odom_topic" value="/$(arg second_tb2)/odom" />
<arg name="laser_topic" value="/$(arg second_tb2)/scan" />
<arg name="cmd_vel_topic" value="/$(arg second_tb2)/cmd_vel" />
<arg name="model" value="$(arg model)" />
<arg name="move_forward_only" value="$(arg move_forward_only)"/>
</include>
</group>
<!-- rviz -->
<group if="$(arg open_rviz)">
<node pkg="rviz" type="rviz" name="rviz" required="true"
args="-d $(find turtlebot_navigation)/rviz/multi_turtlebot_navigation.rviz"/>
</group>
</launch>
导航launch文件(multi_move_base.launch)如下:
<launch>
<!-- Arguments -->
<arg name="odom_frame_id" default="odom"/>
<arg name="base_frame_id" default="base_footprint"/>
<arg name="global_frame_id" default="map"/>
<arg name="cmd_vel_topic" default="/cmd_vel" />
<arg name="odom_topic" default="odom" />
<arg name="laser_topic" default="scan" />
<arg name="move_forward_only" default="false"/>
<!-- move_base -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<param name="base_global_planner" value="global_planner/GlobalPlanner"/>
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS"/>
<rosparam file="$(find turtlebot_navigation)/param/costmap_common_params_$(arg model).yaml" command="load" ns="global_costmap" />
<rosparam file="$(find turtlebot_navigation)/param/costmap_common_params_$(arg model).yaml" command="load" ns="local_costmap" />
<rosparam file="$(find turtlebot_navigation)/param/local_costmap_params.yaml" command="load" />
<rosparam file="$(find turtlebot_navigation)/param/global_costmap_params.yaml" command="load" />
<rosparam file="$(find turtlebot_navigation)/param/move_base_params.yaml" command="load" />
<rosparam file="$(find turtlebot_navigation)/param/dwa_local_planner_params_$(arg model).yaml" command="load" />
<!-- reset frame_id parameters using user input data -->
<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="local_costmap/global_frame" value="$(arg odom_frame_id)"/>
<param name="local_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/obstacle_layer/scan/topic" value="$(arg laser_topic)"/>
<remap from="cmd_vel" to="$(arg cmd_vel_topic)"/>
<remap from="odom" to="$(arg odom_topic)"/>
<remap from="scan" to="$(arg laser_topic)"/>
<param name="DWAPlanner/min_vel_x" value="0.0" if="$(arg move_forward_only)" />
</node>
</launch>
定位的launch文件(multi_amcl.launch)如下:
<launch>
<!-- Arguments -->
<arg name="use_map_topic" default="true"/>
<arg name="scan_topic" default="scan"/>
<arg name="initial_pose_x" default="0.0"/>
<arg name="initial_pose_y" default="0.0"/>
<arg name="initial_pose_a" default="0.0"/>
<arg name="odom_frame_id" default="odom"/>
<arg name="base_frame_id" default="base_footprint"/>
<arg name="global_frame_id" default="map"/>
<!-- AMCL -->
<node pkg="amcl" type="amcl" name="amcl">
<param name="use_map_topic" value="$(arg use_map_topic)"/>
<param name="min_particles" value="500"/>
<param name="max_particles" value="3000"/>
<param name="kld_err" value="0.02"/>
<param name="update_min_d" value="0.20"/>
<param name="update_min_a" value="0.20"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.5"/>
<param name="recovery_alpha_slow" value="0.00"/>
<param name="recovery_alpha_fast" value="0.00"/>
<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)"/>
<param name="gui_publish_rate" value="50.0"/>
<remap from="scan" to="$(arg scan_topic)"/>
<param name="laser_max_range" value="3.5"/>
<param name="laser_max_beams" value="180"/>
<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_likelihood_max_dist" value="2.0"/>
<param name="laser_model_type" value="likelihood_field"/>
<param name="odom_model_type" value="diff"/>
<param name="odom_alpha1" value="0.1"/>
<param name="odom_alpha2" value="0.1"/>
<param name="odom_alpha3" value="0.1"/>
<param name="odom_alpha4" value="0.1"/>
<param name="odom_frame_id" value="$(arg odom_frame_id)"/>
<param name="base_frame_id" value="$(arg base_frame_id)"/>
<param name="global_frame_id" value="$(arg global_frame_id)"/>
</node>
</launch>
2.启动launch文件配置rviz
启动multi_move_base.launch,然后配置rviz显示。效果如下图:
遇到的问题及解决:
1.tf信息错误
两个小车的tf变换中的节点名称不对,没有区分成tb2_0还是tb2_1.其次两个小车没有转换到一个map坐标系下,使得小车模型或者地图加载错误.
解决办法:
认真仔细修改tf变换,在launch文件中给小车对应的每个节点都加上属性,同时发布的话题也加上ns属性,保证tf树变换正确.
2.激光雷达扫描信息与地图不匹配
AMCL初始化位置中的激光扫描信息与实际地图不匹配,原因是激光雷达的坐标系与底盘坐标系有误差.
解决办法:
人为手动旋转激光雷达,保证激光雷达坐标系和底盘坐标系尽量一致;或者在launch文件中加入静态TF变换,给予尽量正确的外参.