Uses costmap 2d to assign negative costs if robot footprint is in obstacle on any point of the trajectory. More...
#include <obstacle_cost_function.h>
Public Member Functions | |
ObstacleCostFunction (costmap_2d::Costmap2D *costmap) | |
bool | prepare () |
double | scoreTrajectory (Trajectory &traj) |
void | setFootprint (std::vector< geometry_msgs::Point > footprint_spec) |
void | setParams (double max_trans_vel, double max_scaling_factor, double scaling_speed) |
~ObstacleCostFunction () | |
Static Public Member Functions | |
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) |
static double | getScalingFactor (Trajectory &traj, double scaling_speed, double max_trans_vel, double max_scaling_factor) |
Private Attributes | |
costmap_2d::Costmap2D * | costmap_ |
std::vector< geometry_msgs::Point > | footprint_spec_ |
double | max_scaling_factor_ |
double | max_trans_vel_ |
double | scaling_speed_ |
base_local_planner::WorldModel * | world_model_ |
Uses costmap 2d to assign negative costs if robot footprint is in obstacle on any point of the trajectory.
class ObstacleCostFunction
Definition at line 54 of file obstacle_cost_function.h.
Definition at line 45 of file obstacle_cost_function.cpp.
Definition at line 51 of file obstacle_cost_function.cpp.
double base_local_planner::ObstacleCostFunction::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 | ||
) | [static] |
Definition at line 108 of file obstacle_cost_function.cpp.
double base_local_planner::ObstacleCostFunction::getScalingFactor | ( | Trajectory & | traj, |
double | scaling_speed, | ||
double | max_trans_vel, | ||
double | max_scaling_factor | ||
) | [static] |
Definition at line 94 of file obstacle_cost_function.cpp.
bool base_local_planner::ObstacleCostFunction::prepare | ( | ) | [virtual] |
General updating of context values if required. Subclasses may overwrite. Return false in case there is any error.
Implements base_local_planner::TrajectoryCostFunction.
Definition at line 69 of file obstacle_cost_function.cpp.
double base_local_planner::ObstacleCostFunction::scoreTrajectory | ( | Trajectory & | traj | ) | [virtual] |
return a score for trajectory traj
Implements base_local_planner::TrajectoryCostFunction.
Definition at line 73 of file obstacle_cost_function.cpp.
void base_local_planner::ObstacleCostFunction::setFootprint | ( | std::vector< geometry_msgs::Point > | footprint_spec | ) |
Definition at line 65 of file obstacle_cost_function.cpp.
void base_local_planner::ObstacleCostFunction::setParams | ( | double | max_trans_vel, |
double | max_scaling_factor, | ||
double | scaling_speed | ||
) |
Definition at line 58 of file obstacle_cost_function.cpp.
Definition at line 78 of file obstacle_cost_function.h.
std::vector<geometry_msgs::Point> base_local_planner::ObstacleCostFunction::footprint_spec_ [private] |
Definition at line 79 of file obstacle_cost_function.h.
double base_local_planner::ObstacleCostFunction::max_scaling_factor_ [private] |
Definition at line 83 of file obstacle_cost_function.h.
double base_local_planner::ObstacleCostFunction::max_trans_vel_ [private] |
Definition at line 81 of file obstacle_cost_function.h.
double base_local_planner::ObstacleCostFunction::scaling_speed_ [private] |
Definition at line 83 of file obstacle_cost_function.h.
Definition at line 80 of file obstacle_cost_function.h.