Template Class ActionModelAbstractTpl
Defined in File action-base.hpp
Inheritance Relationships
Base Type
public crocoddyl::ActionModelBase(Class ActionModelBase)
Derived Types
public crocoddyl::ActionModelImpulseFwdDynamicsTpl< _Scalar >(Template Class ActionModelImpulseFwdDynamicsTpl)public crocoddyl::ActionModelLQRTpl< _Scalar >(Template Class ActionModelLQRTpl)public crocoddyl::ActionModelNumDiffTpl< _Scalar >(Template Class ActionModelNumDiffTpl)public crocoddyl::ActionModelUnicycleTpl< _Scalar >(Template Class ActionModelUnicycleTpl)public crocoddyl::IntegratedActionModelAbstractTpl< _Scalar >(Template Class IntegratedActionModelAbstractTpl)
Class Documentation
-
template<typename _Scalar>
class ActionModelAbstractTpl : public crocoddyl::ActionModelBase Abstract class for action model.
An action model combines dynamics, cost functions and constraints. Each node, in our optimal control problem, is described through an action model. Every time that we want describe a problem, we need to provide ways of computing the dynamics, cost functions, constraints and their derivatives. All these is described inside the action model.
Concretely speaking, the action model describes a time-discrete action model with a first-order ODE along a cost function, i.e.
the state \(\mathbf{z}\in\mathcal{Z}\) lies in a manifold described with a
nx-tuple,the state rate \(\mathbf{\dot{x}}\in T_{\mathbf{q}}\mathcal{Q}\) is the tangent vector to the state manifold with
ndxdimension,the control input \(\mathbf{u}\in\mathbb{R}^{nu}\) is an Euclidean vector
\(\mathbf{r}(\cdot)\) and \(a(\cdot)\) are the residual and activation functions (see
ResidualModelAbstractTplandActivationModelAbstractTpl, respetively),\(\mathbf{g}(\cdot)\in\mathbb{R}^{ng}\) and \(\mathbf{h}(\cdot)\in\mathbb{R}^{nh}\) are the inequality and equality vector functions, respectively.
The computation of these equations are carried out out inside
calc()function. In short, this function computes the system acceleration, cost and constraints values (also called constraints violations). This procedure is equivalent to running a forward pass of the action model.However, during numerical optimization, we also need to run backward passes of the action model. These calculations are performed by
calcDiff(). In short, this method builds a linear-quadratic approximation of the action model, i.e.:\[\begin{split} \begin{aligned} &\delta\mathbf{x}_{k+1} = \mathbf{f_x}\delta\mathbf{x}_k+\mathbf{f_u}\delta\mathbf{u}_k, &\textrm{(dynamics)}\\ &\ell(\delta\mathbf{x}_k,\delta\mathbf{u}_k) = \begin{bmatrix}1 \\ \delta\mathbf{x}_k \\ \delta\mathbf{u}_k\end{bmatrix}^T \begin{bmatrix}0 & \mathbf{\ell_x}^T & \mathbf{\ell_u}^T \\ \mathbf{\ell_x} & \mathbf{\ell_{xx}} & \mathbf{\ell_{ux}}^T \\ \mathbf{\ell_u} & \mathbf{\ell_{ux}} & \mathbf{\ell_{uu}}\end{bmatrix} \begin{bmatrix}1 \\ \delta\mathbf{x}_k \\ \delta\mathbf{u}_k\end{bmatrix}, &\textrm{(cost)}\\ &\mathbf{g}(\delta\mathbf{x}_k,\delta\mathbf{u}_k)<\mathbf{0}, &\textrm{(inequality constraint)}\\ &\mathbf{h}(\delta\mathbf{x}_k,\delta\mathbf{u}_k)=\mathbf{0}, &\textrm{(equality constraint)} \end{aligned} \end{split}\]where\(\mathbf{f_x}\in\mathbb{R}^{ndx\times ndx}\) and \(\mathbf{f_u}\in\mathbb{R}^{ndx\times nu}\) are the Jacobians of the dynamics,
\(\mathbf{\ell_x}\in\mathbb{R}^{ndx}\) and \(\mathbf{\ell_u}\in\mathbb{R}^{nu}\) are the Jacobians of the cost function,
\(\mathbf{\ell_{xx}}\in\mathbb{R}^{ndx\times ndx}\), \(\mathbf{\ell_{xu}}\in\mathbb{R}^{ndx\times nu}\) and \(\mathbf{\ell_{uu}}\in\mathbb{R}^{nu\times nu}\) are the Hessians of the cost function,
\(\mathbf{g_x}\in\mathbb{R}^{ng\times ndx}\) and \(\mathbf{g_u}\in\mathbb{R}^{ng\times nu}\) are the Jacobians of the inequality constraints, and
\(\mathbf{h_x}\in\mathbb{R}^{nh\times ndx}\) and \(\mathbf{h_u}\in\mathbb{R}^{nh\times nu}\) are the Jacobians of the equality constraints.
Additionally, it is important to note that
calcDiff()computes the derivatives using the latest stored values bycalc(). Thus, we need to first runcalc().See also
Subclassed by crocoddyl::ActionModelImpulseFwdDynamicsTpl< _Scalar >, crocoddyl::ActionModelLQRTpl< _Scalar >, crocoddyl::ActionModelNumDiffTpl< _Scalar >, crocoddyl::ActionModelUnicycleTpl< _Scalar >, crocoddyl::IntegratedActionModelAbstractTpl< _Scalar >
Public Types
-
typedef ScalarSelector<Scalar>::type ScalarType
-
typedef MathBaseTpl<Scalar> MathBase
-
typedef ActionDataAbstractTpl<Scalar> ActionDataAbstract
-
typedef StateAbstractTpl<Scalar> StateAbstract
Public Functions
Initialize the action model.
- Parameters:
state – [in] State description
nu – [in] Dimension of control vector
nr – [in] Dimension of cost-residual vector
ng – [in] Number of inequality constraints (default 0)
nh – [in] Number of equality constraints (default 0)
ng_T – [in] Number of inequality terminal constraints (default 0)
nh_T – [in] Number of equality terminal constraints (default 0)
-
ActionModelAbstractTpl(const ActionModelAbstractTpl<Scalar> &other)
Copy constructor.
- Parameters:
other – Action model to be copied
-
virtual ~ActionModelAbstractTpl() = default
Compute the next state and cost value.
- Parameters:
data – [in] Action 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 next state is not computed as it is not expected to change. This function is used in the terminal nodes of an optimal control problem.
- Parameters:
data – [in] Action data
x – [in] State point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
Compute the derivatives of the dynamics and cost functions.
It computes the partial derivatives of the dynamical system and the cost function. It assumes that
calc()has been run first. This function builds a linear-quadratic approximation of the action model (i.e. dynamical system and cost function).- Parameters:
data – [in] Action 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. This function is used in the terminal nodes of an optimal control problem.
- Parameters:
data – [in] Action data
x – [in] State point \(\mathbf{x}\in\mathbb{R}^{ndx}\)
-
virtual std::shared_ptr<ActionDataAbstract> createData()
Create the action data.
- Returns:
the action data
Checks that a specific data belongs to this model.
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
- Parameters:
data – [in] Action data
x – [in] State point (velocity has to be zero)
maxiter – [in] Maximum allowed number of iterations
tol – [in] Tolerance
- Returns:
Quasic static commands
-
std::size_t get_nu() const
Return the dimension of the control input.
-
std::size_t get_nr() const
Return the dimension of the cost-residual vector.
-
virtual std::size_t get_ng() const
Return the number of inequality constraints.
-
virtual std::size_t get_nh() const
Return the number of equality constraints.
-
virtual std::size_t get_ng_T() const
Return the number of inequality terminal constraints.
-
virtual std::size_t get_nh_T() const
Return the number of equality terminal constraints.
-
const std::shared_ptr<StateAbstract> &get_state() const
Return the state.
-
bool get_has_control_limits() const
Indicates if there are defined control limits.
-
virtual void print(std::ostream &os) const
Print relevant information of the action model.
- Parameters:
os – [out] Output stream object
Public Members
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
Protected Functions
-
inline ActionModelAbstractTpl()
-
void update_has_control_limits()
Update the status of the control limits (i.e. if there are defined limits)
Protected Attributes
-
std::size_t nu_
Control dimension.
-
std::size_t nr_
Dimension of the cost residual.
-
std::size_t ng_
Number of inequality constraints.
-
std::size_t nh_
Number of equality constraints.
-
std::size_t ng_T_
Number of inequality terminal constraints.
-
std::size_t nh_T_
Number of equality terminal constraints.
-
std::shared_ptr<StateAbstract> state_
Model of the state.
-
bool has_control_limits_
Indicates whether any of the control limits is finite
Friends
- friend class ConstraintModelManagerTpl
-
template<class Scalar>
friend std::ostream &operator<<(std::ostream &os, const ActionModelAbstractTpl<Scalar> &model) Print information on the action model.