sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
nd-trajectory-generator.hh
Go to the documentation of this file.
1 /*
2  * Copyright 2017,Thomas Flayols, LAAS-CNRS
3  * File derived from sot-torque-control package available on
4  * https://github.com/stack-of-tasks/sot-torque-control
5  *
6  * This file is part of sot-talos-balance.
7  * sot-talos-balance is free software: you can redistribute it and/or
8  * modify it under the terms of the GNU Lesser General Public License
9  * as published by the Free Software Foundation, either version 3 of
10  * the License, or (at your option) any later version.
11  * sot-torque-control is distributed in the hope that it will be
12  * useful, but WITHOUT ANY WARRANTY; without even the implied warranty
13  * of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU Lesser General Public License for more details. You should
15  * have received a copy of the GNU Lesser General Public License along
16  * with sot-talos-balance. If not, see <http://www.gnu.org/licenses/>.
17  */
18 
19 #ifndef __sot_talos_balance_nd_trajectory_generator_H__
20 #define __sot_talos_balance_nd_trajectory_generator_H__
21 
22 /* --------------------------------------------------------------------- */
23 /* --- API ------------------------------------------------------------- */
24 /* --------------------------------------------------------------------- */
25 
26 #if defined(WIN32)
27 #if defined(nd_position_controller_EXPORTS)
28 #define SOTNDTRAJECTORYGENERATOR_EXPORT __declspec(dllexport)
29 #else
30 #define SOTNDTRAJECTORYGENERATOR_EXPORT __declspec(dllimport)
31 #endif
32 #else
33 #define SOTNDTRAJECTORYGENERATOR_EXPORT
34 #endif
35 
36 /* --------------------------------------------------------------------- */
37 /* --- INCLUDE --------------------------------------------------------- */
38 /* --------------------------------------------------------------------- */
39 
40 #include <dynamic-graph/signal-helper.h>
41 
42 #include <map>
43 #include <parametric-curves/constant.hpp>
44 #include <parametric-curves/infinite-const-acc.hpp>
45 #include <parametric-curves/infinite-sinusoid.hpp>
46 #include <parametric-curves/linear-chirp.hpp>
47 #include <parametric-curves/minimum-jerk.hpp>
48 #include <parametric-curves/spline.hpp>
49 #include <parametric-curves/text-file.hpp>
50 #include <sot/core/matrix-geometry.hh>
51 
52 #include "boost/assign.hpp"
53 
54 namespace dynamicgraph {
55 namespace sot {
56 namespace talos_balance {
57 
58 /* --------------------------------------------------------------------- */
59 /* --- CLASS ----------------------------------------------------------- */
60 /* --------------------------------------------------------------------- */
61 
63  : public ::dynamicgraph::Entity {
65  DYNAMIC_GRAPH_ENTITY_DECL();
66 
67  public:
68  /* --- CONSTRUCTOR ---- */
69  NdTrajectoryGenerator(const std::string& name);
70 
71  void init(const double& dt, const unsigned int& n);
72 
73  /* --- SIGNALS --- */
75  DECLARE_SIGNAL_IN(trigger, bool);
79 
80  protected:
82 
83  public:
84  /* --- COMMANDS --- */
85 
86  void playTrajectoryFile(const std::string& fileName);
87 
88  void playSpline(const std::string& fileName);
89 
90  void setSpline(const std::string& filename, const double& timeToInitConf);
91  void startSpline();
92 
94  void getValue(const int& id);
95 
101  void move(const int& id, const double& xFinal, const double& time);
102 
107  void set(const int& id, const double& xVal);
108 
115  void startSinusoid(const int& id, const double& xFinal, const double& time);
116 
123  // void startTriangle(const int& id, const double& xFinal, const double& time,
124  // const double& Tacc);
125 
133  void startConstAcc(const int& id, const double& xFinal, const double& time);
134 
144  void startLinearChirp(const int& id, const double& xFinal, const double& f0,
145  const double& f1, const double& time);
146 
151  void stop(const int& id);
152 
153  /* --- ENTITY INHERITANCE --- */
154  virtual void display(std::ostream& os) const;
155 
156  protected:
157  enum JTG_Status {
162  // JTG_TRIANGLE,
165  JTG_SPLINE
166  };
167 
168  bool
170  bool m_firstIter;
171  double m_dt;
172  double m_t;
173  unsigned int m_n;
174  unsigned int m_iterLast;
176 
177  std::vector<JTG_Status> m_status;
178  std::vector<
179  parametriccurves::AbstractCurve<double, dynamicgraph::sot::Vector1d>*>
181  std::vector<parametriccurves::Constant<double, 1>*> m_noTrajGen;
182  std::vector<parametriccurves::MinimumJerk<double, 1>*> m_minJerkTrajGen;
183  std::vector<parametriccurves::InfiniteSinusoid<double, 1>*> m_sinTrajGen;
184  std::vector<parametriccurves::LinearChirp<double, 1>*> m_linChirpTrajGen;
185  // std::vector<parametriccurves::InfiniteTriangular<double,1>* >
186  // m_triangleTrajGen;
187  std::vector<parametriccurves::InfiniteConstAcc<double, 1>*> m_constAccTrajGen;
188  parametriccurves::TextFile<double, Eigen::Dynamic>* m_textFileTrajGen;
189  parametriccurves::Spline<double, Eigen::Dynamic>* m_splineTrajGen;
190 
191 }; // class NdTrajectoryGenerator
192 
193 } // namespace talos_balance
194 } // namespace sot
195 } // namespace dynamicgraph
196 
197 #endif // #ifndef __sot_talos_balance_nd_trajectory_generator_H__
parametriccurves::TextFile< double, Eigen::Dynamic > * m_textFileTrajGen
std::vector< parametriccurves::Constant< double, 1 > * > m_noTrajGen
DECLARE_SIGNAL_IN(initial_value, dynamicgraph::Vector)
std::vector< parametriccurves::InfiniteSinusoid< double, 1 > * > m_sinTrajGen
double m_dt
true if it is the first iteration, false otherwise
parametriccurves::Spline< double, Eigen::Dynamic > * m_splineTrajGen
std::vector< parametriccurves::InfiniteConstAcc< double, 1 > * > m_constAccTrajGen
std::vector< parametriccurves::MinimumJerk< double, 1 > * > m_minJerkTrajGen
bool m_firstIter
true if the entity has been successfully initialized
std::vector< parametriccurves::AbstractCurve< double, dynamicgraph::sot::Vector1d > * > m_currentTrajGen
status of the component
std::vector< JTG_Status > m_status
true if the spline has been successfully loaded.
std::vector< parametriccurves::LinearChirp< double, 1 > * > m_linChirpTrajGen
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: fwd.hh:36
#define SOTNDTRAJECTORYGENERATOR_EXPORT