Terminal ball constraint (specialized for SE2) More...
#include <final_state_conditions_se2.h>

Public Types | |
| using | Ptr = std::shared_ptr< TerminalBallSE2 > |
Public Types inherited from corbo::TerminalBall | |
| typedef std::shared_ptr< const TerminalBall > | ConstPtr |
| typedef std::shared_ptr< TerminalBall > | Ptr |
Public Types inherited from corbo::FinalStageConstraint | |
| typedef std::shared_ptr< const FinalStageConstraint > | ConstPtr |
| typedef std::shared_ptr< FinalStageConstraint > | Ptr |
Public Types inherited from corbo::StageFunction | |
| typedef std::shared_ptr< const StageFunction > | ConstPtr |
| typedef std::shared_ptr< StageFunction > | Ptr |
Public Member Functions | |
| void | computeNonIntegralStateTerm (int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, Eigen::Ref< Eigen::VectorXd > cost) const override |
| corbo::FinalStageConstraint::Ptr | getInstance () const override |
| TerminalBallSE2 () | |
| TerminalBallSE2 (const Eigen::Ref< const Eigen::MatrixXd > &S, double gamma) | |
Public Member Functions inherited from corbo::TerminalBall | |
| bool | checkParameters (int state_dim, int control_dim, FinalStageCost::ConstPtr final_stage_cost, std::stringstream *issues) const override |
| double | getGamma () |
| int | getNonIntegralStateTermDimension (int k) const override |
| const Eigen::MatrixXd & | getWeightS () const |
| bool | isEqualityConstraint () const override |
| void | setGamma (double gamma) |
| bool | setWeightS (const Eigen::DiagonalMatrix< double, -1 > &S) |
| bool | setWeightS (const Eigen::Ref< const Eigen::MatrixXd > &S) |
| TerminalBall ()=default | |
| TerminalBall (const Eigen::Ref< const Eigen::MatrixXd > &S, double gamma) | |
| bool | update (int n, double t, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, ReferenceTrajectoryInterface *sref, bool single_dt, const Eigen::VectorXd &x0, FinalStageCost::ConstPtr final_stage_cost, StagePreprocessor::Ptr stage_preprocessor, const std::vector< double > &dts, const DiscretizationGridInterface *) override |
Public Member Functions inherited from corbo::FinalStageConstraint | |
| bool | hasIntegralTerms (int k) const final |
| bool | hasNonIntegralTerms (int k) const final |
| bool | isInequalityConstraint () const |
| bool | update (int n, double t, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, ReferenceTrajectoryInterface *sref, bool single_dt, const Eigen::VectorXd &x0, StagePreprocessor::Ptr stage_preprocessor, const std::vector< double > &dts, const DiscretizationGridInterface *grid) final |
Public Member Functions inherited from corbo::StageFunction | |
| virtual bool | checkParameters (int state_dim, int control_dim, std::stringstream *issues) const |
| virtual void | computeConcatenatedNonIntegralStateControlTerms (int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, const Eigen::Ref< const Eigen::VectorXd > &u_k, double dt_k, Eigen::Ref< Eigen::VectorXd > cost, bool lsq_mode=false) const |
| virtual void | computeConcatenatedNonIntegralStateTerms (int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, const Eigen::Ref< const Eigen::VectorXd > &u_k, double dt_k, Eigen::Ref< Eigen::VectorXd > cost, bool lsq_mode=false) const |
| virtual void | computeNonIntegralStateDtTerm (int k, const Eigen::Ref< const Eigen::VectorXd > &x_k, double dt_k, Eigen::Ref< Eigen::VectorXd > cost) const |
| virtual int | getConcatenatedNonIntegralStateControlTermDimension (int k, bool lsq_mode=false) const |
| virtual int | getConcatenatedNonIntegralStateTermDimension (int k, bool lsq_mode=false) const |
| virtual int | getNonIntegralStateDtTermDimension (int k) const |
| virtual bool | isLinearNonIntegralControlTerm (int k) const |
| virtual bool | isLinearNonIntegralDtTerm (int k) const |
| virtual bool | isLinearNonIntegralStateTerm (int k) const |
| virtual bool | isLsqFormNonIntegralControlTerm (int k) const |
| virtual bool | isLsqFormNonIntegralDtTerm (int k) const |
| virtual bool | isLsqFormNonIntegralStateTerm (int k) const |
| virtual | ~StageFunction ()=default |
Additional Inherited Members | |
Protected Attributes inherited from corbo::TerminalBall | |
| bool | _diagonal_mode |
| bool | _diagonal_mode_intentionally |
| double | _gamma |
| Eigen::MatrixXd | _S |
| Eigen::DiagonalMatrix< double, -1 > | _S_diag |
| const ReferenceTrajectoryInterface * | _x_ref |
| bool | _zero_x_ref |
Terminal ball constraint (specialized for SE2)
This class ensures that the distance (x_{ref} - x) is computed properly in SO(2) for the third state component.
Definition at line 92 of file final_state_conditions_se2.h.
| using mpc_local_planner::TerminalBallSE2::Ptr = std::shared_ptr<TerminalBallSE2> |
Definition at line 95 of file final_state_conditions_se2.h.
|
inline |
Definition at line 97 of file final_state_conditions_se2.h.
|
inline |
Definition at line 99 of file final_state_conditions_se2.h.
|
overridevirtual |
Reimplemented from corbo::TerminalBall.
Definition at line 74 of file final_state_conditions_se2.cpp.
|
inlineoverridevirtual |
Reimplemented from corbo::TerminalBall.
Definition at line 101 of file final_state_conditions_se2.h.