Public Member Functions
teb_local_planner::EdgeAccelerationHolonomicStart Class Reference

Edge defining the cost function for limiting the translational and rotational acceleration at the beginning of the trajectory. More...

#include <edge_acceleration.h>

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

List of all members.

Public Member Functions

void computeError ()
 Actual cost function.
 EdgeAccelerationHolonomicStart ()
 Construct edge.
void setInitialVelocity (const geometry_msgs::Twist &vel_start)
 Set the initial velocity that is taken into account for calculating the acceleration.

Detailed Description

Edge defining the cost function for limiting the translational and rotational acceleration at the beginning of the trajectory.

The edge depends on three vertices $ \mathbf{s}_i, \mathbf{s}_{ip1}, \Delta T_i $, an initial velocity defined by setInitialVelocity() and minimizes:
$ \min \textrm{penaltyInterval}( [ax, ay, omegadot ]^T ) \cdot weight $.
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 the strafing acceleration and the third one the rotational acceleration.

See also:
TebOptimalPlanner::AddEdgesAcceleration
EdgeAccelerationHolonomic
EdgeAccelerationHolonomicGoal
Remarks:
Do not forget to call setTebConfig()
Refer to EdgeAccelerationHolonomicGoal() for defining boundary values at the end of the trajectory!

Definition at line 566 of file edge_acceleration.h.


Constructor & Destructor Documentation

Construct edge.

Definition at line 573 of file edge_acceleration.h.


Member Function Documentation

Actual cost function.

Definition at line 582 of file edge_acceleration.h.

void teb_local_planner::EdgeAccelerationHolonomicStart::setInitialVelocity ( const geometry_msgs::Twist &  vel_start) [inline]

Set the initial velocity that is taken into account for calculating the acceleration.

Parameters:
vel_starttwist message containing the translational and rotational velocity

Definition at line 626 of file edge_acceleration.h.


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


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sat Jun 8 2019 20:21:34