Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix multi robot example of navigation_stage. #22

Open
wants to merge 6 commits into
base: indigo-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
56 changes: 22 additions & 34 deletions navigation_stage/launch/move_base_multi_robot.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,52 +3,40 @@
<param name="/use_sim_time" value="true"/>

<node pkg="map_server" type="map_server" name="map_server" args="$(find navigation_stage)/stage_config/maps/willow-full.pgm 0.1" respawn="false" >
<param name="frame_id" value="/map" />
<param name="frame_id" value="map" />
</node>

<node pkg="stage_ros" type="stageros" name="stageros" args="$(optenv ROS_STAGE_GRAPHICS -g) $(find navigation_stage)/stage_config/worlds/willow-pr2-multi.world" respawn="false">
<node pkg="stage_ros" type="stageros" name="stageros" args="$(find navigation_stage)/stage_config/worlds/willow-pr2-multi.world" respawn="false">
<param name="base_watchdog_timeout" value="0.2"/>
</node>

<!-- BEGIN ROBOT 0 -->
<group ns="robot_0">
<param name="tf_prefix" value="robot_0" />

<node pkg="move_base" type="move_base" respawn="false" name="move_base_node" output="screen">
<remap from="map" to="/map" />
<param name="controller_frequency" value="10.0" />
<rosparam file="$(find navigation_stage)/move_base_config/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find navigation_stage)/move_base_config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find navigation_stage)/move_base_config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find navigation_stage)/move_base_config/global_costmap_params.yaml" command="load" />
<rosparam file="$(find navigation_stage)/move_base_config/base_local_planner_params.yaml" command="load" />
</node>

<node pkg="fake_localization" type="fake_localization" name="fake_localization" respawn="false" output="screen">
<param name="odom_frame_id" value="robot_0/odom" />
<param name="base_frame_id" value="robot_0/base_link" />
</node>
<include file="$(find navigation_stage)/move_base_config/move_base.xml">
<arg name="tf_prefix" value="robot_0/" />
</include>

<include file="$(find navigation_stage)/move_base_config/amcl_node.xml">
<arg name="tf_prefix" value="robot_0/" />
<arg name="initial_pose_x" value="47.0" />
<arg name="initial_pose_y" value="21.0" />
<arg name="initial_pose_a" value="-1.2" />
</include>
</group>
<!-- END ROBOT 0 -->

<!-- BEGIN ROBOT 1 -->
<group ns="robot_1">
<param name="tf_prefix" value="robot_1" />

<node pkg="move_base" type="move_base" respawn="false" name="move_base_node" output="screen">
<remap from="map" to="/map" />
<param name="controller_frequency" value="10.0" />
<rosparam file="$(find navigation_stage)/move_base_config/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find navigation_stage)/move_base_config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find navigation_stage)/move_base_config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find navigation_stage)/move_base_config/global_costmap_params.yaml" command="load" />
<rosparam file="$(find navigation_stage)/move_base_config/base_local_planner_params.yaml" command="load" />
</node>

<node pkg="fake_localization" type="fake_localization" name="fake_localization" respawn="false">
<param name="odom_frame_id" value="robot_1/odom" />
<param name="base_frame_id" value="robot_1/base_link" />
</node>
<include file="$(find navigation_stage)/move_base_config/move_base.xml">
<arg name="tf_prefix" value="robot_1/" />
</include>

<include file="$(find navigation_stage)/move_base_config/amcl_node.xml">
<arg name="tf_prefix" value="robot_1/" />
<arg name="initial_pose_x" value="48.0" />
<arg name="initial_pose_y" value="21.0" />
<arg name="initial_pose_a" value="-1.2" />
</include>
</group>
<!-- END ROBOT 1 -->

