joint-trajectory-entity.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2013,
3  * Olivier Stasse,
4  *
5  * CNRS, LAAS
6  *
7  */
8 // #define VP_DEBUG
9 // #define VP_DEBUG_MODE 10
10 #include <sot/core/debug.hh>
12 #ifdef VP_DEBUG
13 class sotJTE__INIT {
14  public:
15  sotJTE__INIT(void) { dynamicgraph::sot::DebugTrace::openFile(); }
16 };
17 sotJTE__INIT sotJTE_initiator;
18 #endif // #ifdef VP_DEBUG
19 
22 #include <dynamic-graph/factory.h>
23 
25 
27 
28 using namespace std;
29 using namespace dynamicgraph;
30 using namespace dynamicgraph::sot;
31 using namespace dynamicgraph::command;
32 
34  "SotJointTrajectoryEntity");
35 
36 SotJointTrajectoryEntity::SotJointTrajectoryEntity(const std::string &n)
37  : Entity(n),
38  refresherSINTERN("SotJointTrajectoryEntity(" + n +
39  ")::intern(dummy)::refresher"),
40  OneStepOfUpdateS(
41  boost::bind(&SotJointTrajectoryEntity::OneStepOfUpdate, this, _1, _2),
42  refresherSINTERN << trajectorySIN,
43  "SotJointTrajectory(" + n + ")::onestepofupdate"),
44  positionSOUT(
45  boost::bind(&SotJointTrajectoryEntity::getNextPosition, this, _1, _2),
46  OneStepOfUpdateS,
47  "SotJointTrajectory(" + n + ")::output(vector)::position"),
48  comSOUT(boost::bind(&SotJointTrajectoryEntity::getNextCoM, this, _1, _2),
49  OneStepOfUpdateS,
50  "SotJointTrajectory(" + n + ")::output(vector)::com"),
51  zmpSOUT(boost::bind(&SotJointTrajectoryEntity::getNextCoP, this, _1, _2),
52  OneStepOfUpdateS,
53  "SotJointTrajectory(" + n + ")::output(vector)::zmp"),
54  waistSOUT(
55  boost::bind(&SotJointTrajectoryEntity::getNextWaist, this, _1, _2),
56  OneStepOfUpdateS,
57  "SotJointTrajectory(" + n + ")::output(MatrixHomogeneous)::waist"),
58  seqIdSOUT(boost::bind(&SotJointTrajectoryEntity::getSeqId, this, _1, _2),
59  OneStepOfUpdateS,
60  "SotJointTrajectory(" + n + ")::output(uint)::seqid"),
61  trajectorySIN(NULL, "SotJointTrajectory(" + n +
62  ")::input(trajectory)::trajectoryIN"),
63  index_(0),
64  traj_timestamp_(0, 0),
65  seqid_(0),
66  deque_traj_(0) {
67  using namespace command;
68  sotDEBUGIN(5);
69 
71  << seqIdSOUT << trajectorySIN);
73  refresherSINTERN.setReady(true);
74 
75  std::string docstring;
76  docstring =
77  " \n"
78  " initialize the first trajectory.\n"
79  " \n"
80  " Input:\n"
81  " = a string : .\n"
82  " \n";
83  addCommand("initTraj",
85  docCommandVoid1("Set initial trajectory",
86  "string (trajectory)")));
87  sotDEBUGOUT(5);
88 }
89 
91  sotDEBUGIN(5);
92  // Posture
94  if (possize == 0) return;
95 
96  pose_.resize(aJTP.positions_.size());
97  for (std::vector<JointTrajectoryPoint>::size_type i = 0; i < possize - 5;
98  i++) {
99  pose_(i) = aJTP.positions_[i];
100  sotDEBUG(5) << pose_(i) << " " << std::endl;
101  }
102 
103  // Center of Mass
104  com_.resize(3);
105  for (std::vector<JointTrajectoryPoint>::size_type i = possize - 5, j = 0;
106  i < possize - 2; i++, j++)
107  com_(j) = aJTP.positions_[i];
108 
109  sotDEBUG(5) << "com: " << com_ << std::endl;
110 
111  // Add a constant height TODO: make it variable
112  dynamicgraph::Vector waistXYZTheta;
113  waistXYZTheta.resize(4);
114 
115  waistXYZTheta(0) = com_(0);
116  waistXYZTheta(1) = com_(1);
117  waistXYZTheta(2) = 0.65;
118  waistXYZTheta(3) = com_(2);
119  waist_ = XYZThetaToMatrixHomogeneous(waistXYZTheta);
120 
121  sotDEBUG(5) << "waist: " << waist_ << std::endl;
122  // Center of Pressure
123  cop_.resize(3);
124  for (std::vector<JointTrajectoryPoint>::size_type i = possize - 2, j = 0;
125  i < possize; i++, j++)
126  cop_(j) = aJTP.positions_[i];
127  cop_(2) = -0.055;
128  sotDEBUG(5) << "cop_: " << cop_ << std::endl;
129  sotDEBUGOUT(5);
130 }
131 
133  sotDEBUGIN(3);
134  sotDEBUG(3) << "traj_timestamp: " << traj_timestamp_
135  << " aTrajectory.header_.stamp_" << aTrajectory.header_.stamp_;
136 
137  // Do we have the same trajectory, or are we at the initialization phase ?
138  if ((traj_timestamp_ == aTrajectory.header_.stamp_) &&
139  (deque_traj_.size() != 0))
140  index_++;
141  else {
142  // No we have a new trajectory.
143  sotDEBUG(3) << "index: " << index_ << " aTrajectory.points_.size(): "
144  << aTrajectory.points_.size();
145 
146  // Put the new trajectory in the queue
147 
148  // if there is nothing
149  if (deque_traj_.size() == 0) {
150  deque_traj_.push_back(aTrajectory);
151  index_ = 0;
152  } else {
153  index_++;
154  // if it is not already inside the queue.
155  if (deque_traj_.back().header_.stamp_ == aTrajectory.header_.stamp_) {
156  } else
157  deque_traj_.push_back(aTrajectory);
158  }
159  }
160 
161  sotDEBUG(3) << "step 1 " << std::endl
162  << "header: " << std::endl
163  << " timestamp:"
164  << static_cast<double>(aTrajectory.header_.stamp_.secs_) +
165  0.000000001 *
166  static_cast<double>(aTrajectory.header_.stamp_.nsecs_)
167  << " seq:" << aTrajectory.header_.seq_ << " "
168  << " frame_id:" << aTrajectory.header_.frame_id_
169  << " index_: " << index_
170  << " aTrajectory.points_.size():" << aTrajectory.points_.size()
171  << std::endl;
172 
173  // Strategy at the end of the trajectory.
174  if (index_ >= deque_traj_.front().points_.size()) {
175  if (deque_traj_.size() > 1) {
176  deque_traj_.pop_front();
177  index_ = 0;
178  }
179 
180  // If the new trajectory has a problem
181  if (deque_traj_.front().points_.size() == 0) {
182  // then neutralize the entity
183  index_ = 0;
184  sotDEBUG(3) << "current_traj_.points_.size()="
185  << deque_traj_.front().points_.size() << std::endl;
186  return;
187  }
188 
189  // Strategy at the end of the trajectory when no new information is
190  // available: It is assumed that the last pose is balanced, and we keep
191  // providing this pose to the robot.
192  if ((index_ != 0) && (deque_traj_.size() == 1)) {
193  index_ = deque_traj_.front().points_.size() - 1;
194  }
195  sotDEBUG(3) << "index_=current_traj_.points_.size()-1;" << std::endl;
196  }
197 
198  sotDEBUG(3) << "index_:" << index_ << " current_traj_.points_.size():"
199  << deque_traj_.front().points_.size() << std::endl;
200 
201  seqid_ = deque_traj_.front().header_.seq_;
202  UpdatePoint(deque_traj_.front().points_[index_]);
203  sotDEBUGOUT(3);
204 }
205 
207  const sigtime_t &time) {
208  sotDEBUGIN(4);
209  const Trajectory &atraj = trajectorySIN(time);
210  if ((atraj.header_.stamp_.secs_ !=
211  deque_traj_.front().header_.stamp_.secs_) ||
212  (atraj.header_.stamp_.nsecs_ !=
213  deque_traj_.front().header_.stamp_.nsecs_)) {
214  if (index_ < deque_traj_.front().points_.size() - 1) {
215  sotDEBUG(4) << "Overwrite trajectory without completion." << index_ << " "
216  << deque_traj_.front().points_.size() << std::endl;
217  }
218  }
219  sotDEBUG(4) << "Finished to read trajectorySIN" << std::endl;
220  UpdateTrajectory(atraj);
221 
222  sotDEBUG(4) << "Finished to update trajectory" << std::endl;
223 
224  sotDEBUGOUT(4);
225  return dummy;
226 }
227 
229  const dynamicgraph::Vector &xyztheta) {
230  assert(xyztheta.size() == 4);
232  t(0) = xyztheta(0);
233  t(1) = xyztheta(1);
234  t(2) = xyztheta(2);
235  Eigen::Affine3d trans;
236  trans = Eigen::Translation3d(t);
237  Eigen::Affine3d _Rd(Eigen::AngleAxisd(xyztheta(3), Eigen::Vector3d::UnitZ()));
239  res = _Rd * trans;
240  return res;
241 }
242 
244  dynamicgraph::Vector &pos, const sigtime_t &time) {
245  sotDEBUGIN(5);
246  OneStepOfUpdateS(time);
247  pos = pose_;
248  sotDEBUG(5) << pos;
249  sotDEBUGOUT(5);
250  return pos;
251 }
252 
254  dynamicgraph::Vector &com, const sigtime_t &time) {
255  sotDEBUGIN(5);
256  OneStepOfUpdateS(time);
257  com = com_;
258  sotDEBUGOUT(5);
259  return com;
260 }
261 
263  dynamicgraph::Vector &cop, const sigtime_t &time) {
264  sotDEBUGIN(5);
265  OneStepOfUpdateS(time);
266  cop = cop_;
267  sotDEBUGOUT(5);
268  return cop;
269 }
270 
272  sot::MatrixHomogeneous &waist, const sigtime_t &time) {
273  sotDEBUGIN(5);
274  OneStepOfUpdateS(time);
275  waist = waist_;
276  sotDEBUGOUT(5);
277  return waist_;
278 }
279 
280 std::size_t &SotJointTrajectoryEntity::getSeqId(std::size_t &seqid,
281  const sigtime_t &time) {
282  sotDEBUGIN(5);
283  OneStepOfUpdateS(time);
284  seqid = seqid_;
285  sotDEBUGOUT(5);
286  return seqid;
287 }
288 
289 void SotJointTrajectoryEntity::loadFile(const std::string &) {
290  sotDEBUGIN(5);
291  // TODO
292  sotDEBUGOUT(5);
293 }
294 
295 void SotJointTrajectoryEntity::display(std::ostream &os) const {
296  sotDEBUGIN(5);
297  os << this;
298  sotDEBUGOUT(5);
299 }
300 
301 void SotJointTrajectoryEntity::setInitTraj(const std::string &as) {
302  sotDEBUGIN(5);
303  std::istringstream is(as);
306 
307  sotDEBUGOUT(5);
308 }
dynamicgraph::sot::SotJointTrajectoryEntity::display
virtual void display(std::ostream &os) const
Definition: joint-trajectory-entity.cpp:295
dynamicgraph::TimeDependency
dynamicgraph::sot::SotJointTrajectoryEntity::waistSOUT
dynamicgraph::SignalTimeDependent< sot::MatrixHomogeneous, sigtime_t > waistSOUT
Publish waist for each evaluation of the graph.
Definition: joint-trajectory-entity.hh:118
dynamicgraph::sot::Trajectory::deserialize
size_type deserialize(std::istringstream &is)
Definition: trajectory.cpp:294
dynamicgraph::sot::MatrixHomogeneous
Eigen::Transform< double, 3, Eigen::Affine > SOT_CORE_EXPORT MatrixHomogeneous
Definition: matrix-geometry.hh:75
dynamicgraph::sot::SotJointTrajectoryEntity::getNextPosition
dynamicgraph::Vector & getNextPosition(dynamicgraph::Vector &pos, const sigtime_t &time)
Return the next pose for the legs.
Definition: joint-trajectory-entity.cpp:243
dynamicgraph
dynamicgraph::sot::SotJointTrajectoryEntity::zmpSOUT
dynamicgraph::SignalTimeDependent< dynamicgraph::Vector, sigtime_t > zmpSOUT
Publish zmp for each evaluation of the graph.
Definition: joint-trajectory-entity.hh:114
dynamicgraph::command
i
int i
dynamicgraph::Entity
dynamicgraph::sot::SotJointTrajectoryEntity::refresherSINTERN
dynamicgraph::SignalTimeDependent< size_type, sigtime_t > refresherSINTERN
Definition: joint-trajectory-entity.hh:101
dynamicgraph::sot::SotJointTrajectoryEntity
This object handles trajectory of quantities and publish them as signals.
Definition: joint-trajectory-entity.hh:47
dynamicgraph::sot::SotJointTrajectoryEntity::OneStepOfUpdate
size_type & OneStepOfUpdate(size_type &dummy, const sigtime_t &time)
Perform one update of the signals.
Definition: joint-trajectory-entity.cpp:206
boost
dynamicgraph::sot::SotJointTrajectoryEntity::positionSOUT
dynamicgraph::SignalTimeDependent< dynamicgraph::Vector, sigtime_t > positionSOUT
Publish pose for each evaluation of the graph.
Definition: joint-trajectory-entity.hh:108
size_type
dynamicgraph::size_type size_type
Definition: exception-abstract.cpp:15
dynamicgraph::sot::SotJointTrajectoryEntity::init_traj_
sot::Trajectory init_traj_
Initial state of the trajectory.
Definition: joint-trajectory-entity.hh:150
dynamicgraph::sot::JointTrajectoryPoint::positions_
std::vector< double > positions_
Definition: trajectory.hh:122
dynamicgraph::sot::timestamp::secs_
unsigned long int secs_
Definition: trajectory.hh:86
dynamicgraph::sot::timestamp::nsecs_
unsigned long int nsecs_
Definition: trajectory.hh:87
debug.hh
command-bind.h
res
res
dynamicgraph::sot::SotJointTrajectoryEntity::deque_traj_
std::deque< sot::Trajectory > deque_traj_
Queue of trajectories.
Definition: joint-trajectory-entity.hh:153
sotDEBUGOUT
#define sotDEBUGOUT(level)
Definition: debug.hh:215
dynamicgraph::sot::SotJointTrajectoryEntity::index_
std::deque< sot::Trajectory >::size_type index_
Index on the point along the trajectory.
Definition: joint-trajectory-entity.hh:129
dynamicgraph::sot::SotJointTrajectoryEntity::UpdateTrajectory
void UpdateTrajectory(const Trajectory &aTrajectory)
Update the entity with the trajectory aTrajectory.
Definition: joint-trajectory-entity.cpp:132
docCommandVoid1
std::string docCommandVoid1(const std::string &doc, const std::string &type)
dynamicgraph::sot::SotJointTrajectoryEntity::UpdatePoint
void UpdatePoint(const JointTrajectoryPoint &aJTP)
Update the entity with the current point of the trajectory.
Definition: joint-trajectory-entity.cpp:90
dynamicgraph::sot::SotJointTrajectoryEntity::XYZThetaToMatrixHomogeneous
sot::MatrixHomogeneous XYZThetaToMatrixHomogeneous(const dynamicgraph::Vector &xyztheta)
Convert a xyztheta vector into an homogeneous matrix.
Definition: joint-trajectory-entity.cpp:228
dynamicgraph::sigtime_t
int64_t sigtime_t
dynamicgraph::sot::Header::frame_id_
std::string frame_id_
Definition: trajectory.hh:116
dynamicgraph::sot::SotJointTrajectoryEntity::comSOUT
dynamicgraph::SignalTimeDependent< dynamicgraph::Vector, sigtime_t > comSOUT
Publish com for each evaluation of the graph.
Definition: joint-trajectory-entity.hh:111
dynamicgraph::sot::SotJointTrajectoryEntity::loadFile
void loadFile(const std::string &name)
Definition: joint-trajectory-entity.cpp:289
sotDEBUGIN
#define sotDEBUGIN(level)
Definition: debug.hh:214
dummy
DummyClass dummy
Definition: test_signal.cpp:31
dynamicgraph::sot::SotJointTrajectoryEntity::getNextCoM
dynamicgraph::Vector & getNextCoM(dynamicgraph::Vector &com, const sigtime_t &time)
Return the next com.
Definition: joint-trajectory-entity.cpp:253
dynamicgraph::sot::SotJointTrajectoryEntity::com_
dynamicgraph::Vector com_
Store the center of mass.
Definition: joint-trajectory-entity.hh:138
pos
pos
dynamicgraph::size_type
Matrix::Index size_type
dynamicgraph::Vector
Eigen::VectorXd Vector
dynamicgraph::sot::SotJointTrajectoryEntity::getNextWaist
sot::MatrixHomogeneous & getNextWaist(sot::MatrixHomogeneous &waist, const sigtime_t &time)
Return the next waist.
Definition: joint-trajectory-entity.cpp:271
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(SotJointTrajectoryEntity, "SotJointTrajectoryEntity")
dynamicgraph::sot::Trajectory
Definition: trajectory.hh:181
dynamicgraph::sot::SotJointTrajectoryEntity::traj_timestamp_
timestamp traj_timestamp_
Keep the starting time as an identifier of the trajector.
Definition: joint-trajectory-entity.hh:132
dynamicgraph::sot::SotJointTrajectoryEntity::seqid_
std::size_t seqid_
Store the current seq identifier.
Definition: joint-trajectory-entity.hh:147
matrix-geometry.hh
dynamicgraph::sot::JointTrajectoryPoint
Definition: trajectory.hh:120
dynamicgraph::sot::SotJointTrajectoryEntity::waist_
sot::MatrixHomogeneous waist_
Store the waist position.
Definition: joint-trajectory-entity.hh:144
dynamicgraph::sot::Trajectory::header_
Header header_
Definition: trajectory.hh:189
dynamicgraph::sot::SotJointTrajectoryEntity::setInitTraj
void setInitTraj(const std::string &os)
Implements the parsing and the affectation of initial trajectory.
Definition: joint-trajectory-entity.cpp:301
dynamicgraph::sot
dynamicgraph::sot::Trajectory::points_
std::vector< JointTrajectoryPoint > points_
Definition: trajectory.hh:192
dynamicgraph::sot::SotJointTrajectoryEntity::getNextCoP
dynamicgraph::Vector & getNextCoP(dynamicgraph::Vector &cop, const sigtime_t &time)
Return the next cop.
Definition: joint-trajectory-entity.cpp:262
dynamicgraph::Entity::addCommand
void addCommand(const std::string &name, command::Command *command)
dynamicgraph::sot::SotJointTrajectoryEntity::pose_
dynamicgraph::Vector pose_
Store the pos;.
Definition: joint-trajectory-entity.hh:135
t
Transform3f t
dynamicgraph::sot::Header::stamp_
timestamp stamp_
Definition: trajectory.hh:115
all-commands.h
dynamicgraph::sot::SotJointTrajectoryEntity::trajectorySIN
dynamicgraph::SignalPtr< Trajectory, sigtime_t > trajectorySIN
Read a trajectory.
Definition: joint-trajectory-entity.hh:124
dynamicgraph::DebugTrace::openFile
static void openFile(const char *filename=DEBUG_FILENAME_DEFAULT)
dynamicgraph::sot::Header::seq_
std::size_t seq_
Definition: trajectory.hh:114
dynamicgraph::sot::SotJointTrajectoryEntity::getSeqId
std::size_t & getSeqId(std::size_t &seqid, const sigtime_t &time)
Return the current seq identified of the current trajectory.
Definition: joint-trajectory-entity.cpp:280
joint-trajectory-entity.hh
dynamicgraph::Entity::signalRegistration
void signalRegistration(const SignalArray< sigtime_t > &signals)
joint-trajectory-command.hh
dynamicgraph::sot::SotJointTrajectoryEntity::OneStepOfUpdateS
SignalTimeDependent< Dummy, sigtime_t > OneStepOfUpdateS
Internal signal to trigger one step of the algorithm.
Definition: joint-trajectory-entity.hh:104
n
Vec3f n
com
com
dynamicgraph::sot::SotJointTrajectoryEntity::cop_
dynamicgraph::Vector cop_
Store the center of pressure ZMP.
Definition: joint-trajectory-entity.hh:141
makeCommandVoid1
CommandVoid1< E, T > * makeCommandVoid1(E &entity, boost::function< void(const T &)> function, const std::string &docString)
dynamicgraph::sot::SotJointTrajectoryEntity::seqIdSOUT
dynamicgraph::SignalTimeDependent< std::size_t, sigtime_t > seqIdSOUT
Publish ID of the trajectory currently realized.
Definition: joint-trajectory-entity.hh:121
sotDEBUG
#define sotDEBUG(level)
Definition: debug.hh:168


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