46 : costmap_(costmap), sum_scores_(false) {
47 if (costmap != NULL) {
80 ROS_ERROR(
"Footprint spec is empty, maybe missing call to setFootprint?");
103 double vmag = hypot(traj.
xv_, traj.
yv_);
108 if (vmag > scaling_speed) {
110 double ratio = (vmag - scaling_speed) / (max_trans_vel - scaling_speed);
111 scale = max_scaling_factor * ratio + 1.0;
121 std::vector<geometry_msgs::Point> footprint_spec,
127 double footprint_cost = world_model->
footprintCost(x, y, th, footprint_spec);
129 if (footprint_cost < 0) {
132 unsigned int cell_x, cell_y;
135 if ( ! costmap->
worldToMap(x, y, cell_x, cell_y)) {
139 double occ_cost = std::max(std::max(0.0, footprint_cost),
double(costmap->
getCost(cell_x, cell_y)));
void setFootprint(std::vector< geometry_msgs::Point > footprint_spec)
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)=0
Subclass will implement this method to check a footprint at a given position and orientation for lega...
base_local_planner::WorldModel * world_model_
static double getScalingFactor(Trajectory &traj, double scaling_speed, double max_trans_vel, double max_scaling_factor)
ObstacleCostFunction(costmap_2d::Costmap2D *costmap)
void getPoint(unsigned int index, double &x, double &y, double &th) const
Get a point within the trajectory.
static double footprintCost(const double &x, const double &y, const double &th, double scale, std::vector< geometry_msgs::Point > footprint_spec, costmap_2d::Costmap2D *costmap, base_local_planner::WorldModel *world_model)
unsigned char getCost(unsigned int mx, unsigned int my) const
double scoreTrajectory(Trajectory &traj)
unsigned int getPointsSize() const
Return the number of points in the trajectory.
An interface the trajectory controller uses to interact with the world regardless of the underlying w...
void setParams(double max_trans_vel, double max_scaling_factor, double scaling_speed)
double max_scaling_factor_
A class that implements the WorldModel interface to provide grid based collision checks for the traje...
std::vector< geometry_msgs::Point > footprint_spec_
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.