Template Class ActionModelImpulseFwdDynamicsTpl
Defined in File impulse-fwddyn.hpp
Inheritance Relationships
Base Type
public crocoddyl::ActionModelAbstractTpl< _Scalar >(Template Class ActionModelAbstractTpl)
Class Documentation
-
template<typename _Scalar>
class ActionModelImpulseFwdDynamicsTpl : public crocoddyl::ActionModelAbstractTpl<_Scalar> Action model for impulse forward dynamics in multibody systems.
This class implements impulse forward dynamics given a stack of rigid-impulses described in
ImpulseModelMultipleTpl, i.e.,\[\begin{split} \left[\begin{matrix}\mathbf{v}^+ \\ -\boldsymbol{\Lambda}\end{matrix}\right] = \left[\begin{matrix}\mathbf{M} & \mathbf{J}^{\top}_c \\ {\mathbf{J}_{c}} & \mathbf{0} \end{matrix}\right]^{-1} \left[\begin{matrix}\mathbf{M}\mathbf{v}^- \\ -e\mathbf{J}_c\mathbf{v}^- \\\end{matrix}\right], \end{split}\]where \(\mathbf{q}\in Q\), \(\mathbf{v}\in\mathbb{R}^{nv}\) are the configuration point and generalized velocity (its tangent vector), respectively; \(\mathbf{v}^+\), \(\mathbf{v}^-\) are the discontinuous changes in the generalized velocity (i.e., velocity before and after impact, respectively); \(\mathbf{J}_c\in\mathbb{R}^{nc\times nv}\) is the contact Jacobian expressed in the local frame; and \(\boldsymbol{\Lambda}\in\mathbb{R}^{nc}\) is the impulse vector.The derivatives of the next state and contact impulses are computed efficiently based on the analytical derivatives of Recursive Newton Euler Algorithm (RNEA) as described in mastalli-icra20. Note that the algorithm for computing the RNEA derivatives is described in carpentier-rss18.
The stack of cost and constraint functions are implemented in
CostModelSumTplandConstraintModelAbstractTpl, respectively. The computation of the impulse 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.See also
Public Types
-
typedef ActionModelAbstractTpl<Scalar> Base
-
typedef ActionDataImpulseFwdDynamicsTpl<Scalar> Data
-
typedef MathBaseTpl<Scalar> MathBase
-
typedef CostModelSumTpl<Scalar> CostModelSum
-
typedef ConstraintModelManagerTpl<Scalar> ConstraintModelManager
-
typedef StateMultibodyTpl<Scalar> StateMultibody
-
typedef ActionDataAbstractTpl<Scalar> ActionDataAbstract
-
typedef ImpulseModelMultipleTpl<Scalar> ImpulseModelMultiple
Public Functions
Initialize the impulse forward-dynamics action model.
It describes the impulse dynamics of a multibody system under rigid-contact constraints defined by
ImpulseModelMultipleTpl. It computes the cost described inCostModelSumTpl.- Parameters:
state – [in] State of the multibody system
actuation – [in] Actuation model
impulses – [in] Stack of rigid impulses
costs – [in] Stack of cost functions
r_coeff – [in] Restitution coefficient (default 0.)
JMinvJt_damping – [in] Damping term used in operational space inertia matrix (default 0.)
enable_force – [in] Enable the computation of the contact force derivatives (default false)
Initialize the impulse forward-dynamics action model.
It describes the impulse dynamics of a multibody system under rigid-contact constraints defined by
ImpulseModelMultipleTpl. It computes the cost described inCostModelSumTpl.- Parameters:
state – [in] State of the multibody system
actuation – [in] Actuation model
impulses – [in] Stack of rigid impulses
costs – [in] Stack of cost functions
constraints – [in] Stack of constraints
r_coeff – [in] Restitution coefficient (default 0.)
JMinvJt_damping – [in] Damping term used in operational space inertia matrix (default 0.)
enable_force – [in] Enable the computation of the contact force derivatives (default false)
-
virtual ~ActionModelImpulseFwdDynamicsTpl() = default
Compute the system acceleration, and cost value.
It computes the system acceleration using the impulse dynamics.
- Parameters:
data – [in] Impulse 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 total cost value for nodes that depends only on the state.
It updates the total cost and the system acceleration is not updated as it is expected to be zero. Additionally, it does not update the contact forces. This function is used in the terminal nodes of an optimal control problem.
- Parameters:
data – [in] Impulse forward-dynamics data
x – [in] State point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
Compute the derivatives of the impulse dynamics, and cost function.
- Parameters:
data – [in] Impulse 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 cost functions with respect to the state only.
It updates the derivatives of the cost function with respect to the state only. Additionally, it does not update the contact forces derivatives. This function is used in the terminal nodes of an optimal control problem.
- Parameters:
data – [in] Impulse forward-dynamics data
x – [in] State point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
-
virtual std::shared_ptr<ActionDataAbstract> createData() override
Create the impulse forward-dynamics data.
- Returns:
impulse forward-dynamics data
-
template<typename NewScalar>
ActionModelImpulseFwdDynamicsTpl<NewScalar> cast() const Cast the impulse-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:
ActionModelImpulseFwdDynamicsTpl<NewScalar> An action model with the new scalar type.
Check that the given data belongs to the impulse 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^q_x}\delta\mathbf{q}+\mathbf{f_u}\delta\mathbf{u}=\mathbf{0}\)
- Parameters:
data – [in] 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<ImpulseModelMultiple> &get_impulses() const
Return the impulse 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.
-
const Scalar get_restitution_coefficient() const
Return the restituion coefficient.
-
const Scalar get_damping_factor() const
Return the damping factor used in the operational space inertia matrix.
-
void set_restitution_coefficient(const Scalar r_coeff)
Modify the restituion coefficient.
-
void set_damping_factor(const Scalar damping)
Modify the damping factor used in the operational space inertia matrix.
-
virtual void print(std::ostream &os) const override
Print relevant information of the impulse forward-dynamics model.
- Parameters:
os – [out] Output stream object
Public Members
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
-
typedef ActionModelAbstractTpl<Scalar> Base