SequencePlayer.cpp
Go to the documentation of this file.
1 // -*- C++ -*-
10 #include <rtm/CorbaNaming.h>
11 #include <hrpModel/Link.h>
12 #include <hrpModel/ModelLoaderUtil.h>
13 #include "SequencePlayer.h"
14 #include "hrpsys/util/VectorConvert.h"
15 #include <hrpModel/JointPath.h>
16 #include <hrpUtil/MatrixSolvers.h>
17 #include "../ImpedanceController/JointPathEx.h"
18 
20 
21 // Module specification
22 // <rtc-template block="module_spec">
23 static const char* sequenceplayer_spec[] =
24  {
25  "implementation_id", "SequencePlayer",
26  "type_name", "SequencePlayer",
27  "description", "sequence player component",
28  "version", HRPSYS_PACKAGE_VERSION,
29  "vendor", "AIST",
30  "category", "example",
31  "activity_type", "DataFlowComponent",
32  "max_instance", "10",
33  "language", "C++",
34  "lang_type", "compile",
35  // Configuration variables
36  "conf.default.debugLevel", "0",
37  "conf.default.fixedLink", "",
38 
39  ""
40  };
41 // </rtc-template>
42 
44  : RTC::DataFlowComponentBase(manager),
45  // <rtc-template block="initializer">
46  m_qInitIn("qInit", m_qInit),
47  m_basePosInitIn("basePosInit", m_basePosInit),
48  m_baseRpyInitIn("baseRpyInit", m_baseRpyInit),
49  m_zmpRefInitIn("zmpRefInit", m_zmpRefInit),
50  m_qRefOut("qRef", m_qRef),
51  m_tqRefOut("tqRef", m_tqRef),
52  m_zmpRefOut("zmpRef", m_zmpRef),
53  m_accRefOut("accRef", m_accRef),
54  m_basePosOut("basePos", m_basePos),
55  m_baseRpyOut("baseRpy", m_baseRpy),
56  m_optionalDataOut("optionalData", m_optionalData),
57  m_SequencePlayerServicePort("SequencePlayerService"),
58  // </rtc-template>
59  m_robot(hrp::BodyPtr()),
60  m_debugLevel(0),
61  m_error_pos(0.0001),
62  m_error_rot(0.001),
63  m_iteration(50),
64  dummy(0)
65 {
66  sem_init(&m_waitSem, 0, 0);
67  m_service0.player(this);
68  m_clearFlag = false;
69  m_waitFlag = false;
70 }
71 
73 {
74 }
75 
76 
77 RTC::ReturnCode_t SequencePlayer::onInitialize()
78 {
79  std::cout << "SequencePlayer::onInitialize()" << std::endl;
80  // Registration: InPort/OutPort/Service
81  // <rtc-template block="registration">
82  // Set InPort buffers
83  addInPort("qInit", m_qInitIn);
84  addInPort("basePosInit", m_basePosInitIn);
85  addInPort("baseRpyInit", m_baseRpyInitIn);
86  addInPort("zmpRefInit", m_zmpRefInitIn);
87 
88  // Set OutPort buffer
89  addOutPort("qRef", m_qRefOut);
90  addOutPort("tqRef", m_tqRefOut);
91  addOutPort("zmpRef", m_zmpRefOut);
92  addOutPort("accRef", m_accRefOut);
93  addOutPort("basePos", m_basePosOut);
94  addOutPort("baseRpy", m_baseRpyOut);
95  addOutPort("optionalData", m_optionalDataOut);
96 
97  // Set service provider to Ports
98  m_SequencePlayerServicePort.registerProvider("service0", "SequencePlayerService", m_service0);
99 
100  // Set service consumers to Ports
101 
102  // Set CORBA Service Ports
104 
105  // </rtc-template>
106  // <rtc-template block="bind_config">
107  // Bind variables and configuration variable
108 
109  bindParameter("debugLevel", m_debugLevel, "0");
110  bindParameter("fixedLink", m_fixedLink, "");
111  // </rtc-template>
112 
114  coil::stringTo(dt, prop["dt"].c_str());
115 
116  m_robot = hrp::BodyPtr(new Body());
117 
118  RTC::Manager& rtcManager = RTC::Manager::instance();
119  std::string nameServer = rtcManager.getConfig()["corba.nameservers"];
120  int comPos = nameServer.find(",");
121  if (comPos < 0){
122  comPos = nameServer.length();
123  }
124  nameServer = nameServer.substr(0, comPos);
125  RTC::CorbaNaming naming(rtcManager.getORB(), nameServer.c_str());
126  if (!loadBodyFromModelLoader(m_robot, prop["model"].c_str(),
127  CosNaming::NamingContext::_duplicate(naming.getRootContext())
128  )){
129  std::cerr << "failed to load model[" << prop["model"] << "]"
130  << std::endl;
131  }
132 
133  unsigned int dof = m_robot->numJoints();
134 
135 
136  // Setting for wrench data ports (real + virtual)
137  std::vector<std::string> fsensor_names;
138  // find names for real force sensors
139  unsigned int npforce = m_robot->numSensors(hrp::Sensor::FORCE);
140  for (unsigned int i=0; i<npforce; i++){
141  fsensor_names.push_back(m_robot->sensor(hrp::Sensor::FORCE, i)->name);
142  }
143  // find names for virtual force sensors
144  coil::vstring virtual_force_sensor = coil::split(prop["virtual_force_sensor"], ",");
145  unsigned int nvforce = virtual_force_sensor.size()/10;
146  for (unsigned int i=0; i<nvforce; i++){
147  fsensor_names.push_back(virtual_force_sensor[i*10+0]);
148  }
149  // add ports for all force sensors
150  unsigned int nforce = npforce + nvforce;
151  m_wrenches.resize(nforce);
152  m_wrenchesOut.resize(nforce);
153  for (unsigned int i=0; i<nforce; i++){
154  m_wrenchesOut[i] = new OutPort<TimedDoubleSeq>(std::string(fsensor_names[i]+"Ref").c_str(), m_wrenches[i]);
155  m_wrenches[i].data.length(6);
156  registerOutPort(std::string(fsensor_names[i]+"Ref").c_str(), *m_wrenchesOut[i]);
157  }
158 
159  if (prop.hasKey("seq_optional_data_dim")) {
160  coil::stringTo(optional_data_dim, prop["seq_optional_data_dim"].c_str());
161  } else {
162  optional_data_dim = 1;
163  }
164 
165  m_seq = new seqplay(dof, dt, nforce, optional_data_dim);
166 
167  m_qInit.data.length(dof);
168  for (unsigned int i=0; i<dof; i++) m_qInit.data[i] = 0.0;
169  Link *root = m_robot->rootLink();
170  m_basePosInit.data.x = root->p[0]; m_basePosInit.data.y = root->p[1]; m_basePosInit.data.z = root->p[2];
172  m_baseRpyInit.data.r = rpy[0]; m_baseRpyInit.data.p = rpy[1]; m_baseRpyInit.data.y = rpy[2];
173  m_zmpRefInit.data.x = 0; m_zmpRefInit.data.y = 0; m_zmpRefInit.data.z = 0;
174 
175  // allocate memory for outPorts
176  m_qRef.data.length(dof);
177  m_tqRef.data.length(dof);
178  m_optionalData.data.length(optional_data_dim);
179 
180  return RTC::RTC_OK;
181 }
182 
183 
184 
185 RTC::ReturnCode_t SequencePlayer::onFinalize()
186 {
187  if ( m_debugLevel > 0 ) {
188  std::cerr << __PRETTY_FUNCTION__ << std::endl;
189  }
190  return RTC::RTC_OK;
191 }
192 
193 /*
194  RTC::ReturnCode_t SequencePlayer::onStartup(RTC::UniqueId ec_id)
195  {
196  return RTC::RTC_OK;
197  }
198 */
199 
200 /*
201  RTC::ReturnCode_t SequencePlayer::onShutdown(RTC::UniqueId ec_id)
202  {
203  return RTC::RTC_OK;
204  }
205 */
206 
208 {
209  std::cout << "SequencePlayer::onActivated(" << ec_id << ")" << std::endl;
210 
211  return RTC::RTC_OK;
212 }
213 
214 /*
215  RTC::ReturnCode_t SequencePlayer::onDeactivated(RTC::UniqueId ec_id)
216  {
217  return RTC::RTC_OK;
218  }
219 */
220 
221 RTC::ReturnCode_t SequencePlayer::onExecute(RTC::UniqueId ec_id)
222 {
223  static int loop = 0;
224  loop++;
225  if ( m_debugLevel > 0 && loop % 1000 == 0) {
226  std::cerr << __PRETTY_FUNCTION__ << "(" << ec_id << ")" << std::endl;
227  }
228  if (m_qInitIn.isNew()) m_qInitIn.read();
232 
233  if (m_gname != "" && m_seq->isEmpty(m_gname.c_str())){
234  if (m_waitFlag){
235  m_gname = "";
236  m_waitFlag = false;
237  sem_post(&m_waitSem);
238  }
239  }
240  if (m_seq->isEmpty()){
241  m_clearFlag = false;
242  if (m_waitFlag){
243  m_waitFlag = false;
244  sem_post(&m_waitSem);
245  }
246  }else{
247  Guard guard(m_mutex);
248 
249  double zmp[3], acc[3], pos[3], rpy[3], wrenches[6*m_wrenches.size()];
250  m_seq->get(m_qRef.data.get_buffer(), zmp, acc, pos, rpy, m_tqRef.data.get_buffer(), wrenches, m_optionalData.data.get_buffer());
251  m_zmpRef.data.x = zmp[0];
252  m_zmpRef.data.y = zmp[1];
253  m_zmpRef.data.z = zmp[2];
254  m_accRef.data.ax = acc[0];
255  m_accRef.data.ay = acc[1];
256  m_accRef.data.az = acc[2];
257 
258  if (m_fixedLink != ""){
259  for (int i=0; i<m_robot->numJoints(); i++){
260  m_robot->joint(i)->q = m_qRef.data[i];
261  }
262  for (int i=0; i<3; i++){
263  m_robot->rootLink()->p[i] = pos[i];
264  }
265  m_robot->rootLink()->R = hrp::rotFromRpy(rpy[0], rpy[1], rpy[2]);
266  m_robot->calcForwardKinematics();
267  hrp::Link *root = m_robot->rootLink();
268  hrp::Vector3 rootP;
269  hrp::Matrix33 rootR;
270  if (m_timeToStartPlaying > 0){
272  hrp::Link *fixed = m_robot->link(m_fixedLink);
273  hrp::Matrix33 fixed2rootR = fixed->R.transpose()*root->R;
274  hrp::Vector3 fixed2rootP = fixed->R.transpose()*(root->p - fixed->p);
275  rootR = m_fixedR*fixed2rootR;
276  rootP = m_fixedR*fixed2rootP + m_fixedP;
277  }else{
278  rootR = m_offsetR*m_robot->rootLink()->R;
279  rootP = m_offsetR*m_robot->rootLink()->p + m_offsetP;
280  }
281  hrp::Vector3 rootRpy = hrp::rpyFromRot(rootR);
282  pos[0] = rootP[0];
283  pos[1] = rootP[1];
284  pos[2] = rootP[2];
285  rpy[0] = rootRpy[0];
286  rpy[1] = rootRpy[1];
287  rpy[2] = rootRpy[2];
288  }
289  m_basePos.data.x = pos[0];
290  m_basePos.data.y = pos[1];
291  m_basePos.data.z = pos[2];
292  m_baseRpy.data.r = rpy[0];
293  m_baseRpy.data.p = rpy[1];
294  m_baseRpy.data.y = rpy[2];
295  size_t force_i = 0;
296  for (size_t i = 0; i < m_wrenches.size(); i++) {
297  m_wrenches[i].data[0] = wrenches[force_i++];
298  m_wrenches[i].data[1] = wrenches[force_i++];
299  m_wrenches[i].data[2] = wrenches[force_i++];
300  m_wrenches[i].data[3] = wrenches[force_i++];
301  m_wrenches[i].data[4] = wrenches[force_i++];
302  m_wrenches[i].data[5] = wrenches[force_i++];
303  }
304  m_qRef.tm = m_qInit.tm;
305  m_qRefOut.write();
306  m_tqRefOut.write();
307  m_zmpRefOut.write();
308  m_accRefOut.write();
312  for (size_t i = 0; i < m_wrenchesOut.size(); i++) {
313  m_wrenchesOut[i]->write();
314  }
315 
316  if (m_clearFlag){
317  m_seq->clear(0.001);
318  }
319  }
320  return RTC::RTC_OK;
321 }
322 
323 /*
324  RTC::ReturnCode_t SequencePlayer::onAborting(RTC::UniqueId ec_id)
325  {
326  return RTC::RTC_OK;
327  }
328 */
329 
330 /*
331  RTC::ReturnCode_t SequencePlayer::onError(RTC::UniqueId ec_id)
332  {
333  return RTC::RTC_OK;
334  }
335 */
336 
337 /*
338  RTC::ReturnCode_t SequencePlayer::onReset(RTC::UniqueId ec_id)
339  {
340  return RTC::RTC_OK;
341  }
342 */
343 
344 /*
345  RTC::ReturnCode_t SequencePlayer::onStateUpdate(RTC::UniqueId ec_id)
346  {
347  return RTC::RTC_OK;
348  }
349 */
350 
351 /*
352  RTC::ReturnCode_t SequencePlayer::onRateChanged(RTC::UniqueId ec_id)
353  {
354  return RTC::RTC_OK;
355  }
356 */
357 
359 {
360  if ( m_debugLevel > 0 ) {
361  std::cerr << __PRETTY_FUNCTION__ << std::endl;
362  }
363  m_clearFlag = true;
364 }
365 
367 {
368  if ( m_debugLevel > 0 ) {
369  std::cerr << __PRETTY_FUNCTION__ << std::endl;
370  }
371  m_waitFlag = true;
372  sem_wait(&m_waitSem);
373 }
374 
376 {
377  if ( m_debugLevel > 0 ) {
378  std::cerr << __PRETTY_FUNCTION__ << std::endl;
379  }
380  m_gname = gname;
381  m_waitFlag = true;
382  sem_wait(&m_waitSem);
383  return true;
384 }
385 
386 
387 bool SequencePlayer::setJointAngle(short id, double angle, double tm)
388 {
389  if ( m_debugLevel > 0 ) {
390  std::cerr << __PRETTY_FUNCTION__ << std::endl;
391  }
392  Guard guard(m_mutex);
393  if (!setInitialState()) return false;
394  if (id < 0 || id >= m_robot->numJoints()){
395  std::cerr << "[setJointAngle] Invalid jointId " << id << std::endl;
396  return false;
397  }
398  dvector q(m_robot->numJoints());
399  m_seq->getJointAngles(q.data());
400  q[id] = angle;
401  for (unsigned int i=0; i<m_robot->numJoints(); i++){
402  hrp::Link *j = m_robot->joint(i);
403  if (j) j->q = q[i];
404  }
405  m_robot->calcForwardKinematics();
406  hrp::Vector3 absZmp = m_robot->calcCM();
407  absZmp[2] = 0;
408  hrp::Link *root = m_robot->rootLink();
409  hrp::Vector3 relZmp = root->R.transpose()*(absZmp - root->p);
410  m_seq->setJointAngles(q.data(), tm);
411  m_seq->setZmp(relZmp.data(), tm);
412  return true;
413 }
414 
415 bool SequencePlayer::setJointAngles(const double *angles, double tm)
416 {
417  if ( m_debugLevel > 0 ) {
418  std::cerr << __PRETTY_FUNCTION__ << std::endl;
419  }
420  Guard guard(m_mutex);
421  if (!setInitialState()) return false;
422  for (unsigned int i=0; i<m_robot->numJoints(); i++){
423  hrp::Link *j = m_robot->joint(i);
424  if (j) j->q = angles[i];
425  }
426  m_robot->calcForwardKinematics();
427  hrp::Vector3 absZmp = m_robot->calcCM();
428  absZmp[2] = 0;
429  hrp::Link *root = m_robot->rootLink();
430  hrp::Vector3 relZmp = root->R.transpose()*(absZmp - root->p);
431  std::vector<const double*> v_poss;
432  std::vector<double> v_tms;
433  v_poss.push_back(angles);
434  v_tms.push_back(tm);
435  m_seq->setJointAnglesSequence(v_poss, v_tms);
436  m_seq->setZmp(relZmp.data(), tm);
437  return true;
438 }
439 
440 bool SequencePlayer::setJointAngles(const double *angles, const bool *mask,
441  double tm)
442 {
443  if ( m_debugLevel > 0 ) {
444  std::cerr << __PRETTY_FUNCTION__ << std::endl;
445  }
446  Guard guard(m_mutex);
447 
448  if (!setInitialState()) return false;
449 
450  double pose[m_robot->numJoints()];
451  for (unsigned int i=0; i<m_robot->numJoints(); i++){
452  pose[i] = mask[i] ? angles[i] : m_qInit.data[i];
453  }
454  m_seq->setJointAngles(pose, tm);
455  return true;
456 }
457 
458 bool SequencePlayer::setJointAnglesSequence(const OpenHRP::dSequenceSequence angless, const OpenHRP::bSequence& mask, const OpenHRP::dSequence& times)
459 {
460  if ( m_debugLevel > 0 ) {
461  std::cerr << __PRETTY_FUNCTION__ << std::endl;
462  }
463  Guard guard(m_mutex);
464 
465  if (!setInitialState()) return false;
466 
467  bool tmp_mask[robot()->numJoints()];
468  if (mask.length() != robot()->numJoints()) {
469  for (unsigned int i=0; i < robot()->numJoints(); i++) tmp_mask[i] = true;
470  }else{
471  for (unsigned int i=0; i < robot()->numJoints(); i++) tmp_mask[i] = mask.get_buffer()[i];
472  }
473  int len = angless.length();
474  std::vector<const double*> v_poss;
475  std::vector<double> v_tms;
476  for ( unsigned int i = 0; i < angless.length(); i++ ) v_poss.push_back(angless[i].get_buffer());
477  for ( unsigned int i = 0; i < times.length(); i++ ) v_tms.push_back(times[i]);
478  return m_seq->setJointAnglesSequence(v_poss, v_tms);
479 }
480 
482 {
483  if ( m_debugLevel > 0 ) {
484  std::cerr << __PRETTY_FUNCTION__ << std::endl;
485  }
486  Guard guard(m_mutex);
487 
488  if (!setInitialState()) return false;
489 
490  return m_seq->clearJointAngles();
491 }
492 
493 bool SequencePlayer::setJointAnglesSequenceOfGroup(const char *gname, const OpenHRP::dSequenceSequence angless, const OpenHRP::dSequence& times)
494 {
495  if ( m_debugLevel > 0 ) {
496  std::cerr << __PRETTY_FUNCTION__ << std::endl;
497  }
498  Guard guard(m_mutex);
499  if (!setInitialState()) return false;
500 
501  if (!m_seq->resetJointGroup(gname, m_qInit.data.get_buffer())) return false;
502 
503  std::vector<const double*> v_poss;
504  std::vector<double> v_tms;
505  for ( unsigned int i = 0; i < angless.length(); i++ ) v_poss.push_back(angless[i].get_buffer());
506  for ( unsigned int i = 0; i < times.length(); i++ ) v_tms.push_back(times[i]);
507  return m_seq->setJointAnglesSequenceOfGroup(gname, v_poss, v_tms, angless.length()>0?angless[0].length():0);
508 }
509 
511 {
512  if ( m_debugLevel > 0 ) {
513  std::cerr << __PRETTY_FUNCTION__ << std::endl;
514  }
515  Guard guard(m_mutex);
516  if (!setInitialState()) return false;
517 
518  if (!m_seq->resetJointGroup(gname, m_qInit.data.get_buffer())) return false;
519 
520  return m_seq->clearJointAnglesOfGroup(gname);
521 }
522 
523 bool SequencePlayer::setJointAnglesSequenceFull(const OpenHRP::dSequenceSequence i_jvss, const OpenHRP::dSequenceSequence i_vels, const OpenHRP::dSequenceSequence i_torques, const OpenHRP::dSequenceSequence i_poss, const OpenHRP::dSequenceSequence i_rpys, const OpenHRP::dSequenceSequence i_accs, const OpenHRP::dSequenceSequence i_zmps, const OpenHRP::dSequenceSequence i_wrenches, const OpenHRP::dSequenceSequence i_optionals, const dSequence i_tms)
524 {
525  if ( m_debugLevel > 0 ) {
526  std::cerr << __PRETTY_FUNCTION__ << std::endl;
527  }
528  Guard guard(m_mutex);
529 
530  if (!setInitialState()) return false;
531 
532  int len = i_jvss.length();
533  std::vector<const double*> v_jvss, v_vels, v_torques, v_poss, v_rpys, v_accs, v_zmps, v_wrenches, v_optionals;
534  std::vector<double> v_tms;
535  for ( unsigned int i = 0; i < i_jvss.length(); i++ ) v_jvss.push_back(i_jvss[i].get_buffer());
536  for ( unsigned int i = 0; i < i_vels.length(); i++ ) v_vels.push_back(i_vels[i].get_buffer());
537  for ( unsigned int i = 0; i < i_torques.length(); i++ ) v_torques.push_back(i_torques[i].get_buffer());
538  for ( unsigned int i = 0; i < i_poss.length(); i++ ) v_poss.push_back(i_poss[i].get_buffer());
539  for ( unsigned int i = 0; i < i_rpys.length(); i++ ) v_rpys.push_back(i_rpys[i].get_buffer());
540  for ( unsigned int i = 0; i < i_accs.length(); i++ ) v_accs.push_back(i_accs[i].get_buffer());
541  for ( unsigned int i = 0; i < i_zmps.length(); i++ ) v_zmps.push_back(i_zmps[i].get_buffer());
542  for ( unsigned int i = 0; i < i_wrenches.length(); i++ ) v_wrenches.push_back(i_wrenches[i].get_buffer());
543  for ( unsigned int i = 0; i < i_optionals.length(); i++ ) v_optionals.push_back(i_optionals[i].get_buffer());
544  for ( unsigned int i = 0; i < i_tms.length(); i++ ) v_tms.push_back(i_tms[i]);
545  return m_seq->setJointAnglesSequenceFull(v_jvss, v_vels, v_torques, v_poss, v_rpys, v_accs, v_zmps, v_wrenches, v_optionals, v_tms);
546 }
547 
548 bool SequencePlayer::setBasePos(const double *pos, double tm)
549 {
550  if ( m_debugLevel > 0 ) {
551  std::cerr << __PRETTY_FUNCTION__ << std::endl;
552  }
553  Guard guard(m_mutex);
554  if (!setInitialState()) return false;
555  m_seq->setBasePos(pos, tm);
556  return true;
557 }
558 
559 bool SequencePlayer::setBaseRpy(const double *rpy, double tm)
560 {
561  if ( m_debugLevel > 0 ) {
562  std::cerr << __PRETTY_FUNCTION__ << std::endl;
563  }
564  Guard guard(m_mutex);
565  if (!setInitialState()) return false;
566  m_seq->setBaseRpy(rpy, tm);
567  return true;
568 }
569 
570 bool SequencePlayer::setZmp(const double *zmp, double tm)
571 {
572  if ( m_debugLevel > 0 ) {
573  std::cerr << __PRETTY_FUNCTION__ << std::endl;
574  }
575  Guard guard(m_mutex);
576  if (!setInitialState()) return false;
577  m_seq->setZmp(zmp, tm);
578  return true;
579 }
580 
581 bool SequencePlayer::setWrenches(const double *wrenches, double tm)
582 {
583  Guard guard(m_mutex);
584  if (!setInitialState()) return false;
585  m_seq->setWrenches(wrenches, tm);
586  return true;
587 }
588 
589 bool SequencePlayer::setTargetPose(const char* gname, const double *xyz, const double *rpy, double tm, const char* frame_name)
590 {
591  if ( m_debugLevel > 0 ) {
592  std::cerr << __PRETTY_FUNCTION__ << std::endl;
593  }
594  Guard guard(m_mutex);
595  if (!setInitialState()) return false;
596  // setup
597  std::vector<int> indices;
598  hrp::dvector start_av, end_av;
599  std::vector<hrp::dvector> avs;
600  if (! m_seq->getJointGroup(gname, indices) ) {
601  std::cerr << "[setTargetPose] Could not find joint group " << gname << std::endl;
602  return false;
603  }
604  start_av.resize(indices.size());
605  end_av.resize(indices.size());
606 
607  //std::cerr << std::endl;
608  if ( ! m_robot->joint(indices[0])->parent ) {
609  std::cerr << "[setTargetPose] " << m_robot->joint(indices[0])->name << " does not have parent" << std::endl;
610  return false;
611  }
612  string base_parent_name = m_robot->joint(indices[0])->parent->name;
613  string target_name = m_robot->joint(indices[indices.size()-1])->name;
614  // prepare joint path
615  hrp::JointPathExPtr manip = hrp::JointPathExPtr(new hrp::JointPathEx(m_robot, m_robot->link(base_parent_name), m_robot->link(target_name), dt, true, std::string(m_profile.instance_name)));
616 
617  // calc fk
618  for (unsigned int i=0; i<m_robot->numJoints(); i++){
619  hrp::Link *j = m_robot->joint(i);
620  if (j) j->q = m_qRef.data.get_buffer()[i];
621  }
622  m_robot->calcForwardKinematics();
623  for ( unsigned int i = 0; i < manip->numJoints(); i++ ){
624  start_av[i] = manip->joint(i)->q;
625  }
626 
627  // xyz and rpy are relateive to root link, where as pos and rotatoin of manip->calcInverseKinematics are relative to base link
628 
629  // ik params
630  hrp::Vector3 start_p(m_robot->link(target_name)->p);
631  hrp::Matrix33 start_R(m_robot->link(target_name)->R);
632  hrp::Vector3 end_p(xyz[0], xyz[1], xyz[2]);
633  hrp::Matrix33 end_R = m_robot->link(target_name)->calcRfromAttitude(hrp::rotFromRpy(rpy[0], rpy[1], rpy[2]));
634 
635  // change start and end must be relative to the frame_name
636  if ( (frame_name != NULL) && (! m_robot->link(frame_name) ) ) {
637  std::cerr << "[setTargetPose] Could not find frame_name " << frame_name << std::endl;
638  return false;
639  } else if ( frame_name != NULL ) {
640  hrp::Vector3 frame_p(m_robot->link(frame_name)->p);
641  hrp::Matrix33 frame_R(m_robot->link(frame_name)->attitude());
642  // fix start/end references from root to frame;
643  end_p = frame_R * end_p + frame_p;
644  end_R = frame_R * end_R;
645  }
646  manip->setMaxIKError(m_error_pos,m_error_rot);
647  manip->setMaxIKIteration(m_iteration);
648  std::cerr << "[setTargetPose] Solveing IK with frame " << (frame_name? frame_name:"world_frame") << ", Error " << m_error_pos << m_error_rot << ", Iteration " << m_iteration << std::endl;
649  std::cerr << " Start\n" << start_p << "\n" << start_R<< std::endl;
650  std::cerr << " End\n" << end_p << "\n" << end_R<< std::endl;
651 
652  // interpolate & calc ik
653  int len = max(((start_p - end_p).norm() / 0.02 ), // 2cm
654  ((hrp::omegaFromRot(start_R.transpose() * end_R).norm()) / 0.025)); // 2 deg
655  len = max(len, 1);
656 
657  std::vector<const double *> v_pos;
658  std::vector<double> v_tm;
659  v_pos.resize(len);
660  v_tm.resize(len);
661 
662  // do loop
663  for (int i = 0; i < len; i++ ) {
664  double a = (1+i)/(double)len;
665  hrp::Vector3 p = (1-a)*start_p + a*end_p;
666  hrp::Vector3 omega = hrp::omegaFromRot(start_R.transpose() * end_R);
667  hrp::Matrix33 R = start_R * rodrigues(omega.isZero()?omega:omega.normalized(), a*omega.norm());
668  bool ret = manip->calcInverseKinematics2(p, R);
669 
670  if ( m_debugLevel > 0 ) {
671  // for debug
672  std::cerr << "target pos/rot : " << i << "/" << a << " : "
673  << p[0] << " " << p[1] << " " << p[2] << ","
674  << omega[0] << " " << omega[1] << " " << omega[2] << std::endl;
675  }
676  if ( ! ret ) {
677  std::cerr << "[setTargetPose] IK failed" << std::endl;
678  return false;
679  }
680  v_pos[i] = (const double *)malloc(sizeof(double)*manip->numJoints());
681  for ( unsigned int j = 0; j < manip->numJoints(); j++ ){
682  ((double *)v_pos[i])[j] = manip->joint(j)->q;
683  }
684  v_tm[i] = tm/len;
685  }
686 
687  if ( m_debugLevel > 0 ) {
688  // for debug
689  for(int i = 0; i < len; i++ ) {
690  std::cerr << v_tm[i] << ":";
691  for(int j = 0; j < start_av.size(); j++ ) {
692  std::cerr << v_pos[i][j] << " ";
693  }
694  std::cerr << std::endl;
695  }
696  }
697 
698  if (!m_seq->resetJointGroup(gname, m_qInit.data.get_buffer())) return false; // reset sequencer
699  bool ret = m_seq->playPatternOfGroup(gname, v_pos, v_tm, m_qInit.data.get_buffer(), v_pos.size()>0?indices.size():0);
700 
701  // clean up memory, need to improve
702  for (int i = 0; i < len; i++ ) {
703  free((double *)v_pos[i]);
704  }
705 
706  return ret;
707 }
708 
709 void SequencePlayer::loadPattern(const char *basename, double tm)
710 {
711  if ( m_debugLevel > 0 ) {
712  std::cerr << __PRETTY_FUNCTION__ << std::endl;
713  }
714  Guard guard(m_mutex);
715  if (setInitialState()){
716  if (m_fixedLink != ""){
717  hrp::Link *l = m_robot->link(m_fixedLink);
718  if (!l) {
719  std::cerr << __PRETTY_FUNCTION__ << "can't find a fixed link("
720  << m_fixedLink << ")" << std::endl;
721  m_fixedLink = "";
722  return;
723  }
724  m_robot->calcForwardKinematics(); // this is not called by setinitialstate()
725  m_fixedP = l->p;
726  m_fixedR = l->R;
727 
728  std::string pos = std::string(basename)+".pos";
729  std::string wst = std::string(basename)+".waist";
730  std::ifstream ifspos(pos.c_str());
731  std::ifstream ifswst(wst.c_str());
732  if (!ifspos.is_open() || !ifswst.is_open()){
733  std::cerr << __PRETTY_FUNCTION__ << "can't open " << pos << " or "
734  << wst << ")" << std::endl;
735  m_fixedLink = "";
736  return;
737  }
738  double time;
739  ifspos >> time;
740  for (int i=0; i<m_robot->numJoints(); i++){
741  ifspos >> m_robot->joint(i)->q;
742  }
743  ifswst >> time;
744  for (int i=0; i<3; i++) ifswst >> m_robot->rootLink()->p[i];
745  hrp::Vector3 rpy;
746  for (int i=0; i<3; i++) ifswst >> rpy[i];
747  m_robot->rootLink()->R = hrp::rotFromRpy(rpy);
748  m_robot->calcForwardKinematics();
749 
750  m_offsetR = m_fixedR*l->R.transpose();
751  m_offsetP = m_fixedP - m_offsetR*l->p;
753  }
754  m_seq->loadPattern(basename, tm);
755  }
756 }
757 
759 {
760  if ( m_debugLevel > 0 ) {
761  std::cerr << __PRETTY_FUNCTION__ << "m_seq-isEmpty() " << m_seq->isEmpty() << ", m_Init.data.length() " << m_qInit.data.length() << std::endl;
762  }
763  if (!m_seq->isEmpty()) return true;
764 
765  if (m_qInit.data.length() == 0){
766  std::cerr << "can't determine initial posture" << std::endl;
767  return false;
768  }else{
769  m_seq->setJointAngles(m_qInit.data.get_buffer(), tm);
770  for (unsigned int i=0; i<m_robot->numJoints(); i++){
771  Link *l = m_robot->joint(i);
772  l->q = m_qInit.data[i];
773  m_qRef.data[i] = m_qInit.data[i]; // update m_qRef for setTargetPose()
774  }
775 
776  Link *root = m_robot->rootLink();
777 
778  root->p << m_basePosInit.data.x,
779  m_basePosInit.data.y,
780  m_basePosInit.data.z;
781  m_seq->setBasePos(root->p.data(), tm);
782 
783  double rpy[] = {m_baseRpyInit.data.r,
784  m_baseRpyInit.data.p,
785  m_baseRpyInit.data.y};
786  m_seq->setBaseRpy(rpy, tm);
787  calcRotFromRpy(root->R, rpy[0], rpy[1], rpy[2]);
788 
789  double zmp[] = {m_zmpRefInit.data.x, m_zmpRefInit.data.y, m_zmpRefInit.data.z};
790  m_seq->setZmp(zmp, tm);
791  double zero[] = {0,0,0};
792  m_seq->setBaseAcc(zero, tm);
793  return true;
794  }
795 }
796 
797 void SequencePlayer::playPattern(const dSequenceSequence& pos, const dSequenceSequence& rpy, const dSequenceSequence& zmp, const dSequence& tm)
798 {
799  if ( m_debugLevel > 0 ) {
800  std::cerr << __PRETTY_FUNCTION__ << std::endl;
801  }
802  Guard guard(m_mutex);
803  if (!setInitialState()) return;
804 
805  std::vector<const double *> v_pos, v_rpy, v_zmp;
806  std::vector<double> v_tm;
807  for ( unsigned int i = 0; i < pos.length(); i++ ) v_pos.push_back(pos[i].get_buffer());
808  for ( unsigned int i = 0; i < rpy.length(); i++ ) v_rpy.push_back(rpy[i].get_buffer());
809  for ( unsigned int i = 0; i < zmp.length(); i++ ) v_zmp.push_back(zmp[i].get_buffer());
810  for ( unsigned int i = 0; i < tm.length() ; i++ ) v_tm.push_back(tm[i]);
811  return m_seq->playPattern(v_pos, v_rpy, v_zmp, v_tm, m_qInit.data.get_buffer(), pos.length()>0?pos[0].length():0);
812 }
813 
814 bool SequencePlayer::setInterpolationMode(OpenHRP::SequencePlayerService::interpolationMode i_mode_)
815 {
816  if ( m_debugLevel > 0 ) {
817  std::cerr << __PRETTY_FUNCTION__ << std::endl;
818  }
819  Guard guard(m_mutex);
821  if (i_mode_ == OpenHRP::SequencePlayerService::LINEAR){
822  new_mode = interpolator::LINEAR;
823  }else if (i_mode_ == OpenHRP::SequencePlayerService::HOFFARBIB){
824  new_mode = interpolator::HOFFARBIB;
825  }else{
826  return false;
827  }
828  return m_seq->setInterpolationMode(new_mode);
829 }
830 
831 bool SequencePlayer::addJointGroup(const char *gname, const OpenHRP::SequencePlayerService::StrSequence& jnames)
832 {
833  std::cerr << "[addJointGroup] group name = " << gname << std::endl;
834  if ( m_debugLevel > 0 ) {
835  std::cerr << __PRETTY_FUNCTION__ << std::endl;
836  }
837  if (!waitInterpolationOfGroup(gname)) return false;
838 
839  Guard guard(m_mutex);
840  std::vector<int> indices;
841  for (size_t i=0; i<jnames.length(); i++){
842  hrp::Link *l = m_robot->link(std::string(jnames[i]));
843  if (l){
844  indices.push_back(l->jointId);
845  }else{
846  std::cerr << "[addJointGroup] link name " << jnames[i] << "is not found" << std::endl;
847  return false;
848  }
849  }
850  return m_seq->addJointGroup(gname, indices);
851 }
852 
853 bool SequencePlayer::removeJointGroup(const char *gname)
854 {
855  std::cerr << "[removeJointGroup] group name = " << gname << std::endl;
856  if (!waitInterpolationOfGroup(gname)) return false;
857  bool ret;
858  {
859  Guard guard(m_mutex);
860  if (!setInitialState()) return false;
861  ret = m_seq->removeJointGroup(gname);
862  }
863  return ret;
864 }
865 
866 bool SequencePlayer::setJointAnglesOfGroup(const char *gname, const dSequence& jvs, double tm)
867 {
868  if ( m_debugLevel > 0 ) {
869  std::cerr << __PRETTY_FUNCTION__ << std::endl;
870  }
871  Guard guard(m_mutex);
872  if (!setInitialState()) return false;
873 
874  if (!m_seq->resetJointGroup(gname, m_qInit.data.get_buffer())) return false;
875  return m_seq->setJointAnglesOfGroup(gname, jvs.get_buffer(), jvs.length(), tm);
876 }
877 
878 bool SequencePlayer::playPatternOfGroup(const char *gname, const dSequenceSequence& pos, const dSequence& tm)
879 {
880  if ( m_debugLevel > 0 ) {
881  std::cerr << __PRETTY_FUNCTION__ << std::endl;
882  }
883  Guard guard(m_mutex);
884  if (!setInitialState()) return false;
885 
886  std::vector<const double *> v_pos;
887  std::vector<double> v_tm;
888  for ( unsigned int i = 0; i < pos.length(); i++ ) v_pos.push_back(pos[i].get_buffer());
889  for ( unsigned int i = 0; i < tm.length() ; i++ ) v_tm.push_back(tm[i]);
890  return m_seq->playPatternOfGroup(gname, v_pos, v_tm, m_qInit.data.get_buffer(), pos.length()>0?pos[0].length():0);
891 }
892 
893 void SequencePlayer::setMaxIKError(double pos, double rot){
894  m_error_pos = pos;
895  m_error_rot = rot;
896 }
897 
899  m_iteration= iter;
900 }
901 
902 
903 extern "C"
904 {
905 
907  {
909  manager->registerFactory(profile,
910  RTC::Create<SequencePlayer>,
911  RTC::Delete<SequencePlayer>);
912  }
913 
914 };
915 
916 
ComponentProfile m_profile
png_infop png_charpp int png_charpp profile
hrp::Matrix33 m_offsetR
#define max(a, b)
static const char * sequenceplayer_spec[]
bool setTargetPose(const char *gname, const double *xyz, const double *rpy, double tm, const char *frame_name)
unsigned int m_debugLevel
virtual RTC::ReturnCode_t onFinalize()
bool setJointAnglesSequenceFull(const OpenHRP::dSequenceSequence i_jvss, const OpenHRP::dSequenceSequence i_vels, const OpenHRP::dSequenceSequence i_torques, const OpenHRP::dSequenceSequence i_poss, const OpenHRP::dSequenceSequence i_rpys, const OpenHRP::dSequenceSequence i_accs, const OpenHRP::dSequenceSequence i_zmps, const OpenHRP::dSequenceSequence i_wrenches, const OpenHRP::dSequenceSequence i_optionals, const dSequence i_tms)
void SequencePlayerInit(RTC::Manager *manager)
hrp::BodyPtr robot()
bool stringTo(To &val, const char *str)
bool clearJointAngles()
Definition: seqplay.cpp:644
void getJointAngles(double *i_qRef)
Definition: seqplay.cpp:162
bool setWrenches(const double *wrenches, double tm)
bool setJointAnglesSequence(std::vector< const double *> pos, std::vector< double > tm)
Definition: seqplay.cpp:598
void setZmp(const double *i_zmp, double i_tm=0.0)
Definition: seqplay.cpp:168
void setBaseAcc(const double *i_acc, double i_tm=0.0)
Definition: seqplay.cpp:195
bool setJointAnglesOfGroup(const char *gname, const double *i_qRef, const size_t i_qsize, double i_tm=0.0)
Definition: seqplay.cpp:489
bool setZmp(const double *zmp, double tm)
sequence player component
char * malloc()
png_infop png_charpp name
virtual RTC::ReturnCode_t onActivated(RTC::UniqueId ec_id)
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
std::vector< TimedDoubleSeq > m_wrenches
coil::Guard< coil::Mutex > Guard
bool setJointAngles(const double *angles, double tm)
TimedDoubleSeq m_tqRef
vstring split(const std::string &input, const std::string &delimiter, bool ignore_empty)
OutPort< TimedOrientation3D > m_baseRpyOut
HRP_UTIL_EXPORT void calcRotFromRpy(Matrix33 &out_R, double r, double p, double y)
void player(SequencePlayer *i_player)
bool getJointGroup(const char *gname, std::vector< int > &indices)
Definition: seqplay.cpp:437
void setBaseRpy(const double *i_rpy, double i_tm=0.0)
Definition: seqplay.cpp:186
CORBA::ORB_ptr getORB()
boost::shared_ptr< JointPathEx > JointPathExPtr
Definition: JointPathEx.h:67
std::string basename(const std::string name)
png_uint_32 i
Eigen::VectorXd dvector
coil::Properties & getProperties()
std::string m_fixedLink
bool setJointAnglesSequence(const OpenHRP::dSequenceSequence angless, const OpenHRP::bSequence &mask, const OpenHRP::dSequence &times)
static Manager & instance()
InPort< TimedPoint3D > m_basePosInitIn
InPort< TimedDoubleSeq > m_qInitIn
bool addOutPort(const char *name, OutPortBase &outport)
bool removeJointGroup(const char *gname)
boost::shared_ptr< Body > BodyPtr
TimedDoubleSeq m_qInit
void loadPattern(const char *basename, double time)
hrp::BodyPtr m_robot
SequencePlayerService_impl m_service0
bool addJointGroup(const char *gname, const OpenHRP::SequencePlayerService::StrSequence &jnames)
Eigen::Vector3d Vector3
Properties * hasKey(const char *key) const
bool removeJointGroup(const char *gname, double time=2.5)
Definition: seqplay.cpp:452
Matrix33 rotFromRpy(const Vector3 &rpy)
bool setJointAnglesSequenceOfGroup(const char *gname, const OpenHRP::dSequenceSequence angless, const OpenHRP::dSequence &times)
bool addJointGroup(const char *gname, const std::vector< int > &indices)
Definition: seqplay.cpp:424
bool setBaseRpy(const double *rpy, double tm)
bool setJointAnglesSequenceOfGroup(const char *gname, std::vector< const double *> pos, std::vector< double > tm, const size_t pos_size)
Definition: seqplay.cpp:762
Eigen::Matrix3d Matrix33
coil::Mutex m_mutex
bool resetJointGroup(const char *gname, const double *full)
Definition: seqplay.cpp:465
std::vector< std::string > vstring
void setBasePos(const double *i_pos, double i_tm=0.0)
Definition: seqplay.cpp:177
bool setBasePos(const double *pos, double tm)
coil::Properties & getConfig()
bool waitInterpolationOfGroup(const char *gname)
bool clearJointAnglesOfGroup(const char *gname)
OutPort< TimedPoint3D > m_zmpRefOut
ExecutionContextHandle_t UniqueId
bool playPatternOfGroup(const char *gname, std::vector< const double *> pos, std::vector< double > tm, const double *qInit, unsigned int len)
Definition: seqplay.cpp:530
bool bindParameter(const char *param_name, VarType &var, const char *def_val, bool(*trans)(VarType &, const char *)=coil::stringTo)
OutPort< TimedDoubleSeq > m_tqRefOut
bool setJointAnglesSequenceFull(std::vector< const double *> pos, std::vector< const double *> vel, std::vector< const double *> torques, std::vector< const double *> bpos, std::vector< const double *> brpy, std::vector< const double *> bacc, std::vector< const double *> zmps, std::vector< const double *> wrenches, std::vector< const double *> optionals, std::vector< double > tm)
Definition: seqplay.cpp:660
void playPattern(const OpenHRP::dSequenceSequence &pos, const OpenHRP::dSequenceSequence &rpy, const OpenHRP::dSequenceSequence &zmp, const OpenHRP::dSequence &tm)
Matrix33 rodrigues(const Vector3 &axis, double q)
TimedPoint3D m_zmpRefInit
int loadBodyFromModelLoader(::World *world, const char *name, const char *url, CosNaming::NamingContext_var cxt)
void setMaxIKIteration(short iter)
int free()
bool setInterpolationMode(interpolator::interpolation_mode i_mode_)
Definition: seqplay.cpp:407
void get(double *o_q, double *o_zmp, double *o_accel, double *o_basePos, double *o_baseRpy, double *o_tq, double *o_wrenches, double *o_optional_data)
Definition: seqplay.cpp:354
TimedAcceleration3D m_accRef
std::string m_gname
OutPort< TimedAcceleration3D > m_accRefOut
hrp::Vector3 m_fixedP
virtual ~SequencePlayer()
void clear(double i_timeLimit=0)
Definition: seqplay.cpp:263
#define __PRETTY_FUNCTION__
void setMaxIKError(double pos, double rot)
bool setJointAngle(short id, double angle, double tm)
prop
TimedDoubleSeq m_optionalData
bool setJointAnglesOfGroup(const char *gname, const OpenHRP::dSequence &jvs, double tm)
TimedDoubleSeq m_qRef
def norm(a)
HRP_UTIL_EXPORT Vector3 rpyFromRot(const Matrix33 &m)
naming
TimedOrientation3D m_baseRpy
bool isEmpty() const
Definition: seqplay.cpp:103
bool setInitialState(double tm=0.0)
InPort< TimedPoint3D > m_zmpRefInitIn
TimedPoint3D m_basePos
TimedPoint3D m_zmpRef
OutPort< TimedDoubleSeq > m_qRefOut
virtual bool isNew()
void loadPattern(const char *i_basename, double i_tm)
Definition: seqplay.cpp:273
bool setInterpolationMode(OpenHRP::SequencePlayerService::interpolationMode i_mode_)
static int id
bool addPort(PortBase &port)
OutPort< TimedDoubleSeq > m_optionalDataOut
virtual bool write(DataType &value)
hrp::Matrix33 m_fixedR
HRP_UTIL_EXPORT Vector3 omegaFromRot(const Matrix33 &r)
virtual RTC::ReturnCode_t onInitialize()
hrp::BodyPtr m_robot
RTC::CorbaPort m_SequencePlayerServicePort
bool clearJointAnglesOfGroup(const char *gname)
Definition: seqplay.cpp:841
OutPort< TimedPoint3D > m_basePosOut
SequencePlayer(RTC::Manager *manager)
bool playPatternOfGroup(const char *gname, const OpenHRP::dSequenceSequence &pos, const OpenHRP::dSequence &tm)
bool addInPort(const char *name, InPortBase &inport)
void registerOutPort(const char *name, OutPortBase &outport)
InPort< TimedOrientation3D > m_baseRpyInitIn
TimedPoint3D m_basePosInit
bool registerFactory(coil::Properties &profile, RtcNewFunc new_func, RtcDeleteFunc delete_func)
double m_timeToStartPlaying
void setJointAngles(const double *i_qRef, double i_tm=0.0)
Definition: seqplay.cpp:153
hrp::Vector3 m_offsetP
void setWrenches(const double *i_wrenches, double i_tm=0.0)
Definition: seqplay.cpp:204
void playPattern(std::vector< const double *> pos, std::vector< const double *> zmp, std::vector< const double *> rpy, std::vector< double > tm, const double *qInit, unsigned int len)
Definition: seqplay.cpp:221
size_t optional_data_dim
bool registerProvider(const char *instance_name, const char *type_name, PortableServer::RefCountServantBase &provider)
virtual RTC::ReturnCode_t onExecute(RTC::UniqueId ec_id)
std::vector< OutPort< TimedDoubleSeq > * > m_wrenchesOut
TimedOrientation3D m_baseRpyInit


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Sat Dec 17 2022 03:52:21