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

Edge defining the cost function for limiting the translational and rotational acceleration. More...

#include <edge_acceleration.h>

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

Public Member Functions

void computeError ()
 Actual cost function. More...
 
 EdgeAccelerationHolonomic ()
 Construct edge. More...
 
- Public Member Functions inherited from teb_local_planner::BaseTebMultiEdge< 3, double >
 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, double >
const TebConfigcfg_
 Store TebConfig class for parameters. More...
 

Detailed Description

Edge defining the cost function for limiting the translational and rotational acceleration.

The edge depends on five vertices $ \mathbf{s}_i, \mathbf{s}_{ip1}, \mathbf{s}_{ip2}, \Delta T_i, \Delta T_{ip1} $ 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 all three poses
ay is calculated using the difference quotient (twice) and the y position parts of all three 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 (x-dir), the second one the strafing acceleration and the third one the rotational acceleration.

See also
TebOptimalPlanner::AddEdgesAcceleration
EdgeAccelerationHolonomicStart
EdgeAccelerationHolonomicGoal
Remarks
Do not forget to call setTebConfig()
Refer to EdgeAccelerationHolonomicStart() and EdgeAccelerationHolonomicGoal() for defining boundary values!

Definition at line 474 of file edge_acceleration.h.

Constructor & Destructor Documentation

teb_local_planner::EdgeAccelerationHolonomic::EdgeAccelerationHolonomic ( )
inline

Construct edge.

Definition at line 481 of file edge_acceleration.h.

Member Function Documentation

void teb_local_planner::EdgeAccelerationHolonomic::computeError ( )
inline

Actual cost function.

Definition at line 489 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