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

inscribed and circumscribed radii of the robot used despite footprint being set

asked 2013-05-06 20:55:40 -0500

Ernest gravatar image

updated 2014-01-28 17:16:27 -0500

ngrennan gravatar image

Hi,

I've declared my robot's footprint in my common costmap params:

footprint: [[-0.7,-0.45], [0.70,-0.45],[0.70, 0.45],[-0.70, 0.45]]

and so I haven't set inscribed or circumscribed radii, because those can be figured out from my footprint.

Nevertheless, when I run move_base I get this warning:

[ WARN] [1367908257.219539023, 2.000000000]: You have set an inflation radius that is less than the inscribed and circumscribed radii of the robot. This is dangerous and could casue the robot to hit obstacles. Please change your inflation radius setting appropraitely.

Any idea why? Can I safely ignore this warning?

Thanks,

Ernest

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
3

answered 2013-05-09 02:06:46 -0500

updated 2013-05-09 02:21:05 -0500

This is a bogus warning stemming from a bug in costmap2d. You can safely ignore it. (you can sometimes safely ignore it, see update below). When you set a robot footprint, costmap2d computes inscribed and circumscribed radii from the footprint, so you it doesn't make sense to set these parameters yourself. However, the warning is issued before the computation. I've issued a pull request to fix that:

https://github.com/ros-planning/navigation/pull/43

(I've also included your change in wording, David.)

Update: I just realized that what I wrote above is not quite correct. By "bogus warning" I mean that costmap2d issues that warning even when your inflation radius is safe; my pull request fixes that.

However, of course you need to set an inflation radius which is greater than both your inscribed and circumscribed radii. Your circumscribed radius is sqrt(0.7^2 + 0.45^2) = 0.83, so your inflation radius needs to be >= 0.84.

edit flag offensive delete link more

Comments

Thank you Martin.

Ernest gravatar image Ernest  ( 2013-05-09 14:57:46 -0500 )edit
1

answered 2013-05-08 18:38:06 -0500

David Lu gravatar image

If you don't set the value of inflation_radius, it will be automatically set to 0.55. The error message probably should read "You have set an inflation radius that is less than the inscribed OR circumscribed radii...". Since the circumscribed radius is .7 in this case, an inflation radius of 0.55 is problematic.

Quick Fix: set the inflation radius to >= .55.

edit flag offensive delete link more

Comments

Math is hard. It should be .83 as Martin points out.

David Lu gravatar image David Lu  ( 2013-05-09 07:43:31 -0500 )edit

Question Tools

Stats

Asked: 2013-05-06 20:55:40 -0500

Seen: 1,660 times

Last updated: May 09 '13