Expand Down
17 changes: 13 additions & 4 deletions navigation_stage/move_base_config/amcl_node.xml
Original file line number Diff line number Diff line change
@@ -1,9 +1,16 @@
<launch>
<arg name="tf_prefix" default=""/>
<arg name="initial_pose_x" default="12.0"/>
<arg name="initial_pose_y" default="26.0"/>
<arg name="initial_pose_a" default="0.0"/>
<!--
Example amcl configuration. Descriptions of parameters, as well as a full list of all amcl parameters, can be found at http://www.ros.org/wiki/amcl.
-->
<node pkg="amcl" type="amcl" name="amcl" respawn="true">
<remap from="scan" to="base_scan" />
<remap from="map" to="/map" />
<remap from="map_metadata" to="/map_metadata" />
<remap from="static_map" to="/static_map" />
<!-- Publish scans from best pose at a max of 10 Hz -->
<param name="odom_model_type" value="omni"/>
<param name="odom_alpha5" value="0.1"/>
Expand Down Expand Up @@ -31,14 +38,16 @@
<param name="laser_likelihood_max_dist" value="2.0"/>
<param name="update_min_d" value="0.2"/>
<param name="update_min_a" value="0.5"/>
<param name="odom_frame_id" value="odom"/>
<param name="odom_frame_id" value="$(arg tf_prefix)odom"/>
<param name="base_frame_id" value="$(arg tf_prefix)base_link"/>
<param name="global_frame_id" value="map"/>
<param name="resample_interval" value="1"/>
<param name="transform_tolerance" value="0.1"/>
<param name="recovery_alpha_slow" value="0.0"/>
<param name="recovery_alpha_fast" value="0.0"/>
<param name="initial_pose_x" value="12.0" />
<param name="initial_pose_y" value="26.0" />
<param name="initial_pose_a" value="0.0" />
<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="initial_cov_xx" value="0.5" />
<param name="initial_cov_yy" value="0.5" />
<param name="initial_cov_aa" value="0.1" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
global_costmap:
#Set the global and robot frames for the costmap
global_frame: map
robot_base_frame: base_link
robot_base_frame: $(arg tf_prefix)base_link

#Set the update and publish frequency of the costmap
update_frequency: 5.0
Expand Down
4 changes: 2 additions & 2 deletions navigation_stage/move_base_config/local_costmap_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,8 @@ local_costmap:
publish_voxel_map: true

#Set the global and robot frames for the costmap
global_frame: odom
robot_base_frame: base_link
global_frame: $(arg tf_prefix)odom
robot_base_frame: $(arg tf_prefix)base_link

#Set the update and publish frequency of the costmap
update_frequency: 5.0
Expand Down
14 changes: 8 additions & 6 deletions navigation_stage/move_base_config/move_base.xml
Original file line number Diff line number Diff line change
@@ -1,8 +1,10 @@
<launch>
<arg name="tf_prefix" default=""/>
<!--
Example move_base configuration. Descriptions of parameters, as well as a full list of all amcl parameters, can be found at http://www.ros.org/wiki/move_base.
-->
<node pkg="move_base" type="move_base" respawn="false" name="move_base_node" output="screen">
<remap from="map" to="/map" />
<param name="footprint_padding" value="0.01" />
<param name="controller_frequency" value="10.0" />
<param name="controller_patience" value="3.0" />
Expand All @@ -14,13 +16,13 @@
<param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
-->

<rosparam file="$(find navigation_stage)/move_base_config/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find navigation_stage)/move_base_config/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find navigation_stage)/move_base_config/local_costmap_params.yaml" command="load" />
<rosparam file="$(find navigation_stage)/move_base_config/global_costmap_params.yaml" command="load" />
<rosparam file="$(find navigation_stage)/move_base_config/base_local_planner_params.yaml" command="load" />
<rosparam file="$(find navigation_stage)/move_base_config/costmap_common_params.yaml" command="load" ns="global_costmap" subst_value="True" />
<rosparam file="$(find navigation_stage)/move_base_config/costmap_common_params.yaml" command="load" ns="local_costmap" subst_value="True" />
<rosparam file="$(find navigation_stage)/move_base_config/local_costmap_params.yaml" command="load" subst_value="True" />
<rosparam file="$(find navigation_stage)/move_base_config/global_costmap_params.yaml" command="load" subst_value="True" />
<rosparam file="$(find navigation_stage)/move_base_config/base_local_planner_params.yaml" command="load" subst_value="True" />
<!--
<rosparam file="$(find navigation_stage)/move_base_config/dwa_local_planner_params.yaml" command="load" />
<rosparam file="$(find navigation_stage)/move_base_config/dwa_local_planner_params.yaml" command="load" subst_value="True" />
-->
</node>
</launch>
Loading