Edge defining the cost function for limiting the translational and rotational acceleration at the end of the trajectory. More...
#include <edge_acceleration.h>

Public Member Functions | |
| void | computeError () |
| Actual cost function. More... | |
| EdgeAccelerationHolonomicGoal () | |
| Construct edge. More... | |
| void | setGoalVelocity (const geometry_msgs::Twist &vel_goal) |
| Set the goal / final velocity that is taken into account for calculating the acceleration. More... | |
Public Member Functions inherited from teb_local_planner::BaseTebMultiEdge< 3, const geometry_msgs::Twist *> | |
| 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... | |
Additional Inherited Members | |
Protected Attributes inherited from teb_local_planner::BaseTebMultiEdge< 3, 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 end of the trajectory.
The edge depends on three vertices
, an initial velocity defined by setGoalVelocity() and minimizes:
.
ax is calculated using the difference quotient (twice) and the x-position parts of the poses
ay is calculated using the difference quotient (twice) and the y-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 3: the first component represents the translational acceleration, the second one is the strafing velocity and the third one the rotational acceleration.
Definition at line 657 of file edge_acceleration.h.
|
inline |
Construct edge.
Definition at line 664 of file edge_acceleration.h.
|
inline |
Actual cost function.
Definition at line 673 of file edge_acceleration.h.
|
inline |
Set the goal / final velocity that is taken into account for calculating the acceleration.
| vel_goal | twist message containing the translational and rotational velocity |
Definition at line 719 of file edge_acceleration.h.