10 #ifndef CROCODDYL_CORE_DIFF_ACTION_BASE_HPP_
11 #define CROCODDYL_CORE_DIFF_ACTION_BASE_HPP_
13 #include <boost/make_shared.hpp>
14 #include <boost/shared_ptr.hpp>
17 #include "crocoddyl/core/fwd.hpp"
18 #include "crocoddyl/core/state-base.hpp"
19 #include "crocoddyl/core/utils/math.hpp"
118 template <
typename _Scalar>
121 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
123 typedef _Scalar Scalar;
128 typedef typename MathBase::VectorXs VectorXs;
129 typedef typename MathBase::MatrixXs MatrixXs;
141 const std::size_t nu,
142 const std::size_t nr = 0,
143 const std::size_t ng = 0,
144 const std::size_t nh = 0);
155 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
156 const Eigen::Ref<const VectorXs>& x,
157 const Eigen::Ref<const VectorXs>& u) = 0;
171 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
172 const Eigen::Ref<const VectorXs>& x);
187 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
188 const Eigen::Ref<const VectorXs>& x,
189 const Eigen::Ref<const VectorXs>& u) = 0;
203 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
204 const Eigen::Ref<const VectorXs>& x);
211 virtual boost::shared_ptr<DifferentialActionDataAbstract>
createData();
217 const boost::shared_ptr<DifferentialActionDataAbstract>& data);
233 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
234 Eigen::Ref<VectorXs> u,
const Eigen::Ref<const VectorXs>& x,
235 const std::size_t maxiter = 100,
const Scalar tol = Scalar(1e-9));
249 const boost::shared_ptr<DifferentialActionDataAbstract>& data,
250 const VectorXs& x,
const std::size_t maxiter = 100,
251 const Scalar tol = Scalar(1e-9));
276 const boost::shared_ptr<StateAbstract>&
get_state()
const;
326 template <
class Scalar>
336 virtual void print(std::ostream& os)
const;
339 std::size_t ng_internal_;
341 std::size_t nh_internal_;
364 template <
class Scalar>
366 template <
class Scalar>
370 template <
typename _Scalar>
372 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
374 typedef _Scalar Scalar;
376 typedef typename MathBase::VectorXs VectorXs;
377 typedef typename MathBase::MatrixXs MatrixXs;
379 template <
template <
typename Scalar>
class Model>
382 xout(model->get_state()->get_nv()),
383 Fx(model->get_state()->get_nv(), model->get_state()->get_ndx()),
384 Fu(model->get_state()->get_nv(), model->get_nu()),
386 Lx(model->get_state()->get_ndx()),
388 Lxx(model->get_state()->get_ndx(), model->get_state()->get_ndx()),
389 Lxu(model->get_state()->get_ndx(), model->get_nu()),
390 Luu(model->get_nu(), model->get_nu()),
392 Gx(model->get_ng(), model->get_state()->get_ndx()),
393 Gu(model->get_ng(), model->get_nu()),
395 Hx(model->get_nh(), model->get_state()->get_ndx()),
396 Hu(model->get_nh(), model->get_nu()) {
444 #include "crocoddyl/core/diff-action-base.hxx"
Manage the individual constraint models.
Abstract class for differential action model.
virtual void calc(const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Compute the total cost value for nodes that depends only on the state.
virtual std::size_t get_ng() const
Return the number of inequality constraints.
void set_g_lb(const VectorXs &g_lb)
Modify the lower bound of the inequality constraints.
virtual void calcDiff(const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)=0
Compute the derivatives of the dynamics and cost functions.
const boost::shared_ptr< StateAbstract > & get_state() const
Return the state.
VectorXs quasiStatic_x(const boost::shared_ptr< DifferentialActionDataAbstract > &data, const VectorXs &x, const std::size_t maxiter=100, const Scalar tol=Scalar(1e-9))
VectorXs u_lb_
Lower control limits.
VectorXs u_ub_
Upper control limits.
virtual std::size_t get_nh() const
Return the number of equality constraints.
virtual boost::shared_ptr< DifferentialActionDataAbstract > createData()
Create the differential action data.
virtual void print(std::ostream &os) const
Print relevant information of the differential action model.
void set_u_ub(const VectorXs &u_ub)
Modify the control upper bounds.
const VectorXs & get_u_ub() const
Return the control upper bound.
virtual void calc(const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)=0
Compute the system acceleration and cost value.
VectorXs g_ub_
Lower bound of the inequality constraints.
friend std::ostream & operator<<(std::ostream &os, const DifferentialActionModelAbstractTpl< Scalar > &model)
Print information on the differential action model.
bool get_has_control_limits() const
Indicates if there are defined control limits.
virtual const VectorXs & get_g_lb() const
Return the lower bound of the inequality constraints.
DifferentialActionModelAbstractTpl(boost::shared_ptr< StateAbstract > state, const std::size_t nu, const std::size_t nr=0, const std::size_t ng=0, const std::size_t nh=0)
Initialize the differential action model.
void update_has_control_limits()
Update the status of the control limits (i.e. if there are defined limits)
boost::shared_ptr< StateAbstract > state_
Model of the state.
std::size_t nu_
Control dimension.
VectorXs unone_
Neutral state.
std::size_t nr_
Dimension of the cost residual.
std::size_t nh_
Number of equality constraints.
std::size_t get_nr() const
Return the dimension of the cost-residual vector.
void set_g_ub(const VectorXs &g_ub)
Modify the upper bound of the inequality constraints.
virtual void quasiStatic(const boost::shared_ptr< DifferentialActionDataAbstract > &data, Eigen::Ref< VectorXs > u, const Eigen::Ref< const VectorXs > &x, const std::size_t maxiter=100, const Scalar tol=Scalar(1e-9))
Computes the quasic static commands.
void set_u_lb(const VectorXs &u_lb)
Modify the control lower bounds.
virtual bool checkData(const boost::shared_ptr< DifferentialActionDataAbstract > &data)
Checks that a specific data belongs to this model.
VectorXs g_lb_
Lower bound of the inequality constraints.
virtual const VectorXs & get_g_ub() const
Return the upper bound of the inequality constraints.
const VectorXs & get_u_lb() const
Return the control lower bound.
virtual void calcDiff(const boost::shared_ptr< DifferentialActionDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
Compute the derivatives of the cost functions with respect to the state only.
std::size_t ng_
Number of inequality constraints.
std::size_t get_nu() const
Return the dimension of the control input.
Abstract class for an integrated action model.
Abstract class for the state representation.
MatrixXs Fx
Jacobian of the dynamics w.r.t. the state .
MatrixXs Fu
Jacobian of the dynamics w.r.t. the control .
VectorXs h
Equality constraint values.
MatrixXs Luu
Hessian of the cost w.r.t. the control .
VectorXs g
Inequality constraint values.
VectorXs Lx
Jacobian of the cost w.r.t. the state .
MatrixXs Lxx
Hessian of the cost w.r.t. the state .
VectorXs Lu
Jacobian of the cost w.r.t. the control .
VectorXs xout
evolution state