ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Timed out waiting for transform from robot1/base_footprint to map ... tf error: canTransform: target_frame map does not exist

asked 2022-03-11 17:26:34 -0500

JustinPMaio gravatar image

updated 2022-04-17 10:31:56 -0500

lucasw gravatar image

I am continuing my project to have several robots navigate using a shared map.

Here are my updated launch files after making changes to have separate namespaces for each robot. Now my struggle is getting the map server to transform data which can feed the move_base.

file 1: navigation launch

<launch>
  <!-- Arguments -->
  <arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
  <arg name="open_rviz" default="true"/>
  <arg name="map_file" default="/home/in/GazeboHouseMap.yaml"/>
  <arg name="move_forward_only" default="false"/>
  <arg name="first_tb3"  default="robot1"/>
  <arg name="second_tb3" default="robot2"/>
  <arg name="third_tb3"  default="robot3"/>
  <arg name="multi_robot_name" default=""/>

  <!-- Turtlebot3 -->
  <group ns = "$(arg first_tb3)">
  <include file="$(find turtlebot3_bringup)/launch/turtlebot3_remote.launch">
    <arg name="model" value="waffle_pi" /> 
    <arg name="multi_robot_name" value="robot1" />
  </include>
  </group>
  <group ns = "$(arg second_tb3)">
  <include file="$(find turtlebot3_bringup)/launch/turtlebot3_remote.launch">
    <arg name="model" value="waffle_pi" /> 
    <arg name="multi_robot_name" value="robot2" />
  </include>
  </group>
  <group ns = "$(arg third_tb3)">
  <include file="$(find turtlebot3_bringup)/launch/turtlebot3_remote.launch">
    <arg name="model" value="burger" /> 
    <arg name="multi_robot_name" value="robot3" />
  </include>
  </group>

  <!-- Map server -->
  <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)">
    <param name="global_frame_id" value="map" />
  </node>

  <!-- AMCL -->
    <include file="$(find MoveOneOfThree)/launch/amcl_robot1.launch"/>
    <include file="$(find MoveOneOfThree)/launch/amcl_robot2.launch"/> 
    <include file="$(find MoveOneOfThree)/launch/amcl_robot3.launch"/> 

  <!-- MOVE_BASE -->
  <include file="$(find MoveOneOfThree)/launch/move_base_11.launch">
    <arg name="model" value="waffle_pi" />
    <arg name="move_forward_only" value="false"/>
  </include>
  <include file="$(find MoveOneOfThree)/launch/move_base_22.launch">
    <arg name="model" value="waffle_pi" />
    <arg name="move_forward_only" value="false"/>
  </include>
  <include file="$(find MoveOneOfThree)/launch/move_base_33.launch">
    <arg name="model" value="burger" />
    <arg name="move_forward_only" value="false"/>
  </include>

  <!-- rviz -->
  <group if="$(arg open_rviz)"> 
    <node pkg="rviz" type="rviz" name="rviz" required="true"
          args="-d $(find turtlebot3_navigation)/rviz/turtlebot3_navigation.rviz"/>
  </group>
</launch>

file 2: AMCL

<launch>
  <!-- Arguments -->
  <arg name="scan_topic"     default="/robot1/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"/>

  <!-- AMCL -->
  <group ns = "robot1">
  <node pkg="amcl" type="amcl" name="amcl">

    <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 ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2022-03-16 06:03:03 -0500

JustinPMaio gravatar image

updated 2022-04-17 10:32:12 -0500

lucasw gravatar image

What a month it has been but I FINALLY got it! The key piece I was missing was that even though the robots all share the same map, they each still need their own map server. I updated the section as follows:

  <!-- Map server -->
<group ns = "$(arg first_tb3)">
  <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)">
    <param name="global_frame_id" value="map" />
  </node>
  </group>
<group ns = "$(arg second_tb3)">
  <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)">
    <param name="global_frame_id" value="map" />
  </node>
  </group>
<group ns = "$(arg third_tb3)">
  <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)">
    <param name="global_frame_id" value="map" />
  </node>
  </group>

I also had to give each robot their own set of params for the move_base file. All the params that look like this <rosparam file="$(find turtlebot3_navigation)/param/local_costmap_params.yaml" command="load"/> have to be updated so that they use the correct frame with namespace preceding base_link, etc.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2022-03-11 17:26:34 -0500

Seen: 531 times

Last updated: Apr 17 '22