Uses costmap 2d to assign negative costs if robot footprint is in obstacle on any point of the trajectory. More...
#include <obstacle_footprint.h>
Public Member Functions | |
double | getScale () const override |
void | onInit () override |
bool | prepare (const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) override |
double | scorePose (const nav_core2::Costmap &costmap, const geometry_msgs::Pose2D &pose) override |
Return the obstacle score for a particular pose. | |
virtual double | scorePose (const nav_core2::Costmap &costmap, const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Polygon2D &oriented_footprint) |
Protected Attributes | |
nav_2d_msgs::Polygon2D | footprint_spec_ |
Uses costmap 2d to assign negative costs if robot footprint is in obstacle on any point of the trajectory.
Internally, this technically only checks if the border of the footprint collides with anything for computational efficiency. This is valid if the obstacles in the local costmap are inflated.
A more robust class could check every cell within the robot's footprint without inflating the obstacles, at some computational cost. That is left as an excercise to the reader.
Definition at line 55 of file obstacle_footprint.h.
double dwb_critics::ObstacleFootprintCritic::getScale | ( | ) | const [inline, override, virtual] |
Reimplemented from dwb_local_planner::TrajectoryCritic.
Definition at line 64 of file obstacle_footprint.h.
void dwb_critics::ObstacleFootprintCritic::onInit | ( | ) | [override, virtual] |
Reimplemented from dwb_critics::BaseObstacleCritic.
Definition at line 50 of file obstacle_footprint.cpp.
bool dwb_critics::ObstacleFootprintCritic::prepare | ( | const geometry_msgs::Pose2D & | pose, |
const nav_2d_msgs::Twist2D & | vel, | ||
const geometry_msgs::Pose2D & | goal, | ||
const nav_2d_msgs::Path2D & | global_plan | ||
) | [override, virtual] |
Reimplemented from dwb_local_planner::TrajectoryCritic.
Definition at line 56 of file obstacle_footprint.cpp.
double dwb_critics::ObstacleFootprintCritic::scorePose | ( | const nav_core2::Costmap & | costmap, |
const geometry_msgs::Pose2D & | pose | ||
) | [override, virtual] |
Return the obstacle score for a particular pose.
costmap | Dereferenced costmap |
pose | Pose to check |
Reimplemented from dwb_critics::BaseObstacleCritic.
Definition at line 67 of file obstacle_footprint.cpp.
double dwb_critics::ObstacleFootprintCritic::scorePose | ( | const nav_core2::Costmap & | costmap, |
const geometry_msgs::Pose2D & | pose, | ||
const nav_2d_msgs::Polygon2D & | oriented_footprint | ||
) | [virtual] |
Definition at line 75 of file obstacle_footprint.cpp.
nav_2d_msgs::Polygon2D dwb_critics::ObstacleFootprintCritic::footprint_spec_ [protected] |
Definition at line 66 of file obstacle_footprint.h.