19 #ifndef __sot_talos_balance_nd_trajectory_generator_H__
20 #define __sot_talos_balance_nd_trajectory_generator_H__
27 #if defined(nd_position_controller_EXPORTS)
28 #define SOTNDTRAJECTORYGENERATOR_EXPORT __declspec(dllexport)
30 #define SOTNDTRAJECTORYGENERATOR_EXPORT __declspec(dllimport)
33 #define SOTNDTRAJECTORYGENERATOR_EXPORT
40 #include <dynamic-graph/signal-helper.h>
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>
52 #include "boost/assign.hpp"
56 namespace talos_balance {
63 :
public ::dynamicgraph::Entity {
65 DYNAMIC_GRAPH_ENTITY_DECL();
71 void init(
const double&
dt,
const unsigned int& n);
86 void playTrajectoryFile(
const std::string& fileName);
90 void setSpline(
const std::string& filename,
const double& timeToInitConf);
94 void getValue(
const int&
id);
101 void move(
const int&
id,
const double& xFinal,
const double& time);
107 void set(
const int&
id,
const double& xVal);
115 void startSinusoid(
const int&
id,
const double& xFinal,
const double& time);
133 void startConstAcc(
const int&
id,
const double& xFinal,
const double& time);
144 void startLinearChirp(
const int&
id,
const double& xFinal,
const double& f0,
145 const double& f1,
const double& time);
151 void stop(
const int&
id);
154 virtual void display(std::ostream& os)
const;
179 parametriccurves::AbstractCurve<double, dynamicgraph::sot::Vector1d>*>
183 std::vector<parametriccurves::InfiniteSinusoid<double, 1>*>
m_sinTrajGen;
parametriccurves::TextFile< double, Eigen::Dynamic > * m_textFileTrajGen
std::vector< parametriccurves::Constant< double, 1 > * > m_noTrajGen
DECLARE_SIGNAL_IN(initial_value, dynamicgraph::Vector)
DECLARE_SIGNAL_IN(trigger, bool)
std::vector< parametriccurves::InfiniteSinusoid< double, 1 > * > m_sinTrajGen
double m_t
control loop time step.
bool m_splineReady
last iter index
unsigned int m_n
current control loop time.
unsigned int m_iterLast
size of ouput vector
double m_dt
true if it is the first iteration, false otherwise
DECLARE_SIGNAL_OUT_FUNCTION(x, dynamicgraph::Vector)
parametriccurves::Spline< double, Eigen::Dynamic > * m_splineTrajGen
std::vector< parametriccurves::InfiniteConstAcc< double, 1 > * > m_constAccTrajGen
DECLARE_SIGNAL_OUT(dx, dynamicgraph::Vector)
std::vector< parametriccurves::MinimumJerk< double, 1 > * > m_minJerkTrajGen
bool m_firstIter
true if the entity has been successfully initialized
DECLARE_SIGNAL_OUT(ddx, dynamicgraph::Vector)
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.
void playSpline(const std::string &fileName)
DECLARE_SIGNAL(x, OUT, dynamicgraph::Vector)
std::vector< parametriccurves::LinearChirp< double, 1 > * > m_linChirpTrajGen
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
AdmittanceControllerEndEffector EntityClassName
#define SOTNDTRAJECTORYGENERATOR_EXPORT