9 #ifndef CROCODDYL_CORE_OPTCTRL_SHOOTING_HPP_
10 #define CROCODDYL_CORE_OPTCTRL_SHOOTING_HPP_
15 #include "crocoddyl/core/action-base.hpp"
16 #include "crocoddyl/core/fwd.hpp"
17 #include "crocoddyl/core/utils/deprecate.hpp"
18 #include "crocoddyl/core/utils/exception.hpp"
34 template <
typename _Scalar>
37 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
39 typedef _Scalar Scalar;
43 typedef typename MathBase::VectorXs VectorXs;
53 const std::vector<boost::shared_ptr<ActionModelAbstract> >&
55 boost::shared_ptr<ActionModelAbstract> terminal_model);
68 const std::vector<boost::shared_ptr<ActionModelAbstract> >&
70 boost::shared_ptr<ActionModelAbstract> terminal_model,
71 const std::vector<boost::shared_ptr<ActionDataAbstract> >& running_datas,
72 boost::shared_ptr<ActionDataAbstract> terminal_data);
92 Scalar
calc(
const std::vector<VectorXs>& xs,
const std::vector<VectorXs>& us);
111 const std::vector<VectorXs>& us);
121 void rollout(
const std::vector<VectorXs>& us, std::vector<VectorXs>& xs);
131 std::vector<VectorXs>
rollout_us(
const std::vector<VectorXs>& us);
141 void quasiStatic(std::vector<VectorXs>& us,
const std::vector<VectorXs>& xs);
163 boost::shared_ptr<ActionDataAbstract> data);
184 boost::shared_ptr<ActionModelAbstract> model,
185 boost::shared_ptr<ActionDataAbstract> data);
194 boost::shared_ptr<ActionModelAbstract> model);
209 const std::vector<boost::shared_ptr<ActionModelAbstract> >&
237 const std::vector<boost::shared_ptr<ActionModelAbstract> >& models);
265 DEPRECATED(
"Compute yourself the maximum dimension of the control vector",
266 std::size_t get_nu_max()
const;)
271 std::size_t get_nthreads()
const;
282 template <
class Scalar>
290 boost::shared_ptr<ActionModelAbstract>
292 boost::shared_ptr<ActionDataAbstract>
294 std::vector<boost::shared_ptr<ActionModelAbstract> >
296 std::vector<boost::shared_ptr<ActionDataAbstract> >
314 #include "crocoddyl/core/optctrl/shooting.hxx"
Abstract class for action model.
This class encapsulates a shooting problem.
boost::shared_ptr< ActionDataAbstract > terminal_data_
Terminal action data.
std::vector< VectorXs > quasiStatic_xs(const std::vector< VectorXs > &xs)
Compute the quasic static commands given a state trajectory.
void circularAppend(boost::shared_ptr< ActionModelAbstract > model, boost::shared_ptr< ActionDataAbstract > data)
Circular append of the model and data onto the end running node.
Scalar calcDiff(const std::vector< VectorXs > &xs, const std::vector< VectorXs > &us)
Compute the derivatives of the cost and dynamics.
void quasiStatic(std::vector< VectorXs > &us, const std::vector< VectorXs > &xs)
Compute the quasic static commands given a state trajectory.
void rollout(const std::vector< VectorXs > &us, std::vector< VectorXs > &xs)
Integrate the dynamics given a control sequence.
std::vector< VectorXs > rollout_us(const std::vector< VectorXs > &us)
Integrate the dynamics given a control sequence.
const std::vector< boost::shared_ptr< ActionModelAbstract > > & get_runningModels() const
Return the running models.
std::size_t get_ndx() const
Return the dimension of the tangent space of the state manifold.
ShootingProblemTpl(const VectorXs &x0, const std::vector< boost::shared_ptr< ActionModelAbstract > > &running_models, boost::shared_ptr< ActionModelAbstract > terminal_model, const std::vector< boost::shared_ptr< ActionDataAbstract > > &running_datas, boost::shared_ptr< ActionDataAbstract > terminal_data)
Initialize the shooting problem (models and datas)
const std::vector< boost::shared_ptr< ActionDataAbstract > > & get_runningDatas() const
Return the running datas.
ShootingProblemTpl(const VectorXs &x0, const std::vector< boost::shared_ptr< ActionModelAbstract > > &running_models, boost::shared_ptr< ActionModelAbstract > terminal_model)
Initialize the shooting problem and allocate its data.
std::size_t nx_
State dimension.
Scalar calc(const std::vector< VectorXs > &xs, const std::vector< VectorXs > &us)
Compute the cost and the next states.
void set_terminalModel(boost::shared_ptr< ActionModelAbstract > model)
Modify the terminal model and allocate new data.
void updateNode(const std::size_t i, boost::shared_ptr< ActionModelAbstract > model, boost::shared_ptr< ActionDataAbstract > data)
Update the model and data for a specific node.
ShootingProblemTpl(const ShootingProblemTpl< Scalar > &problem)
Initialize the shooting problem.
std::size_t T_
number of running nodes
std::vector< boost::shared_ptr< ActionModelAbstract > > running_models_
Running action model.
friend std::ostream & operator<<(std::ostream &os, const ShootingProblemTpl< Scalar > &problem)
Print information on the 'ShootingProblem'.
void updateModel(const std::size_t i, boost::shared_ptr< ActionModelAbstract > model)
Update a model and allocated new data for a specific node.
const boost::shared_ptr< ActionModelAbstract > & get_terminalModel() const
Return the terminal model.
void set_x0(const VectorXs &x0_in)
Modify the initial state.
void set_runningModels(const std::vector< boost::shared_ptr< ActionModelAbstract > > &models)
Modify the running models and allocate new data.
std::vector< boost::shared_ptr< ActionDataAbstract > > running_datas_
Running action data.
void set_nthreads(const int nthreads)
Modify the number of threads using with multithreading support.
boost::shared_ptr< ActionModelAbstract > terminal_model_
Terminal action model.
std::size_t get_T() const
Return the number of running nodes.
DEPRECATED("Compute yourself the maximum dimension of the control vector", std::size_t get_nu_max() const ;) std bool is_updated()
Return the maximum dimension of the control vector.
const boost::shared_ptr< ActionDataAbstract > & get_terminalData() const
Return the terminal data.
void circularAppend(boost::shared_ptr< ActionModelAbstract > model)
Circular append of the model and data onto the end running node.
std::size_t get_nx() const
Return the dimension of the state tuple.
VectorXs x0_
Initial state.
std::size_t nu_max_
Maximum control dimension.
const VectorXs & get_x0() const
Return the initial state.
std::size_t ndx_
State rate dimension.