Edge defining the cost function for keeping a distance from dynamic (moving) obstacles. More...
#include <edge_dynamic_obstacle.h>
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 BaseRobotFootprintModel * | robot_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 TebConfig * | cfg_ |
Store TebConfig class for parameters. More... | |
Edge defining the cost function for keeping a distance from dynamic (moving) obstacles.
The edge depends on two vertices and minimizes:
.
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().
Definition at line 71 of file edge_dynamic_obstacle.h.
|
inline |
Construct edge.
Definition at line 78 of file edge_dynamic_obstacle.h.
|
inline |
Construct edge and specify the time for its associated pose (neccessary for computeError).
t_ | Estimated time until current pose is reached |
Definition at line 86 of file edge_dynamic_obstacle.h.
|
inline |
Actual cost function.
Definition at line 93 of file edge_dynamic_obstacle.h.
|
inline |
Set Obstacle for the underlying cost function.
Definition at line 111 of file edge_dynamic_obstacle.h.
|
inline |
Set all parameters at once.
cfg | TebConfig class |
robot_model | Robot model required for distance calculation |
obstacle | 2D position vector containing the position of the obstacle |
Definition at line 131 of file edge_dynamic_obstacle.h.
|
inline |
Set pointer to the robot model.
robot_model | Robot model required for distance calculation |
Definition at line 120 of file edge_dynamic_obstacle.h.
|
protected |
Store pointer to robot_model.
Definition at line 140 of file edge_dynamic_obstacle.h.
|
protected |
Estimated time until current pose is reached.
Definition at line 141 of file edge_dynamic_obstacle.h.