Go to the documentation of this file.
10 #define SOBEC_FWD_HPP_
12 #include <crocoddyl/core/action-base.hpp>
13 #include <crocoddyl/core/activations/quadratic-barrier.hpp>
14 #include <crocoddyl/core/activations/quadratic-flat-log.hpp>
15 #include <crocoddyl/core/activations/weighted-quadratic.hpp>
16 #include <crocoddyl/core/fwd.hpp>
17 #include <crocoddyl/core/integrator/euler.hpp>
18 #include <crocoddyl/core/optctrl/shooting.hpp>
19 #include <crocoddyl/core/residuals/control.hpp>
20 #include <crocoddyl/core/solver-base.hpp>
21 #include <crocoddyl/core/solvers/fddp.hpp>
22 #include <crocoddyl/core/utils/exception.hpp>
23 #include <crocoddyl/multibody/actions/contact-fwddyn.hpp>
24 #include <crocoddyl/multibody/actuations/floating-base.hpp>
25 #include <crocoddyl/multibody/contacts/contact-6d.hpp>
26 #include <crocoddyl/multibody/contacts/multiple-contacts.hpp>
27 #include <crocoddyl/multibody/frames.hpp>
28 #include <crocoddyl/multibody/fwd.hpp>
29 #include <crocoddyl/multibody/residuals/com-position.hpp>
30 #include <crocoddyl/multibody/residuals/contact-control-gravity.hpp>
31 #include <crocoddyl/multibody/residuals/contact-wrench-cone.hpp>
32 #include <crocoddyl/multibody/residuals/frame-placement.hpp>
33 #include <crocoddyl/multibody/residuals/frame-rotation.hpp>
34 #include <crocoddyl/multibody/residuals/frame-translation.hpp>
35 #include <crocoddyl/multibody/residuals/frame-velocity.hpp>
36 #include <crocoddyl/multibody/residuals/state.hpp>
37 #include <crocoddyl/multibody/states/multibody.hpp>
38 #include <pinocchio/algorithm/center-of-mass.hpp>
39 #include <pinocchio/algorithm/frames.hpp>
40 #include <pinocchio/algorithm/joint-configuration.hpp>
41 #include <pinocchio/algorithm/model.hpp>
42 #include <pinocchio/fwd.hpp>
43 #include <pinocchio/multibody/data.hpp>
44 #include <pinocchio/multibody/model.hpp>
52 template <
typename Scalar>
53 class ResidualModelCoMVelocityTpl;
54 template <
typename Scalar>
60 template <
typename Scalar>
62 template <
typename Scalar>
68 template <
typename Scalar>
70 template <
typename Scalar>
76 template <
typename Scalar>
78 template <
typename Scalar>
84 template <
typename Scalar>
86 template <
typename Scalar>
92 template <
typename Scalar>
94 template <
typename Scalar>
100 template <
typename Scalar>
109 typedef boost::shared_ptr<crocoddyl::IntegratedActionModelEuler>
IAM;
110 typedef boost::shared_ptr<crocoddyl::IntegratedActionDataEuler>
IAD;
111 typedef boost::shared_ptr<crocoddyl::ActionModelAbstract>
AMA;
112 typedef boost::shared_ptr<crocoddyl::ActionDataAbstract>
ADA;
113 typedef boost::shared_ptr<crocoddyl::DifferentialActionModelContactFwdDynamics>
115 typedef boost::shared_ptr<crocoddyl::CostModelSum>
Cost;
116 typedef boost::shared_ptr<crocoddyl::ContactModelMultiple>
Contact;
117 typedef boost::shared_ptr<crocoddyl::SolverFDDP>
DDP;
119 typedef boost::shared_ptr<crocoddyl::ResidualModelFramePlacement>
121 typedef boost::shared_ptr<crocoddyl::ResidualModelContactWrenchCone>
125 template <
typename Scalar>
130 template <
typename Scalar>
133 template <
typename Scalar>
146 namespace newcontacts {
149 template <
typename Scalar>
152 template <
typename Scalar>
157 template <
typename Scalar>
160 template <
typename Scalar>
165 template <
typename Scalar>
170 template <
typename Scalar>
176 template <
typename Scalar>
191 #endif // SOBEC_FWD_HPP_
boost::shared_ptr< crocoddyl::IntegratedActionDataEuler > IAD
Definition: fwd.hpp:110
StateLPFTpl< double > StateLPF
Definition: fwd.hpp:126
Definition: activation-quad-ref.hpp:23
ResidualDataVelCollisionTpl< double > ResidualDataVelCollision
Definition: fwd.hpp:81
Definition: residual-cop.hpp:118
boost::shared_ptr< crocoddyl::ResidualModelContactWrenchCone > ResidualModelContactWrenchConePtr
Definition: fwd.hpp:122
Eigen::Vector2d eVector2
Definition: fwd.hpp:108
Definition: action.hpp:165
Definition: residual-fly-high.hpp:128
COP residual.
Definition: residual-cop.hpp:41
Cost penalizing distance between two frames r=||f1.translation-f2.translation||.
Definition: residual-feet-collision.hpp:29
ResidualModelCoMVelocityTpl< double > ResidualModelCoMVelocity
Definition: fwd.hpp:55
boost::shared_ptr< ActivationModelQuadRef > ActivationModelQuadRefPtr
Definition: fwd.hpp:103
Definition: residual-center-of-friction.hpp:118
boost::shared_ptr< crocoddyl::SolverFDDP > DDP
Definition: fwd.hpp:117
boost::shared_ptr< crocoddyl::ResidualModelFramePlacement > ResidualModelFramePlacementPtr
Definition: fwd.hpp:120
ResidualModelVelCollisionTpl< double > ResidualModelVelCollision
Definition: fwd.hpp:79
ResidualDataFlyHighTpl< double > ResidualDataFlyHigh
Definition: fwd.hpp:89
boost::shared_ptr< crocoddyl::ContactModelMultiple > Contact
Definition: fwd.hpp:116
boost::shared_ptr< crocoddyl::DifferentialActionModelContactFwdDynamics > DAM
Definition: fwd.hpp:114
ResidualModelCenterOfFrictionTpl< double > ResidualModelCenterOfFriction
Definition: fwd.hpp:71
ResidualDataCenterOfPressureTpl< double > ResidualDataCenterOfPressure
Definition: fwd.hpp:65
boost::shared_ptr< crocoddyl::ActionModelAbstract > AMA
Definition: fwd.hpp:111
IntegratedActionDataLPFTpl< double > IntegratedActionDataLPF
Definition: fwd.hpp:134
Definition: activation-quad-ref.hpp:19
ResidualModelFlyHighTpl< double > ResidualModelFlyHigh
Definition: fwd.hpp:87
boost::shared_ptr< crocoddyl::CostModelSum > Cost
Definition: fwd.hpp:115
Definition: residual-com-velocity.hpp:23
IntegratedActionModelLPFTpl< double > IntegratedActionModelLPF
Definition: fwd.hpp:131
Eigen::Matrix< double, 4, 1 > eVector4
Definition: fwd.hpp:106
Definition: action.hpp:25
boost::shared_ptr< crocoddyl::ActionDataAbstract > ADA
Definition: fwd.hpp:112
Eigen::Matrix< double, 6, 1 > eVector6
Definition: fwd.hpp:105
Cost penalizing high horizontal velocity near zero altitude.
Definition: residual-fly-high.hpp:32
ResidualModelCenterOfPressureTpl< double > ResidualModelCenterOfPressure
Definition: fwd.hpp:63
ResidualModelFeetCollisionTpl< double > ResidualModelFeetCollision
Definition: fwd.hpp:95
ResidualDataFeetCollisionTpl< double > ResidualDataFeetCollision
Definition: fwd.hpp:97
boost::shared_ptr< crocoddyl::IntegratedActionModelEuler > IAM
Definition: fwd.hpp:109
CoM velocity residual.
Definition: residual-com-velocity.hpp:73
ActivationModelQuadRefTpl< double > ActivationModelQuadRef
Definition: fwd.hpp:101
Center of friction residual.
Definition: residual-center-of-friction.hpp:41
ResidualDataCenterOfFrictionTpl< double > ResidualDataCenterOfFriction
Definition: fwd.hpp:73
Definition: residual-feet-collision.hpp:119
Eigen::Vector3d eVector3
Definition: fwd.hpp:107
ResidualDataCoMVelocityTpl< double > ResidualDataCoMVelocity
Definition: fwd.hpp:57