Multiple robots simulation in Stage with amcl navigation
Hi,
I am trying to set two robots on the map and use amcl navigation for each of them. As a role model, I used this question (it deals with the same situation in Gazebo).
After creating a .yaml and .world files with a map and two robots on it, I created a launch file that uses namespaces and tf_prefix.
The final list of topics is as expected.
The trouble is with frames: there is no /map frame, nor the link from it to robot_0/odom and robot_1/odom. As far as I know, the responsibility for publishing that frame is on amcl but can't figure out why it fails to publish it. (The warning received is:
Timed out waiting for transform from robot_0/base_footprint to map to become available before running costmap, tf error: . canTransform returned after 0.1 timeout was 0.1.
UPDATE: managed to make it work with fake localization (by taking this example as is and adding custom .yaml and .world files. The question remains: how to add amcl into it? If I use fake_localization for one robot, and amcl for the other one, the tf tree looks like this
Please, help me with any hint on how frames actually work and why could it be that there is transformation from /map frame to robot_0/odom (the one that uses amcl)
The launch files are is as below:
<launch>
<arg name="map_file" default=" $(find demo_1)/stageSetup/maze.yaml" />
<arg name="world_file" default="$(find demo_1)/stageSetup/stage/maze.world" />
<master auto="start" />
<param name="/use_sim_time" value="true" />
<node pkg="map_server" type="map_server" name="map_server" args="$(arg map_file)"
respawn="false">
<param name="frame_id" value="/map" />
</node>
<node pkg="stage_ros" type="stageros" name="stageros"
args="$(arg world_file)"
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>
-->
<node pkg="amcl" type="amcl" name="amcl" output="screen">
<remap from="static_map" to="/static_map"/>
<remap from="map" to="/map"/>
</node>
</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 ...