Crocoddyl
shooting.hpp
1 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-2021, LAAS-CNRS, University of Edinburgh, University of
5 // Oxford Copyright note valid unless otherwise stated in individual files. All
6 // rights reserved.
8 
9 #ifndef CROCODDYL_CORE_OPTCTRL_SHOOTING_HPP_
10 #define CROCODDYL_CORE_OPTCTRL_SHOOTING_HPP_
11 
12 #include <stdexcept>
13 #include <vector>
14 
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"
19 
20 namespace crocoddyl {
21 
34 template <typename _Scalar>
36  public:
37  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
38 
39  typedef _Scalar Scalar;
43  typedef typename MathBase::VectorXs VectorXs;
44 
52  ShootingProblemTpl(const VectorXs& x0,
53  const std::vector<boost::shared_ptr<ActionModelAbstract> >&
54  running_models,
55  boost::shared_ptr<ActionModelAbstract> terminal_model);
56 
67  const VectorXs& x0,
68  const std::vector<boost::shared_ptr<ActionModelAbstract> >&
69  running_models,
70  boost::shared_ptr<ActionModelAbstract> terminal_model,
71  const std::vector<boost::shared_ptr<ActionDataAbstract> >& running_datas,
72  boost::shared_ptr<ActionDataAbstract> terminal_data);
78 
92  Scalar calc(const std::vector<VectorXs>& xs, const std::vector<VectorXs>& us);
93 
110  Scalar calcDiff(const std::vector<VectorXs>& xs,
111  const std::vector<VectorXs>& us);
112 
121  void rollout(const std::vector<VectorXs>& us, std::vector<VectorXs>& xs);
122 
131  std::vector<VectorXs> rollout_us(const std::vector<VectorXs>& us);
132 
141  void quasiStatic(std::vector<VectorXs>& us, const std::vector<VectorXs>& xs);
142 
151  std::vector<VectorXs> quasiStatic_xs(const std::vector<VectorXs>& xs);
152 
162  void circularAppend(boost::shared_ptr<ActionModelAbstract> model,
163  boost::shared_ptr<ActionDataAbstract> data);
164 
174  void circularAppend(boost::shared_ptr<ActionModelAbstract> model);
175 
183  void updateNode(const std::size_t i,
184  boost::shared_ptr<ActionModelAbstract> model,
185  boost::shared_ptr<ActionDataAbstract> data);
186 
193  void updateModel(const std::size_t i,
194  boost::shared_ptr<ActionModelAbstract> model);
195 
199  std::size_t get_T() const;
200 
204  const VectorXs& get_x0() const;
205 
209  const std::vector<boost::shared_ptr<ActionModelAbstract> >&
211 
215  const boost::shared_ptr<ActionModelAbstract>& get_terminalModel() const;
216 
220  const std::vector<boost::shared_ptr<ActionDataAbstract> >& get_runningDatas()
221  const;
222 
226  const boost::shared_ptr<ActionDataAbstract>& get_terminalData() const;
227 
231  void set_x0(const VectorXs& x0_in);
232 
237  const std::vector<boost::shared_ptr<ActionModelAbstract> >& models);
238 
242  void set_terminalModel(boost::shared_ptr<ActionModelAbstract> model);
243 
250  void set_nthreads(const int nthreads);
251 
255  std::size_t get_nx() const;
256 
260  std::size_t get_ndx() const;
261 
265  DEPRECATED("Compute yourself the maximum dimension of the control vector",
266  std::size_t get_nu_max() const;)
267 
271  std::size_t get_nthreads() const;
272 
277  bool is_updated();
278 
282  template <class Scalar>
283  friend std::ostream& operator<<(std::ostream& os,
284  const ShootingProblemTpl<Scalar>& problem);
285 
286  protected:
287  Scalar cost_;
288  std::size_t T_;
289  VectorXs x0_;
290  boost::shared_ptr<ActionModelAbstract>
292  boost::shared_ptr<ActionDataAbstract>
294  std::vector<boost::shared_ptr<ActionModelAbstract> >
296  std::vector<boost::shared_ptr<ActionDataAbstract> >
298  std::size_t nx_;
299  std::size_t ndx_;
300  std::size_t nu_max_;
301  std::size_t nthreads_;
303  bool is_updated_;
304 
305  private:
306  void allocateData();
307 };
308 
309 } // namespace crocoddyl
310 
311 /* --- Details -------------------------------------------------------------- */
312 /* --- Details -------------------------------------------------------------- */
313 /* --- Details -------------------------------------------------------------- */
314 #include "crocoddyl/core/optctrl/shooting.hxx"
315 
316 #endif // CROCODDYL_CORE_OPTCTRL_SHOOTING_HPP_
Abstract class for action model.
Definition: action-base.hpp:95
This class encapsulates a shooting problem.
Definition: shooting.hpp:35
boost::shared_ptr< ActionDataAbstract > terminal_data_
Terminal action data.
Definition: shooting.hpp:293
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.
Definition: shooting.hpp:298
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
Definition: shooting.hpp:288
std::vector< boost::shared_ptr< ActionModelAbstract > > running_models_
Running action model.
Definition: shooting.hpp:295
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.
Scalar cost_
Total cost.
Definition: shooting.hpp:287
std::vector< boost::shared_ptr< ActionDataAbstract > > running_datas_
Running action data.
Definition: shooting.hpp:297
void set_nthreads(const int nthreads)
Modify the number of threads using with multithreading support.
boost::shared_ptr< ActionModelAbstract > terminal_model_
Terminal action model.
Definition: shooting.hpp:291
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.
Definition: shooting.hpp:289
std::size_t nu_max_
Maximum control dimension.
Definition: shooting.hpp:300
const VectorXs & get_x0() const
Return the initial state.
std::size_t ndx_
State rate dimension.
Definition: shooting.hpp:299