[ros-users] Cost function in base_local_planner

Eitan Marder-Eppstein eitan at willowgarage.com
Thu Jun 3 17:24:55 UTC 2010


Advait,

I've answered inline:

On Wed, Jun 2, 2010 at 10:23 PM, Advait Jain <advait at cc.gatech.edu> wrote:

> How is the maximum obstacle cost along the forward simulated trajectory
> computed by the base_local_planner?
> http://www.ros.org/wiki/base_local_planner#Trajectory_Scoring_Parameters
>

The maximum obstacle cost is computed by discretely sampling the trajectory
at a resolution specified by the "sim_granularity" parameter and taking the
maximum obstacle cost of any point sampled.


> Does it come from the costmap with the robot treated as a point?
>

In the case that the robot is circular... yes, but in the case that a
footprint is specified it actually comes from the maximum cost of any point
on the robot's footprint when it is rasterized into the grid. (In looking at
this, I actually found a bug where I was returning the maximum cost of the
last line in the robot's footprint rasterized into the grid instead of the
overall cost, but that will be fixed in the next release which I hope to
push out later today)


>
> Does this mean that the actual footprint of the robot gets used only via
> the radii of the incircle and circumcircle?
>

This used to be the case, but now the footprint of the robot is rasterized
into the grid every time. There is a performance penalty to this and I'm
having a bit of trouble remembering why we switched away from using the
inner and outer circles as an efficient first check. If I remember
correctly, with the inner circle, there's the chance that you may be
pessimistic by using it because the robot isn't exactly centered in the cell
that it maps to in the costmap. So, you may actually map to a cell that has
the cost of an obstacle inflated by the inscribed radius of the robot when
your footprint doesn't actually hit the obstacle. In rare cases, this will
keep you from being able to move through very tight spaces. For the
circumscribed radius, there's the opposite problem that could cause you to
hit things in rare cases. Overall, it runs fast enough for us with the
explicit laydown, but there's also room to write a collision detection
module that makes the efficiency checks.


>
> If I set the inflation radius to be less than the circumscribed radius (but
> greater than the inscribed radius), is it possible for the robot to collide
> with obstacles?
>

With the default collision model, this shouldn't be possible, but given that
can always be swapped out for something where the robot could collide quite
easily, the costmap will always warn you when you run with an inflation
radius that is less than either the circumscribed or inscribed radius of the
robot.

>
>
> Advait
>


Hope this helps and that all is well,

Eitan


> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20100603/3178924b/attachment-0003.html>


More information about the ros-users mailing list