integrator.cpp
Go to the documentation of this file.
1 // BSD 2-Clause License
2 
3 // Copyright (c) 2023, CNRS
4 // Author: Florent Lamiraux
5 
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 
13 // * Redistributions in binary form must reproduce the above copyright
14 // notice, this list of conditions and the following disclaimer in
15 // the documentation and/or other materials provided with the
16 // distribution.
17 
18 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
20 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
21 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
22 // COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
23 // INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
24 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
25 // SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
26 // HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
27 // STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
29 // OF THE POSSIBILITY OF SUCH DAMAGE.
30 
31 #include <sot/core/integrator.hh>
32 #include <dynamic-graph/factory.h>
35 #include <dynamic-graph/signal.h>
36 
37 namespace dynamicgraph {
38 namespace sot {
39 namespace internal {
40 
41 Signal::Signal(std::string name)
43 
44 /* ------------------------------------------------------------------------ */
45 
46 void Signal::set(std::istringstream &stringValue) {
47  (*this) = signal_io<Vector>::cast(stringValue);
48 }
49 
50 void Signal::get(std::ostream &os) const {
52 }
53 
54 void Signal::trace(std::ostream &os) const {
55  try {
57  } catch DG_RETHROW catch (...) {
59  "TRACE operation not possible with this signal. ",
60  "(bad cast while getting value from %s).",
62  }
63 }
64 
65 void Signal::setConstant(const Vector &) {
66  throw std::runtime_error("Not implemented.");
67 }
68 
69 void Signal::setReference(const Vector *, Mutex *) {
70  throw std::runtime_error("Not implemented.");
71 }
72 
74  throw std::runtime_error("Not implemented.");
75 }
76 
77 void Signal::setFunction(boost::function2<Vector &, Vector &, sigtime_t> t,
78  Mutex *mutexref) {
80  Tfunction = t;
81  providerMutex = mutexref;
82  copyInit = false;
83  setReady();
84 }
85 
86 const Vector &Signal::accessCopy() const { return Tcopy1; }
87 
88 const Vector &Signal::access(const sigtime_t &t) {
89  if (NULL == providerMutex) {
90  signalTime = t;
91  Tfunction(Tcopy1, t);
92  return Tcopy1;
93  } else {
94  try {
95 #ifdef HAVE_LIBBOOST_THREAD
96  boost::try_mutex::scoped_try_lock lock(*providerMutex);
97 #endif
98  signalTime = t;
99  Tfunction(Tcopy1, t);
100  return Tcopy1;
101  } catch (const MutexError &) {
102  return accessCopy();
103  }
104  }
105 }
106 
108  throw std::runtime_error("Output signal cannot be assigned a value.");
109  return *this;
110 }
111 
112 std::ostream &Signal::display(std::ostream &os) const {
113  os << "Sig:" << this->name << " (Type ";
114  switch (this->signalType) {
115  case Signal::CONSTANT:
116  os << "Cst";
117  break;
118  case Signal::REFERENCE:
119  os << "Ref";
120  break;
122  os << "RefNonCst";
123  break;
124  case Signal::FUNCTION:
125  os << "Fun";
126  break;
127  }
128  return os << ")";
129 }
130 
131 } // namespace internal
133 
134 const double Integrator::dt = 1e-6;
135 
136 Integrator::Integrator(const std::string &name)
137  : Entity(name),
138  velocitySIN_(0x0, "Integrator(" + name + ")::input(vector)::velocity"),
139  configurationSOUT_("Integrator(" + name +
140  ")::output(vector)::configuration"),
141  model_(0x0),
142  configuration_(),
143  lastComputationTime_(-1),
144  recursivityLevel_(0) {
146  boost::bind(&Integrator::integrate, this, _1, _2));
149 }
150 
152 
154  model_ = model;
155  configuration_.resize(model->nq);
156  ::pinocchio::neutral(*model_, configuration_);
157 }
158 
159 void Integrator::setInitialConfig(const Vector &initConfig) {
160  configuration_ = initConfig;
161 }
162 
165  if (recursivityLevel_ == 2) {
166  configuration = configuration_;
168  return configuration;
169  }
170  configuration.resize(configuration_.size());
171  assert(model_);
172  Vector velocity(velocitySIN_(time));
173  // Run Synchronous commands and evaluate signals outside the main
174  // connected component of the graph.
175  try {
176  periodicCallBefore_.run(time);
177  } catch (const std::exception &e) {
178  dgRTLOG() << "exception caught while running periodical commands (before): "
179  << e.what() << std::endl;
180  }
181  if (lastComputationTime_ == -1 && !velocity.isZero(0)) {
182  recursivityLevel_ = 0;
183  std::ostringstream os;
184  os << "Integrator entity expects zero velocity input for the first "
185  "computation. Got instead "
186  << velocity.transpose() << ".";
187  throw std::runtime_error(os.str().c_str());
188  }
189  double delta_t = dt * (double)(time - lastComputationTime_);
190  ::pinocchio::integrate(*model_, configuration_, delta_t * velocity,
191  configuration);
192  configuration_ = configuration;
193  lastComputationTime_ = time;
194  try {
195  periodicCallAfter_.run(time);
196  } catch (const std::exception &e) {
197  dgRTLOG() << "exception caught while running periodical commands (after): "
198  << e.what() << std::endl;
199  }
201  return configuration;
202 }
203 
204 } // namespace sot
205 } // namespace dynamicgraph
dynamicgraph::ExceptionSignal::SET_IMPOSSIBLE
SET_IMPOSSIBLE
dynamicgraph::Signal
dynamicgraph::sot::internal::Signal::REFERENCE_NON_CONST
@ REFERENCE_NON_CONST
Definition: integrator.hh:46
dynamicgraph::signal_io_base::cast
static T cast(std::istringstream &is)
dynamicgraph::sot::Integrator::getModel
::pinocchio::Model * getModel()
Definition: integrator.cpp:151
dynamicgraph::sot::internal::Signal::get
virtual void get(std::ostream &value) const
Definition: integrator.cpp:50
dynamicgraph::sot::Integrator::setModel
void setModel(::pinocchio::Model *model)
Definition: integrator.cpp:153
dynamicgraph
dynamicgraph::sot::internal::Signal
Definition: integrator.hh:44
dynamicgraph::Entity
dynamicgraph::sot::Integrator::Integrator
Integrator(const std::string &name)
Definition: integrator.cpp:136
dynamicgraph::sot::internal::Signal::setReferenceNonConstant
virtual void setReferenceNonConstant(Vector *t, Mutex *mutexref=NULL)
Definition: integrator.cpp:73
dynamicgraph::sot::internal::Signal::setReference
virtual void setReference(const Vector *t, Mutex *mutexref=NULL)
Definition: integrator.cpp:69
dynamicgraph::sot::internal::Signal::FUNCTION
@ FUNCTION
Definition: integrator.hh:46
dynamicgraph::sot::Integrator::configuration_
Vector configuration_
Definition: integrator.hh:142
dynamicgraph::sot::Integrator::periodicCallAfter_
PeriodicCall periodicCallAfter_
Definition: integrator.hh:134
dynamicgraph::signal_io_base::trace
static void trace(const T &value, std::ostream &os)
dynamicgraph::sot::internal::Signal::set
virtual void set(std::istringstream &value)
Definition: integrator.cpp:46
dynamicgraph::sot::Integrator::periodicCallBefore_
PeriodicCall periodicCallBefore_
Definition: integrator.hh:133
dynamicgraph::sot::PeriodicCall::run
void run(const sigtime_t &t)
Definition: periodic-call.cpp:84
model
model
dynamicgraph::sot::Integrator::integrate
Vector & integrate(Vector &configuration, sigtime_t time)
Definition: integrator.cpp:163
dynamicgraph::sot::Integrator::lastComputationTime_
sigtime_t lastComputationTime_
Definition: integrator.hh:143
dynamicgraph::sot::internal::Signal::providerMutex
Mutex * providerMutex
Definition: integrator.hh:66
dynamicgraph::sot::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(FeaturePosture, "FeaturePosture")
dynamicgraph::sot::internal::Signal::Signal
Signal(std::string name)
Definition: integrator.cpp:41
dynamicgraph::sot::internal::Signal::setConstant
virtual void setConstant(const Vector &t)
Definition: integrator.cpp:65
dynamicgraph::sot::internal::Signal::MutexError
size_type * MutexError
Definition: integrator.hh:62
dynamicgraph::sot::internal::Signal::Tfunction
boost::function2< Vector &, Vector &, sigtime_t > Tfunction
Definition: integrator.hh:51
dynamicgraph::sot::internal::Signal::Mutex
size_type * Mutex
Definition: integrator.hh:61
dynamicgraph::sigtime_t
int64_t sigtime_t
dynamicgraph::Signal< Vector, sigtime_t >::Tcopy1
T Tcopy1
dynamicgraph::Signal< Vector, sigtime_t >::copyInit
bool copyInit
dynamicgraph::sot::internal::Signal::operator=
virtual Signal & operator=(const Vector &t)
Definition: integrator.cpp:107
dgRTLOG
#define dgRTLOG()
DG_RETHROW
#define DG_RETHROW
DG_THROW
#define DG_THROW
dynamicgraph::sot::Integrator
Definition: integrator.hh:114
signal-caster.h
integrator.hh
dynamicgraph::Vector
Eigen::VectorXd Vector
dynamicgraph::sot::internal::Signal::accessCopy
virtual const Vector & accessCopy() const
Definition: integrator.cpp:86
dynamicgraph::sot::internal::Signal::REFERENCE
@ REFERENCE
Definition: integrator.hh:46
dynamicgraph::sot::internal::Signal::access
virtual const Vector & access(const sigtime_t &t)
Definition: integrator.cpp:88
real-time-logger.h
dynamicgraph::ExceptionSignal
dynamicgraph::sot::Integrator::model_
::pinocchio::Model * model_
Definition: integrator.hh:141
dynamicgraph::sot::double
double
Definition: fir-filter.cpp:49
dynamicgraph::sot::Integrator::dt
static const double dt
Definition: integrator.hh:117
dynamicgraph::sot::internal::Signal::CONSTANT
@ CONSTANT
Definition: integrator.hh:46
dynamicgraph::sot::Integrator::recursivityLevel_
sigtime_t recursivityLevel_
Definition: integrator.hh:144
dynamicgraph::sot::Integrator::configurationSOUT_
internal::Signal configurationSOUT_
Definition: integrator.hh:139
x0
x0
t
Transform3f t
dynamicgraph::sot::Integrator::velocitySIN_
SignalPtr< Vector, sigtime_t > velocitySIN_
Definition: integrator.hh:138
dynamicgraph::sot::internal::Signal::display
virtual std::ostream & display(std::ostream &os) const
Definition: integrator.cpp:112
dynamicgraph::Signal< Vector, sigtime_t >::signalType
SignalType signalType
pinocchio::ModelTpl
dynamicgraph::SignalBase
dynamicgraph::Entity::signalRegistration
void signalRegistration(const SignalArray< sigtime_t > &signals)
dynamicgraph::sot::Integrator::setInitialConfig
void setInitialConfig(const Vector &initConfig)
Definition: integrator.cpp:159
dynamicgraph::sot::internal::Signal::trace
virtual void trace(std::ostream &os) const
Definition: integrator.cpp:54
dynamicgraph::signal_io_base::disp
static void disp(const T &value, std::ostream &os)
compile.name
name
Definition: compile.py:23
dynamicgraph::sot::internal::Signal::setFunction
virtual void setFunction(boost::function2< Vector &, Vector &, sigtime_t > t, Mutex *mutexref=NULL)
Definition: integrator.cpp:77


sot-core
Author(s): Olivier Stasse, ostasse@laas.fr
autogenerated on Tue Oct 24 2023 02:26:31