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

move_base warning: "Unable to get starting pose of robot, unable to create global plan"

asked 2013-03-20 20:29:41 -0500

Hi, this is a problem extended from my previous post. Are both Gmapping and amcl publishing Map to Odom TF? I described my objective and my system there.

After some more testing, we have found that there is no problem if we use our own global path, launch the navigation package without both gmapping and amcl. The tf from map to odom is published by a static tf. The robot can move along with the global path, can generate local cost map and local path.

The problem is when we launch fake_localization, there is no global plan and it gives a warning "Unable to get starting pose of robot, unable to create global plan". This warning is from move-base.

  //get the starting pose of the robot
    tf::Stamped<tf::Pose> global_pose;
    if(!planner_costmap_ros_->getRobotPose(global_pose)) {
      ROS_WARN("Unable to get starting pose of robot, unable to create global plan");
      return false;
    }

I have checked the TF, the related topics such as base_link_ground_truth, amcl_pose, all correct.

I cannot figure it out .. The only difference is that the fake_localization is updated at a only 1 Hz in frequency.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2013-03-20 23:27:37 -0500

updated 2013-03-20 23:28:30 -0500

Solved. I have checked the getRobotPose function in costmap_2d_ros.cpp. start from line 1331

// check global_pose timeout
    if (current_time.toSec() - global_pose.stamp_.toSec() > transform_tolerance_) {
      ROS_WARN_THROTTLE(1.0, "Costmap2DROS transform timeout. Current time: %.4f, global_pose stamp: %.4f, tolerance: %.4f",
          current_time.toSec() ,global_pose.stamp_.toSec() ,transform_tolerance_);
      return false;
    }

So we increased the transform_tolerance, and finally it can get the robot pose and make global plan.

edit flag offensive delete link more

Comments

i just wondering how to increased the transform_tolerance

nancy_nan gravatar image nancy_nan  ( 2013-10-28 22:47:03 -0500 )edit

transform_tolerance is a parameter of the corresponding costmap. Simply change the value for this parameter.

Tones gravatar image Tones  ( 2016-01-07 06:11:39 -0500 )edit

I also solved the problem by increasing transform_tolerence. The transform_tolerence parameter is in the cost_common_param.yaml file of move_base.

Good luck. Thank you.

LEECHEOLWON gravatar image LEECHEOLWON  ( 2020-11-08 22:02:02 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2013-03-20 20:29:41 -0500

Seen: 8,163 times

Last updated: Mar 20 '13