cubic-interpolation-se3.cc
Go to the documentation of this file.
1 //
2 // Copyright (C) 2012 LAAS-CNRS
3 //
4 // Author: Florent Lamiraux
5 //
6 
8 
11 #include <dynamic-graph/command.h>
12 #include <dynamic-graph/factory.h>
13 
14 namespace dynamicgraph {
15 namespace sot {
16 namespace tools {
17 DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(CubicInterpolationSE3,
18  "CubicInterpolationSE3");
20  : Entity(name),
21  soutSOUT_("CubicInterpolationSE3(" + name +
22  ")::output(MatrixHomo)::sout"),
23  soutdotSOUT_("CubicInterpolationSE3(" + name +
24  ")::output(vector)::soutdot"),
25  initSIN_(NULL,
26  "CubicInterpolationSE3(" + name + ")::input(MatrixHomo)::init"),
27  goalSIN_(NULL,
28  "CubicInterpolationSE3(" + name + ")::input(MatrixHomo)::goal"),
29  startTime_(0),
30  samplingPeriod_(0.),
31  state_(0),
32  p0_(3),
33  p1_(3),
34  p2_(3),
35  p3_(3),
36  position_(3),
37  soutdot_(3) {
43  boost::bind(&CubicInterpolationSE3::computeSout, this, _1, _2));
44  soutdot_.setZero();
46 
47  std::string docstring;
48  docstring =
49  "\n"
50  " Set sampling period of control discretization.\n"
51  "\n"
52  " Input:\n"
53  " - a floating point value.\n"
54  "\n";
55  addCommand("setSamplingPeriod",
57  *this, &CubicInterpolationSE3::setSamplingPeriod, docstring));
58  docstring =
59  "\n"
60  " Start tracking.\n"
61  "\n"
62  " Input\n"
63  " - duration of the motion.\n"
64  "\n"
65  "\n Read init and goal signals, compute output trajectory and start\n"
66  "tracking.\n";
68  *this, &CubicInterpolationSE3::start, docstring));
69  docstring =
70  " Reset interpolation before calling start again\n"
71  "\n"
72  " After the end of an interpolation, goal signal is copied into\n"
73  " sout signal. Calling reset make the entity copy init signal into\n"
74  " sout signal.\n";
76  *this, &CubicInterpolationSE3::reset, docstring));
77 }
78 
80 
82  std::string doc =
83  "Perform a cubic interpolation in SE(3) between two poses.\n"
84  "\n"
85  " Initial pose is given by signal 'init', Target position is given"
86  " by signal\n"
87  " 'goal'. Interpolation is performed with zero velocities at start"
88  " and goal\n"
89  " positions.\n";
90  return doc;
91 }
92 
94 
96  sot::MatrixHomogeneous& sout, const sigtime_t& inTime) {
97  double t;
98  switch (state_) {
99  case 0:
100  sout = initSIN_.accessCopy();
101  break;
102  case 1:
103  t = (inTime - startTime_) * samplingPeriod_;
104  position_ = p0_ + (p1_ + (p2_ + p3_ * t) * t) * t;
105  sout(0, 3) = position_(0);
106  sout(1, 3) = position_(1);
107  sout(2, 3) = position_(2);
108  soutdot_ = p1_ + (p2_ * 2 + p3_ * (3 * t)) * t;
110  if (t >= duration_) {
111  state_ = 2;
112  }
113  break;
114  case 2:
115  soutdot_.setZero();
117  sout = goalSIN_.accessCopy();
118  default:
119  break;
120  }
121  return sout;
122 }
123 
124 void CubicInterpolationSE3::setSamplingPeriod(const double& period) {
125  samplingPeriod_ = period;
126 }
127 
128 void CubicInterpolationSE3::start(const double& duration) { doStart(duration); }
129 
130 void CubicInterpolationSE3::doStart(const double& duration) {
131  // Check that sampling period has been initialized
132  if (samplingPeriod_ <= 0)
134  "CubicInterpolationSE3: samplingPeriod should"
135  " be positive. Are you sure you did\n"
136  "initialize it?");
137  if (state_ == 0) {
138  duration_ = duration;
139  startTime_ = soutSOUT_.getTime();
140  double T = duration;
141  // Initial position
142  p0_(0) = initSIN_.accessCopy()(0, 3);
143  p0_(1) = initSIN_.accessCopy()(1, 3);
144  p0_(2) = initSIN_.accessCopy()(2, 3);
145  // Initial velocity
146  p1_(0) = 0.;
147  p1_(1) = 0.;
148  p1_(2) = 0.;
149  // Goal position
150  Vector P_T(3);
151  P_T(0) = goalSIN_.accessCopy()(0, 3);
152  P_T(1) = goalSIN_.accessCopy()(1, 3);
153  P_T(2) = goalSIN_.accessCopy()(2, 3);
154  // Final velocity
155  Vector D_T(3);
156  D_T.setZero();
157  p2_ = (D_T + p1_ * 2) * (-1. / T) + (P_T - p0_) * (3. / (T * T));
158  p3_ = (P_T - p0_) * (-2 / (T * T * T)) + (p1_ + D_T) * (1. / (T * T));
159  state_ = 1;
160  }
161 }
162 } // namespace tools
163 } // namespace sot
164 } // namespace dynamicgraph
dynamicgraph::sot::tools::CubicInterpolationSE3::start
void start(const double &duration)
Start tracking.
Definition: cubic-interpolation-se3.cc:128
dynamicgraph::sot::tools::CubicInterpolationSE3::state_
unsigned state_
Definition: cubic-interpolation-se3.hh:48
dynamicgraph::SignalPtr::accessCopy
virtual const T & accessCopy() const
dynamicgraph::sot::MatrixHomogeneous
Eigen::Transform< double, 3, Eigen::Affine > SOT_CORE_EXPORT MatrixHomogeneous
dynamicgraph::sot::ExceptionSignal
dynamicgraph::sot::tools::CubicInterpolationSE3::p0_
Vector p0_
Definition: cubic-interpolation-se3.hh:50
T
int T
dynamicgraph
dynamicgraph::Entity
dynamicgraph::sot::tools::CubicInterpolationSE3::doStart
virtual void doStart(const double &duration)
Definition: cubic-interpolation-se3.cc:130
dynamicgraph::sot::tools::CubicInterpolationSE3::~CubicInterpolationSE3
virtual ~CubicInterpolationSE3()
Definition: cubic-interpolation-se3.cc:79
dynamicgraph::sot::tools::CubicInterpolationSE3::CubicInterpolationSE3
CubicInterpolationSE3(const std::string &name)
Definition: cubic-interpolation-se3.cc:19
dynamicgraph::Signal::setFunction
virtual void setFunction(boost::function2< T &, T &, Time > t, Mutex *mutexref=NULL)
dynamicgraph::sot::tools::CubicInterpolationSE3::p3_
Vector p3_
Definition: cubic-interpolation-se3.hh:53
dynamicgraph::sot::ExceptionSignal::NOT_INITIALIZED
NOT_INITIALIZED
dynamicgraph::sot::tools::CubicInterpolationSE3::duration_
double duration_
Definition: cubic-interpolation-se3.hh:46
dynamicgraph::sot::tools::CubicInterpolationSE3::getDocString
virtual std::string getDocString() const
Documentation.
Definition: cubic-interpolation-se3.cc:81
dynamicgraph::command::makeCommandVoid0
CommandVoid0< E > * makeCommandVoid0(E &entity, boost::function< void(E *)> function, const std::string &docString)
command-bind.h
command-setter.h
dynamicgraph::sot::tools::CubicInterpolationSE3::samplingPeriod_
double samplingPeriod_
Definition: cubic-interpolation-se3.hh:45
dynamicgraph::sot::tools::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(CubicInterpolationSE3, "CubicInterpolationSE3")
dynamicgraph::sigtime_t
int64_t sigtime_t
dynamicgraph::sot::tools::CubicInterpolationSE3::setSamplingPeriod
void setSamplingPeriod(const double &period)
Set sampling period of control discretization.
Definition: cubic-interpolation-se3.cc:124
dynamicgraph::sot::tools::CubicInterpolationSE3::soutSOUT_
dynamicgraph::Signal< MatrixHomogeneous, sigtime_t > soutSOUT_
Definition: cubic-interpolation-se3.hh:36
dynamicgraph::sot::tools::CubicInterpolationSE3::p2_
Vector p2_
Definition: cubic-interpolation-se3.hh:52
dynamicgraph::sot::tools::CubicInterpolationSE3::initSIN_
dynamicgraph::SignalPtr< MatrixHomogeneous, sigtime_t > initSIN_
Definition: cubic-interpolation-se3.hh:38
dynamicgraph::sot::Vector
Vector
dynamicgraph::Signal::setConstant
virtual void setConstant(const T &t)
dynamicgraph::sot::tools::CubicInterpolationSE3::startTime_
sigtime_t startTime_
Definition: cubic-interpolation-se3.hh:44
dynamicgraph::sot::tools::CubicInterpolationSE3::soutdotSOUT_
dynamicgraph::Signal< Vector, sigtime_t > soutdotSOUT_
Definition: cubic-interpolation-se3.hh:37
dynamicgraph::sot::tools::CubicInterpolationSE3::reset
void reset()
Reset state to 0 before starting a new motion.
Definition: cubic-interpolation-se3.cc:93
dynamicgraph::sot::tools::CubicInterpolationSE3::soutdot_
Vector soutdot_
Definition: cubic-interpolation-se3.hh:56
dynamicgraph::sot::tools::CubicInterpolationSE3::goalSIN_
dynamicgraph::SignalPtr< MatrixHomogeneous, sigtime_t > goalSIN_
Definition: cubic-interpolation-se3.hh:39
dynamicgraph::Entity::addCommand
void addCommand(const std::string &name, command::Command *command)
t
Transform3f t
dynamicgraph::sot::tools::CubicInterpolationSE3::computeSout
MatrixHomogeneous & computeSout(MatrixHomogeneous &sout, const sigtime_t &inTime)
Definition: cubic-interpolation-se3.cc:95
cubic-interpolation-se3.hh
dynamicgraph::command::Setter
command.h
dynamicgraph::Entity::signalRegistration
void signalRegistration(const SignalArray< sigtime_t > &signals)
dynamicgraph::sot::tools::CubicInterpolationSE3::position_
Vector position_
Definition: cubic-interpolation-se3.hh:55
dynamicgraph::sot::tools::CubicInterpolationSE3::p1_
Vector p1_
Definition: cubic-interpolation-se3.hh:51
compile.name
name
Definition: compile.py:23


sot-tools
Author(s): Mehdi Benallegue, Francois Keith, Florent Lamiraux, Thomas Moulard, Olivier Stasse, Jorrit T'Hooft
autogenerated on Wed Aug 2 2023 02:35:13