0
$\begingroup$

Rosanswers logo

I've been trying to increase the inflation radius of obstacles in the local_costmap for move_base. The problem that I've noticed is that the inflation radius as viewed by Costmap2dPublisher never changes. Using rosparam get, I verified that the inflation_radius parameter was correctly set, but even setting this value as high as 10m has no effect. It seems that the inflation radius of the obstacles is directly linked to the circumscribed radius of the robot footprint.

If I set the robot footprint to a 0.5m x 0.5m box, the inflation radius is 0.25m. If I set the robot footprint to a 0.8m x 0.8m box, the inflation radius is 0.4m. From the documentation on costmap_2d, it seemed that I could set my own inflation radius, but I've been unable to do so.

I would like to be able to set two different values for the footprint and the inflation_radius. How can I go about doing so?


Originally posted by DimitriProsser on ROS Answers with karma: 11163 on 2012-02-03

Post score: 10

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

I had similar confusion when I first went to configure the costmap to inflate differently.

The inflation_radius is actually the radius to which the cost scaling function is applied, not a parameter of the cost scaling function. Inside the inflation radius, the cost scaling function is applied, but outside the inflation radius, the cost of a cell is not inflated using the cost function.

Take a look at the documentation for the cost_scaling_factor. What you have to do is basically solve the equation there ( exp(-1.0 * cost_scaling_factor * (distance_from_obstacle - inscribed_radius)) * (costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1)) for the correct cost_scaling_factor, using your distance from obstacle and the cost value you want that cell to have.

You'll have to make sure to set the inflation radius large enough that it includes the distance you need the cost function to be applied out to, as anything outside the inflation_radius will not have the cost function applied.


Originally posted by Eric Perko with karma: 8406 on 2012-02-03

This answer was ACCEPTED on the original site

Post score: 13


Original comments

Comment by Eric Perko on 2012-02-06:
I'm not sure where you can get the inscribed_radius directly, since it's calculated from the robot footprint. It might get printed as a debug statement somewhere. I think I just calculated it by hand. Might be useful to open a ticket to print out debugs with this if costmap_2d doesn't already.

Comment by DimitriProsser on 2012-02-03:
That makes sense. Where can I obtain the value of "inscribed_radius"? Also, is there a way to get Rviz to account for this change? While I can see the cost values changing (by accessing the costmap directly), Rviz still limits inflation to the size of the robot footprint.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.