Edge defining the cost function for limiting the translational and rotational acceleration at the beginning of the trajectory. More...
#include <edge_acceleration.h>
Public Member Functions | |
void | computeError () |
Actual cost function. More... | |
EdgeAccelerationStart () | |
Construct edge. More... | |
void | setInitialVelocity (const geometry_msgs::Twist &vel_start) |
Set the initial velocity that is taken into account for calculating the acceleration. More... | |
Public Member Functions inherited from teb_local_planner::BaseTebMultiEdge< 2, const geometry_msgs::Twist * > | |
BaseTebMultiEdge () | |
Construct edge. More... | |
ErrorVector & | getError () |
Compute and return error / cost value. More... | |
virtual bool | read (std::istream &is) |
Read values from input stream. More... | |
virtual void | resize (size_t size) |
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 | ~BaseTebMultiEdge () |
Destruct edge. More... | |
Additional Inherited Members | |
Protected Attributes inherited from teb_local_planner::BaseTebMultiEdge< 2, const geometry_msgs::Twist * > | |
const TebConfig * | cfg_ |
Store TebConfig class for parameters. More... | |
Edge defining the cost function for limiting the translational and rotational acceleration at the beginning of the trajectory.
The edge depends on three vertices , an initial velocity defined by setInitialVelocity() and minimizes:
.
a is calculated using the difference quotient (twice) and the position parts of the poses.
omegadot is calculated using the difference quotient of the yaw angles followed by a normalization to [-pi, pi].
weight can be set using setInformation().
penaltyInterval denotes the penalty function, see penaltyBoundToInterval().
The dimension of the error / cost vector is 2: the first component represents the translational acceleration and the second one the rotational acceleration.
Definition at line 291 of file edge_acceleration.h.
|
inline |
Construct edge.
Definition at line 298 of file edge_acceleration.h.
|
inline |
Actual cost function.
Definition at line 308 of file edge_acceleration.h.
|
inline |
Set the initial velocity that is taken into account for calculating the acceleration.
vel_start | twist message containing the translational and rotational velocity |
Definition at line 351 of file edge_acceleration.h.