Template Class DifferentialActionModelFreeFwdDynamicsTpl
Defined in File free-fwddyn.hpp
Inheritance Relationships
Base Type
public crocoddyl::DifferentialActionModelAbstractTpl< _Scalar >(Template Class DifferentialActionModelAbstractTpl)
Class Documentation
-
template<typename _Scalar>
class DifferentialActionModelFreeFwdDynamicsTpl : public crocoddyl::DifferentialActionModelAbstractTpl<_Scalar> Differential action model for free forward dynamics in multibody systems.
This class implements free forward dynamics, i.e.,
\[ \mathbf{M}\dot{\mathbf{v}} + \mathbf{h}(\mathbf{q},\mathbf{v}) = \boldsymbol{\tau}, \]where \(\mathbf{q}\in Q\), \(\mathbf{v}\in\mathbb{R}^{nv}\) are the configuration point and generalized velocity (its tangent vector), respectively; \(\boldsymbol{\tau}\) is the torque inputs and \(\mathbf{h}(\mathbf{q},\mathbf{v})\) are the Coriolis effect and gravity field.The derivatives of the system acceleration is computed efficiently based on the analytical derivatives of Articulate Body Algorithm (ABA) as described in carpentier-rss18.
The stack of cost functions is implemented in
CostModelSumTpl. The computation of the free forward dynamics and its derivatives are carrying out insidecalc()andcalcDiff()functions, respectively. It is also important to remark thatcalcDiff()computes the derivatives using the latest stored values bycalc(). Thus, we need to runcalc()first.Public Types
-
typedef DifferentialActionModelAbstractTpl<Scalar> Base
-
typedef DifferentialActionDataFreeFwdDynamicsTpl<Scalar> Data
-
typedef DifferentialActionDataAbstractTpl<Scalar> DifferentialActionDataAbstract
-
typedef StateMultibodyTpl<Scalar> StateMultibody
-
typedef CostModelSumTpl<Scalar> CostModelSum
-
typedef ConstraintModelManagerTpl<Scalar> ConstraintModelManager
-
typedef ActuationModelAbstractTpl<Scalar> ActuationModelAbstract
-
typedef MathBaseTpl<Scalar> MathBase
Public Functions
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW CROCODDYL_DERIVED_CAST (DifferentialActionModelBase, DifferentialActionModelFreeFwdDynamicsTpl) typedef _Scalar Scalar
-
virtual ~DifferentialActionModelFreeFwdDynamicsTpl() = default
Compute the system acceleration, and cost value.
It computes the system acceleration using the free forward-dynamics.
- Parameters:
data – [in] Free forward-dynamics data
x – [in] State point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
u – [in] Control input \(\mathbf{u}\in\mathbb{R}^{nu}\)
Compute the derivatives of the contact dynamics, and cost function.
- Parameters:
data – [in] Free forward-dynamics data
x – [in] State point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
u – [in] Control input \(\mathbf{u}\in\mathbb{R}^{nu}\)
-
virtual std::shared_ptr<DifferentialActionDataAbstract> createData() override
Create the free forward-dynamics data.
- Returns:
free forward-dynamics data
-
template<typename NewScalar>
DifferentialActionModelFreeFwdDynamicsTpl<NewScalar> cast() const Cast the free-fwddyn model to a different scalar type.
It is useful for operations requiring different precision or scalar types.
- Template Parameters:
NewScalar – The new scalar type to cast to.
- Returns:
DifferentialActionModelFreeFwdDynamicsTpl<NewScalar> A differential-action model with the new scalar type.
Check that the given data belongs to the free forward-dynamics data.
Computes the quasic static commands.
The quasic static commands are the ones produced for a the reference posture as an equilibrium point, i.e. for \(\mathbf{f}(\mathbf{q},\mathbf{v}=\mathbf{0},\mathbf{u})=\mathbf{0}\)
- Parameters:
data – [in] Differential action data
u – [out] Quasic static commands
x – [in] State point (velocity has to be zero)
maxiter – [in] Maximum allowed number of iterations
tol – [in] Tolerance
-
virtual std::size_t get_ng() const override
Return the number of inequality constraints.
-
virtual std::size_t get_nh() const override
Return the number of equality constraints.
-
virtual std::size_t get_ng_T() const override
Return the number of equality terminal constraints.
-
virtual std::size_t get_nh_T() const override
Return the number of equality terminal constraints.
-
virtual const VectorXs &get_g_lb() const override
Return the lower bound of the inequality constraints.
-
virtual const VectorXs &get_g_ub() const override
Return the upper bound of the inequality constraints.
-
const std::shared_ptr<ActuationModelAbstract> &get_actuation() const
Return the actuation model.
-
const std::shared_ptr<CostModelSum> &get_costs() const
Return the cost model.
-
const std::shared_ptr<ConstraintModelManager> &get_constraints() const
Return the constraint model manager.
-
pinocchio::ModelTpl<Scalar> &get_pinocchio() const
Return the Pinocchio model.
-
virtual void print(std::ostream &os) const override
Print relevant information of the free forward-dynamics model.
- Parameters:
os – [out] Output stream object
-
typedef DifferentialActionModelAbstractTpl<Scalar> Base