50 void ObstacleFootprintCritic::onInit()
52 BaseObstacleCritic::onInit();
56 bool ObstacleFootprintCritic::prepare(
const geometry_msgs::Pose2D& pose,
const nav_2d_msgs::Twist2D& vel,
57 const geometry_msgs::Pose2D& goal,
const nav_2d_msgs::Path2D& global_plan)
59 if (footprint_spec_.points.size() == 0)
61 ROS_ERROR_NAMED(
"ObstacleFootprintCritic",
"Footprint spec is empty, maybe missing call to setFootprint?");
67 double ObstacleFootprintCritic::scorePose(
const nav_core2::Costmap& costmap,
const geometry_msgs::Pose2D& pose)
69 unsigned int cell_x, cell_y;
75 double ObstacleFootprintCritic::scorePose(
const nav_core2::Costmap& costmap,
const geometry_msgs::Pose2D& pose,
76 const nav_2d_msgs::Polygon2D& footprint)
78 unsigned char footprint_cost = 0;
82 unsigned char cost = costmap(index.x, index.y);
92 footprint_cost = std::max(cost, footprint_cost);
96 return footprint_cost;
nav_2d_msgs::Polygon2D footprintFromParams(ros::NodeHandle &nh, bool write=true)
static const unsigned char NO_INFORMATION
#define ROS_ERROR_NAMED(name,...)
static const unsigned char LETHAL_OBSTACLE
nav_2d_msgs::Polygon2D movePolygonToPose(const nav_2d_msgs::Polygon2D &polygon, const geometry_msgs::Pose2D &pose)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)