Public Member Functions | Static Public Member Functions | Private Attributes | List of all members
base_local_planner::ObstacleCostFunction Class Reference

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>

Inheritance diagram for base_local_planner::ObstacleCostFunction:
Inheritance graph
[legend]

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::Costmap2Dcostmap_
 
std::vector< geometry_msgs::Pointfootprint_spec_
 
double max_scaling_factor_
 
double max_trans_vel_
 
double scaling_speed_
 
bool sum_scores_
 
base_local_planner::WorldModelworld_model_
 

Additional Inherited Members

- Protected Member Functions inherited from base_local_planner::TrajectoryCostFunction
 TrajectoryCostFunction (double scale=1.0)
 

Detailed Description

Uses costmap 2d to assign negative costs if robot footprint is in obstacle on any point of the trajectory.

class ObstacleCostFunction

Definition at line 53 of file obstacle_cost_function.h.

Constructor & Destructor Documentation

base_local_planner::ObstacleCostFunction::ObstacleCostFunction ( costmap_2d::Costmap2D costmap)

Definition at line 45 of file obstacle_cost_function.cpp.

base_local_planner::ObstacleCostFunction::~ObstacleCostFunction ( )

Definition at line 52 of file obstacle_cost_function.cpp.

Member Function Documentation

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 116 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 102 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 70 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 74 of file obstacle_cost_function.cpp.

void base_local_planner::ObstacleCostFunction::setFootprint ( std::vector< geometry_msgs::Point footprint_spec)

Definition at line 66 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 59 of file obstacle_cost_function.cpp.

void base_local_planner::ObstacleCostFunction::setSumScores ( bool  score_sums)
inline

Definition at line 62 of file obstacle_cost_function.h.

Member Data Documentation

costmap_2d::Costmap2D* base_local_planner::ObstacleCostFunction::costmap_
private

Definition at line 79 of file obstacle_cost_function.h.

std::vector<geometry_msgs::Point> base_local_planner::ObstacleCostFunction::footprint_spec_
private

Definition at line 80 of file obstacle_cost_function.h.

double base_local_planner::ObstacleCostFunction::max_scaling_factor_
private

Definition at line 85 of file obstacle_cost_function.h.

double base_local_planner::ObstacleCostFunction::max_trans_vel_
private

Definition at line 82 of file obstacle_cost_function.h.

double base_local_planner::ObstacleCostFunction::scaling_speed_
private

Definition at line 85 of file obstacle_cost_function.h.

bool base_local_planner::ObstacleCostFunction::sum_scores_
private

Definition at line 83 of file obstacle_cost_function.h.

base_local_planner::WorldModel* base_local_planner::ObstacleCostFunction::world_model_
private

Definition at line 81 of file obstacle_cost_function.h.


The documentation for this class was generated from the following files:


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:25