rosbook / effective_robotics_programming_with_ros

Effective Robotics Programming with ROS
https://www.packtpub.com/hardware-and-creative/effective-robotics-programming-ros-third-edition
233 stars 154 forks source link

Chapter 6: Creating a launch file for the navigation stack error: tf error: canTransform: target_frame map does not exist #9

Open RahmanMifta opened 6 years ago

RahmanMifta commented 6 years ago

Hi, I am learning ros by following "Effective Robotics Programming with ROS" and codes from github. As per the instructions in the book, i have run two launch file (chapter6_configuration_gazebo.launch and move_base.launch) in two separate terminal included in "chpater6_tutorials/launch" folder. But i am facing few errors:

  1. No laser scan received (and thus no pose updates have been published) for 96.852000 seconds. Verify that data is being published on the /scan topic.
  2. Timed out waiting for transform from base_footprint to map to become available before running costmap, tf error: canTransform: target_frame map does not exist.. canTransform returned after 0.102 timeout was 0.1.

I have attached the screen-shot of error file, tf frames, and rqt_graph.

rosgraph

frames

errors

efernandez commented 6 years ago

Likely a duplicate of https://github.com/rosbook/effective_robotics_programming_with_ros/issues/4

Will look into it asap.

huabench commented 5 years ago

I had the same problem and have got it solved.

  1. check robot model for me it is "robot1_description/urdf/robot1_base_04.xacro"
  2. open the xacro file and check gazebo tag (at the bottom of this file) what I saw is:
<gazebo>
    <plugin name="skid_steer_drive_controller"....>
    ...
    <robotBaseFrame>base_link</robotBaseFrame>
    ...
    <broadcastTF>0</broadcastTF>
..
</gazebo>
  1. change "base_link" to "base_footprint" and change "0" to "1"

Reasons:

  1. the root link of robot1 is base_footprint, and the correct tf tree should be:

    map -> odom-> base_footprint -> base_link

    If "base_link" be the robotBaseFrame, it(base_link) will have two parents(base_footprint and odom), which is invalid.

  2. broadcastTF determines whether skid_steer_drive_controller will publish tf transform between odomFrame and robotBaseFrame.

    Find details in https://github.com/ros-simulation/gazebo_ros_pkgs/blob/kinetic-devel/gazebo_plugins/src/gazebo_ros_skid_steer_drive.cpp

    if (!_sdf->HasElement("broadcastTF")) {
         ... } // if "broadcastTF" is not existed
    else // if "broadcastTF" exsits, get the value
      this->broadcast_tf_ = _sdf->GetElement("broadcastTF")->Get<bool>();
    if (this->broadcast_tf_) { 
        transform_broadcaster_->sendTransform(
           tf::StampedTransform(base_footprint_to_odom, current_time,
               odom_frame, base_footprint_frame));
       }