45 bool is_local_goal_function,
48 map_(costmap->getSizeInCellsX(), costmap->getSizeInCellsY()),
49 aggregationType_(aggregationType),
52 is_local_goal_function_(is_local_goal_function),
53 stop_on_failure_(true) {}
71 double grid_dist =
map_(px, py).target_dist;
81 unsigned int cell_x, cell_y;
94 px = px +
yshift_ * cos(pth + M_PI_2);
95 py = py +
yshift_ * sin(pth + M_PI_2);
double unreachableCellCosts()
double scoreTrajectory(Trajectory &traj)
void setTargetCells(const costmap_2d::Costmap2D &costmap, const std::vector< geometry_msgs::PoseStamped > &global_plan)
Update what cells are considered path based on the global plan.
double xshift_
xshift and yshift allow scoring for different
MapGridCostFunction(costmap_2d::Costmap2D *costmap, double xshift=0.0, double yshift=0.0, bool is_local_goal_function=false, CostAggregationType aggregationType=Last)
void getPoint(unsigned int index, double &x, double &y, double &th) const
Get a point within the trajectory.
base_local_planner::MapGrid map_
unsigned int getPointsSize() const
Return the number of points in the trajectory.
CostAggregationType aggregationType_
void setTargetPoses(std::vector< geometry_msgs::PoseStamped > target_poses)
bool is_local_goal_function_
double getCellCosts(unsigned int cx, unsigned int cy)
void setLocalGoal(const costmap_2d::Costmap2D &costmap, const std::vector< geometry_msgs::PoseStamped > &global_plan)
Update what cell is considered the next local goal.
std::vector< geometry_msgs::PoseStamped > target_poses_
void resetPathDist()
reset path distance fields for all cells
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
costmap_2d::Costmap2D * costmap_
Holds a trajectory generated by considering an x, y, and theta velocity.