Class EdgeAccelerationHolonomicGoal

Inheritance Relationships

Base Type

Class Documentation

class EdgeAccelerationHolonomicGoal : public hateb_local_planner::BaseTebMultiEdge<3, const geometry_msgs::Twist*>

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.

Remark

Do not forget to call setHATebConfig()

Remark

Refer to EdgeAccelerationHolonomicStart() for defining boundary (initial) values at the end of the trajectory

Public Functions

inline EdgeAccelerationHolonomicGoal()

Construct edge.

inline void computeError() override

Actual cost function.

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

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

Parameters:

vel_goal – twist message containing the translational and rotational velocity