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/smooth-1norm.hpp>
16 #include <crocoddyl/core/activations/weighted-quadratic.hpp>
17 #include <crocoddyl/core/fwd.hpp>
18 #include <crocoddyl/core/integrator/euler.hpp>
19 #include <crocoddyl/core/optctrl/shooting.hpp>
20 #include <crocoddyl/core/residuals/control.hpp>
21 #include <crocoddyl/core/solver-base.hpp>
22 #include <crocoddyl/core/solvers/fddp.hpp>
23 #include <crocoddyl/core/utils/exception.hpp>
24 #include <crocoddyl/multibody/actions/contact-fwddyn.hpp>
25 #include <crocoddyl/multibody/actuations/floating-base.hpp>
26 #include <crocoddyl/multibody/contacts/contact-6d.hpp>
27 #include <crocoddyl/multibody/contacts/multiple-contacts.hpp>
28 #include <crocoddyl/multibody/frames.hpp>
29 #include <crocoddyl/multibody/fwd.hpp>
30 #include <crocoddyl/multibody/residuals/com-position.hpp>
31 #include <crocoddyl/multibody/residuals/contact-control-gravity.hpp>
32 #include <crocoddyl/multibody/residuals/contact-force.hpp>
33 #include <crocoddyl/multibody/residuals/contact-wrench-cone.hpp>
34 #include <crocoddyl/multibody/residuals/frame-placement.hpp>
35 #include <crocoddyl/multibody/residuals/frame-rotation.hpp>
36 #include <crocoddyl/multibody/residuals/frame-translation.hpp>
37 #include <crocoddyl/multibody/residuals/frame-velocity.hpp>
38 #include <crocoddyl/multibody/residuals/state.hpp>
39 #include <crocoddyl/multibody/states/multibody.hpp>
40 #include <pinocchio/algorithm/center-of-mass.hpp>
41 #include <pinocchio/algorithm/frames.hpp>
42 #include <pinocchio/algorithm/joint-configuration.hpp>
43 #include <pinocchio/algorithm/model.hpp>
44 #include <pinocchio/fwd.hpp>
45 #include <pinocchio/multibody/data.hpp>
46 #include <pinocchio/multibody/model.hpp>
54 template <
typename Scalar>
55 class ResidualModelCoMVelocityTpl;
56 template <
typename Scalar>
62 template <
typename Scalar>
64 template <
typename Scalar>
70 template <
typename Scalar>
72 template <
typename Scalar>
78 template <
typename Scalar>
80 template <
typename Scalar>
86 template <
typename Scalar>
88 template <
typename Scalar>
94 template <
typename Scalar>
96 template <
typename Scalar>
102 template <
typename Scalar>
104 template <
typename Scalar>
110 template <
typename Scalar>
112 template <
typename Scalar>
118 template <
typename Scalar>
120 template <
typename Scalar>
126 template <
typename Scalar>
132 template <
typename Scalar>
134 template <
typename Scalar>
138 typedef boost::shared_ptr<ActivationModelWeightedLog>
145 typedef boost::shared_ptr<crocoddyl::IntegratedActionModelEuler>
IAM;
146 typedef boost::shared_ptr<crocoddyl::IntegratedActionDataEuler>
IAD;
147 typedef boost::shared_ptr<crocoddyl::ActionModelAbstract>
AMA;
148 typedef boost::shared_ptr<crocoddyl::ActionDataAbstract>
ADA;
149 typedef boost::shared_ptr<crocoddyl::DifferentialActionModelContactFwdDynamics>
151 typedef boost::shared_ptr<crocoddyl::DifferentialActionDataContactFwdDynamics>
153 typedef boost::shared_ptr<crocoddyl::CostModelSum>
Cost;
154 typedef boost::shared_ptr<crocoddyl::ContactModelMultiple>
Contact;
155 typedef boost::shared_ptr<crocoddyl::SolverFDDP>
DDP;
157 typedef boost::shared_ptr<crocoddyl::ResidualModelFramePlacement>
159 typedef boost::shared_ptr<crocoddyl::ResidualModelContactWrenchCone>
163 template <
typename Scalar>
168 template <
typename Scalar>
171 template <
typename Scalar>
184 namespace newcontacts {
187 template <
typename Scalar>
190 template <
typename Scalar>
195 template <
typename Scalar>
198 template <
typename Scalar>
203 template <
typename Scalar>
206 template <
typename Scalar>
211 template <
typename Scalar>
216 template <
typename Scalar>
222 template <
typename Scalar>
226 using crocoddyl::ContactType;
231 #endif // SOBEC_FWD_HPP_
boost::shared_ptr< crocoddyl::IntegratedActionDataEuler > IAD
Definition: fwd.hpp:146
StateLPFTpl< double > StateLPF
Definition: fwd.hpp:164
Definition: activation-quad-ref.hpp:23
ResidualDataVelCollisionTpl< double > ResidualDataVelCollision
Definition: fwd.hpp:83
Definition: residual-cop.hpp:118
boost::shared_ptr< crocoddyl::ResidualModelContactWrenchCone > ResidualModelContactWrenchConePtr
Definition: fwd.hpp:160
Eigen::Vector2d eVector2
Definition: fwd.hpp:144
ResidualData2DSurfaceTpl< double > ResidualData2DSurface
Definition: fwd.hpp:123
ActivationDataWeightedLogTpl< double > ActivationDataWeightedLog
Definition: fwd.hpp:137
Definition: residual-fly-high.hpp:128
COP residual.
Definition: residual-cop.hpp:41
Definition: activation-weighted-log.hpp:106
Cost penalizing distance between two frames r=||f1.translation-f2.translation||.
Definition: residual-feet-collision.hpp:29
ResidualModelCoMVelocityTpl< double > ResidualModelCoMVelocity
Definition: fwd.hpp:57
ActivationModelWeightedLogTpl< double > ActivationModelWeightedLog
Definition: fwd.hpp:135
boost::shared_ptr< ActivationModelQuadRef > ActivationModelQuadRefPtr
Definition: fwd.hpp:129
Definition: residual-center-of-friction.hpp:118
ResidualModelDCMPositionTpl< double > ResidualModelDCMPosition
Definition: fwd.hpp:105
boost::shared_ptr< crocoddyl::SolverFDDP > DDP
Definition: fwd.hpp:155
boost::shared_ptr< crocoddyl::ResidualModelFramePlacement > ResidualModelFramePlacementPtr
Definition: fwd.hpp:158
ResidualModelFlyAngleTpl< double > ResidualModelFlyAngle
Definition: fwd.hpp:89
ResidualModelVelCollisionTpl< double > ResidualModelVelCollision
Definition: fwd.hpp:81
ResidualDataFlyHighTpl< double > ResidualDataFlyHigh
Definition: fwd.hpp:99
boost::shared_ptr< crocoddyl::ContactModelMultiple > Contact
Definition: fwd.hpp:154
boost::shared_ptr< crocoddyl::DifferentialActionModelContactFwdDynamics > DAM
Definition: fwd.hpp:150
DCM position residual.
Definition: residual-dcm-position.hpp:37
ResidualModelCenterOfFrictionTpl< double > ResidualModelCenterOfFriction
Definition: fwd.hpp:73
Cost penalizing the position of one effector with respect to the other.
Definition: residual-2D-surface.hpp:31
ResidualDataCenterOfPressureTpl< double > ResidualDataCenterOfPressure
Definition: fwd.hpp:67
boost::shared_ptr< crocoddyl::ActionModelAbstract > AMA
Definition: fwd.hpp:147
IntegratedActionDataLPFTpl< double > IntegratedActionDataLPF
Definition: fwd.hpp:172
Definition: activation-quad-ref.hpp:19
ResidualModelFlyHighTpl< double > ResidualModelFlyHigh
Definition: fwd.hpp:97
boost::shared_ptr< crocoddyl::CostModelSum > Cost
Definition: fwd.hpp:153
ResidualModel2DSurfaceTpl< double > ResidualModel2DSurface
Definition: fwd.hpp:121
Definition: residual-com-velocity.hpp:23
IntegratedActionModelLPFTpl< double > IntegratedActionModelLPF
Definition: fwd.hpp:169
Eigen::Matrix< double, 4, 1 > eVector4
Definition: fwd.hpp:142
Definition: residual-dcm-position.hpp:130
Definition: residual-fly-angle.hpp:134
boost::shared_ptr< ActivationModelWeightedLog > ActivationModelWeightedLogPtr
Definition: fwd.hpp:139
Definition: action.hpp:25
Definition: activation-weighted-log.hpp:23
ResidualDataFlyAngleTpl< double > ResidualDataFlyAngle
Definition: fwd.hpp:91
boost::shared_ptr< crocoddyl::ActionDataAbstract > ADA
Definition: fwd.hpp:148
Eigen::Matrix< double, 6, 1 > eVector6
Definition: fwd.hpp:141
ResidualDataDCMPositionTpl< double > ResidualDataDCMPosition
Definition: fwd.hpp:107
Cost penalizing high horizontal velocity near zero altitude.
Definition: residual-fly-high.hpp:32
ResidualModelCenterOfPressureTpl< double > ResidualModelCenterOfPressure
Definition: fwd.hpp:65
ResidualModelFeetCollisionTpl< double > ResidualModelFeetCollision
Definition: fwd.hpp:113
ResidualDataFeetCollisionTpl< double > ResidualDataFeetCollision
Definition: fwd.hpp:115
boost::shared_ptr< crocoddyl::IntegratedActionModelEuler > IAM
Definition: fwd.hpp:145
Cost penalizing high horizontal velocity near zero altitude.
Definition: residual-fly-angle.hpp:32
CoM velocity residual.
Definition: residual-com-velocity.hpp:73
ActivationModelQuadRefTpl< double > ActivationModelQuadRef
Definition: fwd.hpp:127
Center of friction residual.
Definition: residual-center-of-friction.hpp:41
ResidualDataCenterOfFrictionTpl< double > ResidualDataCenterOfFriction
Definition: fwd.hpp:75
Definition: residual-feet-collision.hpp:119
Eigen::Vector3d eVector3
Definition: fwd.hpp:143
ResidualDataCoMVelocityTpl< double > ResidualDataCoMVelocity
Definition: fwd.hpp:59
boost::shared_ptr< crocoddyl::DifferentialActionDataContactFwdDynamics > DAD
Definition: fwd.hpp:152
Definition: action.hpp:165
Definition: residual-2D-surface.hpp:149