38 #ifndef MAP_GRID_COST_FUNCTION_H_ 39 #define MAP_GRID_COST_FUNCTION_H_ 78 bool is_local_goal_function =
false,
86 void setTargetPoses(std::vector<geometry_msgs::PoseStamped> target_poses);
double unreachableCellCosts()
double scoreTrajectory(Trajectory &traj)
double xshift_
xshift and yshift allow scoring for different
double unreachableCellCosts()
MapGridCostFunction(costmap_2d::Costmap2D *costmap, double xshift=0.0, double yshift=0.0, bool is_local_goal_function=false, CostAggregationType aggregationType=Last)
void setStopOnFailure(bool stop_on_failure)
If true, failures along the path cause the entire path to be rejected.
A grid of MapCell cells that is used to propagate path and goal distances for the trajectory controll...
base_local_planner::MapGrid map_
CostAggregationType aggregationType_
void setTargetPoses(std::vector< geometry_msgs::PoseStamped > target_poses)
Provides an interface for critics of trajectories During each sampling run, a batch of many trajector...
void setYShift(double yshift)
bool is_local_goal_function_
double getCellCosts(unsigned int cx, unsigned int cy)
std::vector< geometry_msgs::PoseStamped > target_poses_
void setXShift(double xshift)
costmap_2d::Costmap2D * costmap_
Holds a trajectory generated by considering an x, y, and theta velocity.