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) |
void | setSumScores (bool score_sums) |
~ObstacleCostFunction () | |
Public Member Functions inherited from base_local_planner::TrajectoryCostFunction | |
double | getScale () |
void | setScale (double scale) |
virtual | ~TrajectoryCostFunction () |
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_ |
bool | sum_scores_ |
base_local_planner::WorldModel * | world_model_ |
Additional Inherited Members | |
Protected Member Functions inherited from base_local_planner::TrajectoryCostFunction | |
TrajectoryCostFunction (double scale=1.0) | |
Uses costmap 2d to assign negative costs if robot footprint is in obstacle on any point of the trajectory.
class ObstacleCostFunction
Definition at line 88 of file obstacle_cost_function.h.
base_local_planner::ObstacleCostFunction::ObstacleCostFunction | ( | costmap_2d::Costmap2D * | costmap | ) |
Definition at line 80 of file obstacle_cost_function.cpp.
base_local_planner::ObstacleCostFunction::~ObstacleCostFunction | ( | ) |
Definition at line 87 of file obstacle_cost_function.cpp.
|
static |
Definition at line 151 of file obstacle_cost_function.cpp.
|
static |
Definition at line 137 of file obstacle_cost_function.cpp.
|
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 105 of file obstacle_cost_function.cpp.
|
virtual |
return a score for trajectory traj
Implements base_local_planner::TrajectoryCostFunction.
Definition at line 109 of file obstacle_cost_function.cpp.
void base_local_planner::ObstacleCostFunction::setFootprint | ( | std::vector< geometry_msgs::Point > | footprint_spec | ) |
Definition at line 101 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 94 of file obstacle_cost_function.cpp.
|
inline |
Definition at line 132 of file obstacle_cost_function.h.
|
private |
Definition at line 149 of file obstacle_cost_function.h.
|
private |
Definition at line 150 of file obstacle_cost_function.h.
|
private |
Definition at line 155 of file obstacle_cost_function.h.
|
private |
Definition at line 152 of file obstacle_cost_function.h.
|
private |
Definition at line 155 of file obstacle_cost_function.h.
|
private |
Definition at line 153 of file obstacle_cost_function.h.
|
private |
Definition at line 151 of file obstacle_cost_function.h.