Public Member Functions | List of all members
teb_local_planner::EdgeAccelerationHolonomicGoal Class Reference

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

#include <edge_acceleration.h>

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

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 * >
 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< 3, const geometry_msgs::Twist * >
const TebConfigcfg_
 Store TebConfig class for parameters. More...
 

Detailed Description

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

The edge depends on three vertices $ \mathbf{s}_i, \mathbf{s}_{ip1}, \Delta T_i $, an initial velocity defined by setGoalVelocity() 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 is the strafing velocity and the third one the rotational acceleration.

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

Definition at line 657 of file edge_acceleration.h.

Constructor & Destructor Documentation

teb_local_planner::EdgeAccelerationHolonomicGoal::EdgeAccelerationHolonomicGoal ( )
inline

Construct edge.

Definition at line 664 of file edge_acceleration.h.

Member Function Documentation

void teb_local_planner::EdgeAccelerationHolonomicGoal::computeError ( )
inline

Actual cost function.

Definition at line 673 of file edge_acceleration.h.

void teb_local_planner::EdgeAccelerationHolonomicGoal::setGoalVelocity ( const geometry_msgs::Twist &  vel_goal)
inline

Set the goal / final velocity that is taken into account for calculating the acceleration.

Parameters
vel_goaltwist message containing the translational and rotational velocity

Definition at line 719 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 Wed Jun 3 2020 04:03:08