Public Member Functions | Static Public Member Functions | Private Attributes
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]

List of all members.

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

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


Constructor & Destructor Documentation

Definition at line 45 of file obstacle_cost_function.cpp.

Definition at line 51 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 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.

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.

return a score for trajectory traj

Implements base_local_planner::TrajectoryCostFunction.

Definition at line 73 of file obstacle_cost_function.cpp.

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.


Member Data Documentation

Definition at line 78 of file obstacle_cost_function.h.

Definition at line 79 of file obstacle_cost_function.h.

Definition at line 83 of file obstacle_cost_function.h.

Definition at line 81 of file obstacle_cost_function.h.

Definition at line 83 of file obstacle_cost_function.h.

Definition at line 80 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
autogenerated on Mon Oct 6 2014 02:45:34