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 88 of file obstacle_cost_function.h.

Constructor & Destructor Documentation

◆ ObstacleCostFunction()

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

Definition at line 80 of file obstacle_cost_function.cpp.

◆ ~ObstacleCostFunction()

base_local_planner::ObstacleCostFunction::~ObstacleCostFunction ( )

Definition at line 87 of file obstacle_cost_function.cpp.

Member Function Documentation

◆ footprintCost()

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 151 of file obstacle_cost_function.cpp.

◆ getScalingFactor()

double base_local_planner::ObstacleCostFunction::getScalingFactor ( Trajectory traj,
double  scaling_speed,
double  max_trans_vel,
double  max_scaling_factor 
)
static

Definition at line 137 of file obstacle_cost_function.cpp.

◆ prepare()

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 105 of file obstacle_cost_function.cpp.

◆ scoreTrajectory()

double base_local_planner::ObstacleCostFunction::scoreTrajectory ( Trajectory traj)
virtual

return a score for trajectory traj

Implements base_local_planner::TrajectoryCostFunction.

Definition at line 109 of file obstacle_cost_function.cpp.

◆ setFootprint()

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

Definition at line 101 of file obstacle_cost_function.cpp.

◆ setParams()

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.

◆ setSumScores()

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

Definition at line 132 of file obstacle_cost_function.h.

Member Data Documentation

◆ costmap_

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

Definition at line 149 of file obstacle_cost_function.h.

◆ footprint_spec_

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

Definition at line 150 of file obstacle_cost_function.h.

◆ max_scaling_factor_

double base_local_planner::ObstacleCostFunction::max_scaling_factor_
private

Definition at line 155 of file obstacle_cost_function.h.

◆ max_trans_vel_

double base_local_planner::ObstacleCostFunction::max_trans_vel_
private

Definition at line 152 of file obstacle_cost_function.h.

◆ scaling_speed_

double base_local_planner::ObstacleCostFunction::scaling_speed_
private

Definition at line 155 of file obstacle_cost_function.h.

◆ sum_scores_

bool base_local_planner::ObstacleCostFunction::sum_scores_
private

Definition at line 153 of file obstacle_cost_function.h.

◆ world_model_

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

Definition at line 151 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 Mon Mar 6 2023 03:50:24