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

Timed out waiting for transform from base_footprint to map to become available before running costmap, tf error: canTransform: source_frame base_footprint does not exist.

asked 2021-11-12 07:25:43 -0500

WarTurtle gravatar image

updated 2022-03-08 06:57:15 -0500

lucasw gravatar image

Hello, I am trying to launch a navigation stack on multiple robots, so they can navigate autonomously in gazebo. I have cloned the following turtlebot3 githubs to access models, descriptions, costmaps, and how to set up the launch files.

https://github.com/ROBOTIS-GIT/turtlebot3/tree/melodic-devel
https://github.com/ROBOTIS-GIT/turtlebot3_simulations/tree/melodic-devel
https://github.com/ROBOTIS-GIT/turtlebot3_msgs/tree/melodic-devel

My problem is that when I add namespaces for the robots, the following error occurs.

Timed out waiting for transform from base_footprint to map to become available before running costmap, tf error: canTransform: source_frame base_footprint does not exist.

I have placed everything in a single launch file to make it easier to troubleshoot:

<launch>
<!-- Model and namespace-->
  <arg name="model"       default="burger"/>  <!-- Model, change for process/products -->
  <arg name="robot"       default="bot"/>     <!-- Name space, change for each robot  -->

<!-- Visualization and map location -->
  <arg name="map_file"    default="$(find gazebo_worlds)/maps/factory_map.yaml"/>
  <arg name="open_rviz"   default="true"/>
  <arg name="open_gazebo" default="true"/>

<!-- Positions -->
  <arg name="x_pos" default=" 0.0"/>
  <arg name="y_pos" default=" 0.0"/>
  <arg name="z_pos" default=" 0.0"/>
  <arg name="yaw"   default=" 1.57"/>

<!-- Robot group -->
  <group ns = "$(arg robot)">
    <param name="robot_description" command="$(find xacro)/xacro --inorder $(find turtlebot3_description)/urdf/turtlebot3_$(arg model).urdf.xacro" />

    <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
      <param name="publish_frequency" type="double" value="50.0" />
      <param name="tf_prefix" value="$(arg robot)" />
    </node>

    <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" args="-urdf -model $(arg robot) -x $(arg x_pos) -y $(arg y_pos) -z $(arg z_pos) -Y $(arg yaw) -param robot_description" />
  </group>

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

<!-- Tf transformer -->
  <node pkg="tf" type="static_transform_publisher" name="world_to_$(arg robot)_tf_broadcaster"  args="0 0 0 0 0 0 /map /$(arg robot)/map 100"/>

<!-- AMCL -->
  <node pkg="amcl" type="amcl" name="$(arg robot)_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 x_pos)"/>
    <param name="initial_pose_y"            value="$(arg y_pos)"/>
    <param name="initial_pose_a"            value="$(arg yaw)"/>
    <param name="gui_publish_rate"          value="50.0"/>

    <remap from="scan"                      to="$(arg robot)/scan"/>
    <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 ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-11-15 12:32:47 -0500

WarTurtle gravatar image

I made it work by doing this. First, a launch file to create the basics functionalities of each robot.

<launch>
  <!-- Variable Arguments -->
  <arg name="model"/> <!-- waffle_pi, waffle, burger-->
  <arg name="namespace"/>
  <arg name="initial_pose_x"/>
  <arg name="initial_pose_y"/>
  <arg name="initial_pose_a"     default="0.0"/>       <!-- yaw -->

  <!-- Static Arguments -->
  <arg name="move_forward_only" default="false"/>
  <arg name="use_map_topic"     default="false"/>
  <arg name="scan_topic"        default="$(arg namespace)/scan"/>
  <arg name="odom_frame_id"     default="$(arg namespace)/odom"/>
  <arg name="base_frame_id"     default="$(arg namespace)/base_footprint"/>
  <arg name="cmd_vel_topic"     default="$(arg namespace)/cmd_vel" />
  <arg name="odom_topic"        default="$(arg namespace)/odom" />
  <arg name="init_pose"         default="-x $(arg initial_pose_x) -y $(arg initial_pose_y) -z 0.0"/>
  <arg name="global_frame_id"   default="map"/>

  <!-- Create robots -->
  <param name="robot_description"
    command="$(find xacro)/xacro.py $(find deploy)/param/models/$(arg model).urdf.xacro" />

  <group ns="$(arg namespace)">
    <param name="tf_prefix"  value="$(arg namespace)"/>
    <node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model"
        args="$(arg init_pose) -urdf -param /robot_description -model $(arg namespace)"
        respawn="false" output="screen"/>

    <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen">
      <param name="publish_frequency" type="double" value="50.0" />
    </node>
  </group>

  <!-- AMCL -->
  <node pkg="amcl" type="amcl" name="$(arg namespace)_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)"/>

    <remap from="initialpose"               to="$(arg namespace)/initialpose"/>
    <remap from="amcl_pose"                 to="$(arg namespace)/amcl_pose"/>
    <remap from="particlecloud"             to="$(arg namespace)/particlecloud"/>
  </node>

  <!-- move_base -->
  <node pkg="move_base" type="move_base" respawn="false" name="$(arg namespace)_move_base" output="screen">
    <param name="base_local_planner" value="dwa_local_planner/DWAPlannerROS" />
    <param name="DWAPlannerROS/min_vel_x" value ...
(more)
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2021-11-12 07:25:43 -0500

Seen: 157 times

Last updated: Nov 15 '21