Public Member Functions | Protected Attributes | List of all members
teb_local_planner::EdgeDynamicObstacle Class Reference

Edge defining the cost function for keeping a distance from dynamic (moving) obstacles. More...

#include <edge_dynamic_obstacle.h>

Inheritance diagram for teb_local_planner::EdgeDynamicObstacle:
Inheritance graph
[legend]

Public Member Functions

void computeError ()
 Actual cost function. More...
 
 EdgeDynamicObstacle ()
 Construct edge. More...
 
 EdgeDynamicObstacle (double t)
 Construct edge and specify the time for its associated pose (neccessary for computeError). More...
 
void setObstacle (const Obstacle *obstacle)
 Set Obstacle for the underlying cost function. More...
 
void setParameters (const TebConfig &cfg, const BaseRobotFootprintModel *robot_model, const Obstacle *obstacle)
 Set all parameters at once. More...
 
void setRobotModel (const BaseRobotFootprintModel *robot_model)
 Set pointer to the robot model. More...
 
- Public Member Functions inherited from teb_local_planner::BaseTebUnaryEdge< 2, const Obstacle *, VertexPose >
 BaseTebUnaryEdge ()
 Construct edge. More...
 
ErrorVector & getError ()
 Compute and return error / cost value. More...
 
virtual bool read (std::istream &is)
 Read values from input stream. More...
 
void setTebConfig (const TebConfig &cfg)
 Assign the TebConfig class for parameters. More...
 
virtual bool write (std::ostream &os) const
 Write values to an output stream. More...
 
virtual ~BaseTebUnaryEdge ()
 Destruct edge. More...
 

Protected Attributes

const BaseRobotFootprintModelrobot_model_
 Store pointer to robot_model. More...
 
double t_
 Estimated time until current pose is reached. More...
 
- Protected Attributes inherited from teb_local_planner::BaseTebUnaryEdge< 2, const Obstacle *, VertexPose >
const TebConfigcfg_
 Store TebConfig class for parameters. More...
 

Detailed Description

Edge defining the cost function for keeping a distance from dynamic (moving) obstacles.

The edge depends on two vertices $ \mathbf{s}_i, \Delta T_i $ and minimizes:
$ \min \textrm{penaltyBelow}( dist2obstacle) \cdot weight $.
dist2obstacle denotes the minimum distance to the obstacle trajectory (spatial and temporal).
weight can be set using setInformation().
penaltyBelow denotes the penalty function, see penaltyBoundFromBelow().

See also
TebOptimalPlanner::AddEdgesDynamicObstacles
Remarks
Do not forget to call setTebConfig(), setVertexIdx() and
Warning
Experimental

Definition at line 71 of file edge_dynamic_obstacle.h.

Constructor & Destructor Documentation

teb_local_planner::EdgeDynamicObstacle::EdgeDynamicObstacle ( )
inline

Construct edge.

Definition at line 78 of file edge_dynamic_obstacle.h.

teb_local_planner::EdgeDynamicObstacle::EdgeDynamicObstacle ( double  t)
inline

Construct edge and specify the time for its associated pose (neccessary for computeError).

Parameters
t_Estimated time until current pose is reached

Definition at line 86 of file edge_dynamic_obstacle.h.

Member Function Documentation

void teb_local_planner::EdgeDynamicObstacle::computeError ( )
inline

Actual cost function.

Definition at line 93 of file edge_dynamic_obstacle.h.

void teb_local_planner::EdgeDynamicObstacle::setObstacle ( const Obstacle obstacle)
inline

Set Obstacle for the underlying cost function.

Parameters
obstacleConst pointer to an Obstacle or derived Obstacle

Definition at line 111 of file edge_dynamic_obstacle.h.

void teb_local_planner::EdgeDynamicObstacle::setParameters ( const TebConfig cfg,
const BaseRobotFootprintModel robot_model,
const Obstacle obstacle 
)
inline

Set all parameters at once.

Parameters
cfgTebConfig class
robot_modelRobot model required for distance calculation
obstacle2D position vector containing the position of the obstacle

Definition at line 131 of file edge_dynamic_obstacle.h.

void teb_local_planner::EdgeDynamicObstacle::setRobotModel ( const BaseRobotFootprintModel robot_model)
inline

Set pointer to the robot model.

Parameters
robot_modelRobot model required for distance calculation

Definition at line 120 of file edge_dynamic_obstacle.h.

Member Data Documentation

const BaseRobotFootprintModel* teb_local_planner::EdgeDynamicObstacle::robot_model_
protected

Store pointer to robot_model.

Definition at line 140 of file edge_dynamic_obstacle.h.

double teb_local_planner::EdgeDynamicObstacle::t_
protected

Estimated time until current pose is reached.

Definition at line 141 of file edge_dynamic_obstacle.h.


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


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 3 2020 04:03:08