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

dwa_local_planner: in place rotation FIRST goal does not work

asked 2015-03-11 05:51:22 -0500

fherrero gravatar image

updated 2015-03-13 03:15:15 -0500

When running the navigation with dwa_local_planner, and give the first goal as an in place rotation, the robot won't move (except for recovery behaviors), and gives the below output. But, if you give a translation goal first, it moves normally, and from then on, it can rotate in place without a problem.

[ERROR] [...]: Footprint spec is empty, maybe missing call to setFootprint?
[ WARN] [...]: Invalid Trajectory 0.000000, 0.000000, -0.401014, cost: -9.000000
[ WARN] [...]: Rotation cmd in collision
[ INFO] [...]: Error when rotating.

I think the error actually comes from line 80 in obstacle_cost_function.cpp at base_local_planner, something about the footprint is not properly initialized:

double ObstacleCostFunction::scoreTrajectory(Trajectory &traj) {
...
if (footprint_spec_.size() == 0) {
  // Bug, should never happen
  ROS_ERROR("Footprint spec is empty, maybe missing call to setFootprint?");
  return -9;
}
...

All this is easy to reproduce running, for example, turtlebot simulator and navigation amcl demo:

$ roslaunch turtlebot_gazebo turtlebot_world.launch
$ roslaunch turtlebot_gazebo amcl_demo.launch
$ roslaunch turtlebot_rviz_launchers view_navigation.launch

EDIT: The local costmap config used in the example above is the one from turtlebot packages, which can be found here: local_costmap_params.yaml

EDIT2: I use ROS Indigo on Ubuntu 14.04.2, but i've also tried with Hydro on 12.04. And yes, I have all installed via apt-get

edit retag flag offensive close merge delete

Comments

Can you add your local costmap config please

paulbovbel gravatar image paulbovbel  ( 2015-03-12 06:16:05 -0500 )edit

Please add information about which version of ROS. You installed navigation through apt-get?

paulbovbel gravatar image paulbovbel  ( 2015-03-12 15:33:28 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
4

answered 2015-03-26 06:52:08 -0500

Peter P. gravatar image

updated 2015-04-02 02:30:53 -0500

To me, it looks like a bug. The footprint of the robot is set on the ObstacleCostFunction whenever DWAPlanner::findBestPath is called (line 298 in https://github.com/ros-planning/navig... ). This call will not be made when the robot is already at the goal location when the goal is given. The LatchedStopRotateController then calls DWAPlanner::checkTrajectory to check for a valid rotation command and this checks the ObstacleCostFunction which needs the footprint, but it wasn't set before. To fix this issue, the footprint has to be set before the call to DWAPlanner::checkTrajectory is made.

I do have the same problem right now, which is why I looked into the sources to find the issue. But other than that, I have no idea about this package or why the footprint isn't set earlier (the cost map, which should know the footprint, is known in the constructor of DWAPlanner and even given to the ObstacleCostFunction upon construction, but the footprint is not extracted). I guess we should create a bugreport...

Edit: finally I did just that: https://github.com/ros-planning/navig...

edit flag offensive delete link more

Comments

Can you detail what you did to make it work ? i have the same problem as you, and i don't know where and what changes i should make.

Swan Baigne gravatar image Swan Baigne  ( 2015-05-18 02:11:40 -0500 )edit

Actually, I did not make it work, sorry that it sounded like that. I just figured out why this error occurs and created a ticket, hoping that it would be resolved by the project authors/maintainers.

Peter P. gravatar image Peter P.  ( 2015-05-18 02:44:50 -0500 )edit

i feared so. The link you gave is quite detailed, except i have not found the dwa_planner.cpp anywhere in my computer, so i have no may to make the mentioned modifications Looks like we will have to wait for maintener's answers

Swan Baigne gravatar image Swan Baigne  ( 2015-05-18 02:51:57 -0500 )edit

You can find the file at https://github.com/ros-planning/navig... . In order to change it, you have to clone the GIT repository into your workspace and build it yourself (and make sure that ROS uses that one over the installed package).

Peter P. gravatar image Peter P.  ( 2015-05-18 03:38:29 -0500 )edit

I noticed that my path never includes an initial in-place rotation. I think that it would frequently make sense for the robot to rotate before starting its translational move. Could the problem you're asking about cause the absence of an initial in-place rotation? Or is this just my parameters?

mitch gravatar image mitch  ( 2016-05-06 16:43:21 -0500 )edit
0

answered 2015-03-12 11:05:46 -0500

paulbovbel gravatar image

updated 2015-03-12 11:05:56 -0500

There may be a backwards compatibility issue. In the common costmap params, try setting the footprint directly instead of using a radius:

footprint: [[-0.325, -0.325], [-0.325, 0.325], [0.325, 0.325], [0.46, 0.0], [0.325, -0.325]] 
#robot_radius: 0.46
edit flag offensive delete link more

Comments

Just tried it, still the same. I noticed the local_costmap_params.yaml seems to be missing the footprint_layer plugin, but adding it didn't fix it either.

fherrero gravatar image fherrero  ( 2015-03-12 11:38:11 -0500 )edit
2

That's not necessary, the obstacle layer spawns it's own footprint layer.

paulbovbel gravatar image paulbovbel  ( 2015-03-13 06:49:46 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-03-11 05:51:22 -0500

Seen: 4,765 times

Last updated: Apr 02 '15