Visual Servoing Platform  version 3.1.0
vpRobotBiclops.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2017 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See http://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Interface for the Biclops robot.
33  *
34  * Authors:
35  * Fabien Spindler
36  *
37  *****************************************************************************/
38 
39 #include <cmath> // std::fabs
40 #include <errno.h>
41 #include <limits> // numeric_limits
42 #include <signal.h>
43 #include <string.h>
44 
45 #include <visp3/core/vpTime.h>
46 
47 #include <visp3/core/vpConfig.h>
48 
49 #ifdef VISP_HAVE_BICLOPS
50 
51 #include <visp3/core/vpExponentialMap.h>
52 #include <visp3/core/vpIoTools.h>
53 #include <visp3/robot/vpBiclops.h>
54 #include <visp3/robot/vpRobotBiclops.h>
55 #include <visp3/robot/vpRobotException.h>
56 
57 //#define VP_DEBUG // Activate the debug mode
58 //#define VP_DEBUG_MODE 10 // Activate debug level 1 and 2
59 #include <visp3/core/vpDebug.h>
60 
61 /* ---------------------------------------------------------------------- */
62 /* --- STATIC ------------------------------------------------------------ */
63 /* ------------------------------------------------------------------------ */
64 
65 bool vpRobotBiclops::robotAlreadyCreated = false;
67 
68 static pthread_mutex_t vpEndThread_mutex;
69 static pthread_mutex_t vpShm_mutex;
70 static pthread_mutex_t vpMeasure_mutex;
71 
72 /* ----------------------------------------------------------------------- */
73 /* --- CONSTRUCTOR ------------------------------------------------------ */
74 /* ---------------------------------------------------------------------- */
75 
115  : vpBiclops(), vpRobot(), control_thread(), controller(), positioningVelocity(defaultPositioningVelocity),
116  q_previous(), controlThreadCreated(false)
117 {
118  vpDEBUG_TRACE(12, "Begin default constructor.");
119 
120  vpRobotBiclops::robotAlreadyCreated = false;
121  setConfigFile("/usr/share/BiclopsDefault.cfg");
122 
123  // Initialize the mutex dedicated to she shm protection
124  pthread_mutex_init(&vpShm_mutex, NULL);
125  pthread_mutex_init(&vpEndThread_mutex, NULL);
126  pthread_mutex_init(&vpMeasure_mutex, NULL);
127 
128  control_thread = 0;
129 }
130 
164 vpRobotBiclops::vpRobotBiclops(const std::string &filename)
165  : vpBiclops(), vpRobot(), control_thread(), controller(), positioningVelocity(defaultPositioningVelocity),
166  q_previous(), controlThreadCreated(false)
167 {
168  vpDEBUG_TRACE(12, "Begin default constructor.");
169 
170  vpRobotBiclops::robotAlreadyCreated = false;
171  setConfigFile(filename);
172 
173  // Initialize the mutex dedicated to she shm protection
174  pthread_mutex_init(&vpShm_mutex, NULL);
175  pthread_mutex_init(&vpEndThread_mutex, NULL);
176  pthread_mutex_init(&vpMeasure_mutex, NULL);
177 
178  init();
179 
180  return;
181 }
182 
191 {
192 
193  vpDEBUG_TRACE(12, "Start vpRobotBiclops::~vpRobotBiclops()");
195 
196  vpDEBUG_TRACE(12, "Unlock mutex vpEndThread_mutex");
197  pthread_mutex_unlock(&vpEndThread_mutex);
198 
199  /* wait the end of the control thread */
200  vpDEBUG_TRACE(12, "Wait end of control thread");
201 
202  if (controlThreadCreated == true) {
203  int code = pthread_join(control_thread, NULL);
204  if (code != 0) {
205  vpCERROR << "Cannot terminate the control thread: " << code << " strErr=" << strerror(errno)
206  << " strCode=" << strerror(code) << std::endl;
207  }
208  }
209 
210  pthread_mutex_destroy(&vpShm_mutex);
211  pthread_mutex_destroy(&vpEndThread_mutex);
212  pthread_mutex_destroy(&vpMeasure_mutex);
213 
214  vpRobotBiclops::robotAlreadyCreated = false;
215 
216  vpDEBUG_TRACE(12, "Stop vpRobotBiclops::~vpRobotBiclops()");
217  return;
218 }
219 
220 /* -------------------------------------------------------------------------
221  */
222 /* --- INITIALISATION ------------------------------------------------------
223  */
224 /* -------------------------------------------------------------------------
225  */
226 
232 void vpRobotBiclops::setConfigFile(const std::string &filename) { this->configfile = filename; }
233 
244 {
245  // test if the config file exists
246  FILE *fd = fopen(configfile.c_str(), "r");
247  if (fd == NULL) {
248  vpCERROR << "Cannot open biclops config file: " << configfile << std::endl;
249  throw vpRobotException(vpRobotException::constructionError, "Cannot open connection with biclops");
250  }
251  fclose(fd);
252 
253  // Initialize the controller
254  controller.init(configfile);
255 
256  try {
258  } catch (...) {
259  vpERROR_TRACE("Error caught");
260  throw;
261  }
262 
263  vpRobotBiclops::robotAlreadyCreated = true;
264 
265  // Initialize previous articular position to manage getDisplacement()
266  q_previous.resize(vpBiclops::ndof);
267  q_previous = 0;
268 
269  controlThreadCreated = false;
270 
271  return;
272 }
273 
274 /*
275  Control loop to manage the biclops joint limits in speed control.
276 
277  This control loop is running in a seperate thread in order to detect each 5
278  ms joint limits during the speed control. If a joint limit is detected the
279  axis should be halted.
280 
281  \warning Velocity control mode is not exported from the top-level Biclops
282  API class provided by Traclabs. That means that there is no protection in
283  this mode to prevent an axis from striking its hard limit. In position mode,
284  Traclabs put soft limits in that keep any command from driving to a position
285  too close to the hard limits. In velocity mode this protection does not
286  exist in the current API.
287 
288  \warning With the understanding that hitting the hard limits at full
289  speed/power can damage the unit, damage due to velocity mode commanding is
290  under user responsibility.
291 */
293 {
294  vpRobotBiclopsController *controller = static_cast<vpRobotBiclopsController *>(arg);
295 
296  int iter = 0;
297  // PMDAxisControl *panAxis = controller->getPanAxis();
298  // PMDAxisControl *tiltAxis = controller->getTiltAxis();
299  vpRobotBiclopsController::shmType shm;
300 
301  vpDEBUG_TRACE(10, "Start control loop");
302  vpColVector mes_q;
303  vpColVector mes_q_dot;
304  vpColVector softLimit(vpBiclops::ndof);
306  bool *new_q_dot = new bool[vpBiclops::ndof];
307  bool *change_dir = new bool[vpBiclops::ndof]; // change of direction
308  bool *force_halt = new bool[vpBiclops::ndof]; // force an axis to halt
309  bool *enable_limit = new bool[vpBiclops::ndof]; // enable soft limit
310  vpColVector prev_q_dot(vpBiclops::ndof); // previous desired speed
311  double secure = vpMath::rad(2); // add a security angle before joint limit
312 
313  // Set the soft limits
314  softLimit[0] = vpBiclops::panJointLimit - secure;
315  softLimit[1] = vpBiclops::tiltJointLimit - secure;
316  vpDEBUG_TRACE(12, "soft limit pan: %f tilt: %f", vpMath::deg(softLimit[0]), vpMath::deg(softLimit[1]));
317 
318  // Initilisation
319  vpDEBUG_TRACE(11, "Lock mutex vpShm_mutex");
320  pthread_mutex_lock(&vpShm_mutex);
321 
322  shm = controller->readShm();
323 
324  vpDEBUG_TRACE(11, "unlock mutex vpShm_mutex");
325  pthread_mutex_unlock(&vpShm_mutex);
326 
327  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
328  prev_q_dot[i] = shm.q_dot[i];
329  new_q_dot[i] = false;
330  change_dir[i] = false;
331  force_halt[i] = false;
332  enable_limit[i] = true;
333  }
334 
335  // Initialize actual position and velocity
336  mes_q = controller->getActualPosition();
337  mes_q_dot = controller->getActualVelocity();
338 
339  vpDEBUG_TRACE(11, "Lock mutex vpShm_mutex");
340  pthread_mutex_lock(&vpShm_mutex);
341 
342  shm = controller->readShm();
343  // Updates the shm
344  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
345  shm.actual_q[i] = mes_q[i];
346  shm.actual_q_dot[i] = mes_q_dot[i];
347  }
348  // Update the actuals positions
349  controller->writeShm(shm);
350 
351  vpDEBUG_TRACE(11, "unlock mutex vpShm_mutex");
352  pthread_mutex_unlock(&vpShm_mutex);
353 
354  vpDEBUG_TRACE(11, "unlock mutex vpMeasure_mutex");
355  pthread_mutex_unlock(&vpMeasure_mutex); // A position is available
356 
357  while (!controller->isStopRequested()) {
358 
359  // Get actual position and velocity
360  mes_q = controller->getActualPosition();
361  mes_q_dot = controller->getActualVelocity();
362 
363  vpDEBUG_TRACE(11, "Lock mutex vpShm_mutex");
364  pthread_mutex_lock(&vpShm_mutex);
365 
366  shm = controller->readShm();
367 
368  // Updates the shm
369  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
370  shm.actual_q[i] = mes_q[i];
371  shm.actual_q_dot[i] = mes_q_dot[i];
372  }
373 
374  vpDEBUG_TRACE(12, "mes pan: %f tilt: %f", vpMath::deg(mes_q[0]), vpMath::deg(mes_q[1]));
375  vpDEBUG_TRACE(13, "mes pan vel: %f tilt vel: %f", vpMath::deg(mes_q_dot[0]), vpMath::deg(mes_q_dot[1]));
376  vpDEBUG_TRACE(12, "desired q_dot : %f %f", vpMath::deg(shm.q_dot[0]), vpMath::deg(shm.q_dot[1]));
377  vpDEBUG_TRACE(13, "previous q_dot : %f %f", vpMath::deg(prev_q_dot[0]), vpMath::deg(prev_q_dot[1]));
378 
379  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
380  // test if joint limits are reached
381  if (mes_q[i] < -softLimit[i]) {
382  vpDEBUG_TRACE(12, "Axe %d in low joint limit", i);
383  shm.status[i] = vpRobotBiclopsController::STOP;
384  shm.jointLimit[i] = true;
385  } else if (mes_q[i] > softLimit[i]) {
386  vpDEBUG_TRACE(12, "Axe %d in hight joint limit", i);
387  shm.status[i] = vpRobotBiclopsController::STOP;
388  shm.jointLimit[i] = true;
389  } else {
390  shm.status[i] = vpRobotBiclopsController::SPEED;
391  shm.jointLimit[i] = false;
392  }
393 
394  // Test if new a speed is demanded
395  // if (shm.q_dot[i] != prev_q_dot[i])
396  if (std::fabs(shm.q_dot[i] - prev_q_dot[i]) >
397  std::fabs(vpMath::maximum(shm.q_dot[i], prev_q_dot[i])) * std::numeric_limits<double>::epsilon())
398  new_q_dot[i] = true;
399  else
400  new_q_dot[i] = false;
401 
402  // Test if desired speed change of sign
403  if ((shm.q_dot[i] * prev_q_dot[i]) < 0.)
404  change_dir[i] = true;
405  else
406  change_dir[i] = false;
407  }
408  vpDEBUG_TRACE(13, "status : %d %d", shm.status[0], shm.status[1]);
409  vpDEBUG_TRACE(13, "joint : %d %d", shm.jointLimit[0], shm.jointLimit[1]);
410  vpDEBUG_TRACE(13, "new q_dot : %d %d", new_q_dot[0], new_q_dot[1]);
411  vpDEBUG_TRACE(13, "new dir : %d %d", change_dir[0], change_dir[1]);
412  vpDEBUG_TRACE(13, "force halt : %d %d", force_halt[0], force_halt[1]);
413  vpDEBUG_TRACE(13, "enable limit: %d %d", enable_limit[0], enable_limit[1]);
414 
415  bool updateVelocity = false;
416  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
417  // Test if a new desired speed is to apply
418  if (new_q_dot[i]) {
419  // A new desired speed is to apply
420  if (shm.status[i] == vpRobotBiclopsController::STOP) {
421  // Axis in joint limit
422  if (change_dir[i] == false) {
423  // New desired speed without change of direction
424  // We go in the joint limit
425  if (enable_limit[i] == true) { // limit detection active
426  // We have to stop this axis
427  // Test if this axis was stopped before
428  if (force_halt[i] == false) {
429  q_dot[i] = 0.;
430  force_halt[i] = true; // indicate that it will be stopped
431  updateVelocity = true; // We have to send this new speed
432  }
433  } else {
434  // We have to apply the desired speed to go away the joint
435  // Update the desired speed
436  q_dot[i] = shm.q_dot[i];
437  shm.status[i] = vpRobotBiclopsController::SPEED;
438  force_halt[i] = false;
439  updateVelocity = true; // We have to send this new speed
440  }
441  } else {
442  // New desired speed and change of direction.
443  if (enable_limit[i] == true) { // limit detection active
444  // Update the desired speed to go away the joint limit
445  q_dot[i] = shm.q_dot[i];
446  shm.status[i] = vpRobotBiclopsController::SPEED;
447  force_halt[i] = false;
448  enable_limit[i] = false; // Disable joint limit detection
449  updateVelocity = true; // We have to send this new speed
450  } else {
451  // We have to stop this axis
452  // Test if this axis was stopped before
453  if (force_halt[i] == false) {
454  q_dot[i] = 0.;
455  force_halt[i] = true; // indicate that it will be stopped
456  enable_limit[i] = true; // Joint limit detection must be active
457  updateVelocity = true; // We have to send this new speed
458  }
459  }
460  }
461  } else {
462  // Axis not in joint limit
463 
464  // Update the desired speed
465  q_dot[i] = shm.q_dot[i];
466  shm.status[i] = vpRobotBiclopsController::SPEED;
467  enable_limit[i] = true; // Joint limit detection must be active
468  updateVelocity = true; // We have to send this new speed
469  }
470  } else {
471  // No change of the desired speed. We have to stop the robot in case
472  // of joint limit
473  if (shm.status[i] == vpRobotBiclopsController::STOP) { // axis limit
474  if (enable_limit[i] == true) { // limit detection active
475 
476  // Test if this axis was stopped before
477  if (force_halt[i] == false) {
478  // We have to stop this axis
479  q_dot[i] = 0.;
480  force_halt[i] = true; // indicate that it will be stopped
481  updateVelocity = true; // We have to send this new speed
482  }
483  }
484  } else {
485  // No need to stop the robot
486  enable_limit[i] = true; // Normal situation, activate limit detection
487  }
488  }
489  }
490  // Update the actuals positions
491  controller->writeShm(shm);
492 
493  vpDEBUG_TRACE(11, "unlock mutex vpShm_mutex");
494  pthread_mutex_unlock(&vpShm_mutex);
495 
496  if (updateVelocity) {
497  vpDEBUG_TRACE(12, "apply q_dot : %f %f", vpMath::deg(q_dot[0]), vpMath::deg(q_dot[1]));
498 
499  // Apply the velocity
500  controller->setVelocity(q_dot);
501  }
502 
503  // Update the previous speed for next iteration
504  for (unsigned int i = 0; i < vpBiclops::ndof; i++)
505  prev_q_dot[i] = shm.q_dot[i];
506 
507  vpDEBUG_TRACE(12, "iter: %d", iter);
508 
509  // wait 5 ms
510  vpTime::wait(5.0);
511 
512  // if (pthread_mutex_trylock(&vpEndThread_mutex) == 0) {
513  // vpDEBUG_TRACE (12, "Calling thread will end");
514  // vpDEBUG_TRACE (12, "Unlock mutex vpEndThread_mutex");
515  // std::cout << "Calling thread will end" << std::endl;
516  // std::cout << "Unlock mutex vpEndThread_mutex" << std::endl;
517  //
518  // pthread_mutex_unlock(&vpEndThread_mutex);
519  // break;
520  // }
521 
522  iter++;
523  }
524  controller->stopRequest(false);
525  // Stop the robot
526  vpDEBUG_TRACE(10, "End of the control thread: stop the robot");
527  q_dot = 0;
528  controller->setVelocity(q_dot);
529 
530  delete[] new_q_dot;
531  delete[] change_dir;
532  delete[] force_halt;
533  delete[] enable_limit;
534  vpDEBUG_TRACE(11, "unlock vpEndThread_mutex");
535  pthread_mutex_unlock(&vpEndThread_mutex);
536 
537  vpDEBUG_TRACE(10, "Exit control thread ");
538  // pthread_exit(0);
539 
540  return NULL;
541 }
542 
550 {
551  switch (newState) {
552  case vpRobot::STATE_STOP: {
554  stopMotion();
555  }
556  break;
557  }
560  vpDEBUG_TRACE(12, "Speed to position control.");
561  stopMotion();
562  }
563 
564  break;
565  }
567 
569  vpDEBUG_TRACE(12, "Lock mutex vpEndThread_mutex");
570  pthread_mutex_lock(&vpEndThread_mutex);
571 
572  vpDEBUG_TRACE(12, "Create speed control thread");
573  int code;
574  code = pthread_create(&control_thread, NULL, &vpRobotBiclops::vpRobotBiclopsSpeedControlLoop, &controller);
575  if (code != 0) {
576  vpCERROR << "Cannot create speed biclops control thread: " << code << " strErr=" << strerror(errno)
577  << " strCode=" << strerror(code) << std::endl;
578  }
579 
580  controlThreadCreated = true;
581 
582  vpDEBUG_TRACE(12, "Speed control thread created");
583  }
584  break;
585  }
586  default:
587  break;
588  }
589 
590  return vpRobot::setRobotState(newState);
591 }
592 
599 {
601  q_dot = 0;
602  controller.setVelocity(q_dot);
603  // std::cout << "Request to stop the velocity controller thread...."<<
604  // std::endl;
605  controller.stopRequest(true);
606 }
607 
619 {
621  cMe = vpBiclops::get_cMe();
622 
623  cVe.buildFrom(cMe);
624 }
625 
636 
648 {
649  vpColVector q(2);
651 
652  try {
653  vpBiclops::get_eJe(q, _eJe);
654  } catch (...) {
655  vpERROR_TRACE("catch exception ");
656  throw;
657  }
658 }
659 
668 {
669  vpColVector q(2);
671 
672  try {
673  vpBiclops::get_fJe(q, _fJe);
674  } catch (...) {
675  vpERROR_TRACE("Error caught");
676  throw;
677  }
678 }
679 
687 void vpRobotBiclops::setPositioningVelocity(const double velocity)
688 {
689  if (velocity < 0 || velocity > 100) {
690  vpERROR_TRACE("Bad positionning velocity");
691  throw vpRobotException(vpRobotException::constructionError, "Bad positionning velocity");
692  }
693 
694  positioningVelocity = velocity;
695 }
703 double vpRobotBiclops::getPositioningVelocity(void) { return positioningVelocity; }
704 
721 {
722 
724  vpERROR_TRACE("Robot was not in position-based control\n"
725  "Modification of the robot state");
727  }
728 
729  switch (frame) {
731  vpERROR_TRACE("Cannot move the robot in camera frame: "
732  "not implemented");
733  throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in camera frame: "
734  "not implemented");
735  break;
737  vpERROR_TRACE("Cannot move the robot in reference frame: "
738  "not implemented");
739  throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in reference frame: "
740  "not implemented");
741  break;
742  case vpRobot::MIXT_FRAME:
743  vpERROR_TRACE("Cannot move the robot in mixt frame: "
744  "not implemented");
745  throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in mixt frame: "
746  "not implemented");
747  break;
749  break;
750  }
751 
752  // test if position reachable
753  // if ( (fabs(q[0]) > vpBiclops::panJointLimit) ||
754  // (fabs(q[1]) > vpBiclops::tiltJointLimit) ) {
755  // vpERROR_TRACE ("Positionning error.");
756  // throw vpRobotException (vpRobotException::wrongStateError,
757  // "Positionning error.");
758  // }
759 
760  vpDEBUG_TRACE(12, "Lock mutex vpEndThread_mutex");
761  pthread_mutex_lock(&vpEndThread_mutex);
762  controller.setPosition(q, positioningVelocity);
763  vpDEBUG_TRACE(12, "Unlock mutex vpEndThread_mutex");
764  pthread_mutex_unlock(&vpEndThread_mutex);
765  return;
766 }
767 
784 void vpRobotBiclops::setPosition(const vpRobot::vpControlFrameType frame, const double &q1, const double &q2)
785 {
786  try {
787  vpColVector q(2);
788  q[0] = q1;
789  q[1] = q2;
790 
791  setPosition(frame, q);
792  } catch (...) {
793  vpERROR_TRACE("Error caught");
794  throw;
795  }
796 }
797 
811 void vpRobotBiclops::setPosition(const char *filename)
812 {
813  vpColVector q;
814  if (readPositionFile(filename, q) == false) {
815  vpERROR_TRACE("Cannot get biclops position from file");
816  throw vpRobotException(vpRobotException::readingParametersError, "Cannot get biclops position from file");
817  }
819 }
820 
837 {
838  switch (frame) {
840  vpERROR_TRACE("Cannot get position in camera frame: not implemented");
841  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in camera frame: "
842  "not implemented");
843  break;
845  vpERROR_TRACE("Cannot get position in reference frame: "
846  "not implemented");
847  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in reference frame: "
848  "not implemented");
849  break;
850  case vpRobot::MIXT_FRAME:
851  vpERROR_TRACE("Cannot get position in mixt frame: "
852  "not implemented");
853  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in mixt frame: "
854  "not implemented");
855  break;
857  break;
858  }
859 
861  state = vpRobot::getRobotState();
862 
863  switch (state) {
864  case STATE_STOP:
866  q = controller.getPosition();
867 
868  break;
871  default:
873 
874  vpDEBUG_TRACE(12, "Lock mutex vpMeasure_mutex");
875  pthread_mutex_lock(&vpMeasure_mutex); // Wait until a position is available
876 
877  vpRobotBiclopsController::shmType shm;
878 
879  vpDEBUG_TRACE(12, "Lock mutex vpShm_mutex");
880  pthread_mutex_lock(&vpShm_mutex);
881 
882  shm = controller.readShm();
883 
884  vpDEBUG_TRACE(12, "unlock mutex vpShm_mutex");
885  pthread_mutex_unlock(&vpShm_mutex);
886 
887  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
888  q[i] = shm.actual_q[i];
889  }
890 
891  vpCDEBUG(11) << "++++++++ Measure actuals: " << q.t();
892 
893  vpDEBUG_TRACE(12, "unlock mutex vpMeasure_mutex");
894  pthread_mutex_unlock(&vpMeasure_mutex); // A position is available
895 
896  break;
897  }
898 }
899 
927 {
929  vpERROR_TRACE("Cannot send a velocity to the robot "
930  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
932  "Cannot send a velocity to the robot "
933  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
934  }
935 
936  switch (frame) {
937  case vpRobot::CAMERA_FRAME: {
938  vpERROR_TRACE("Cannot send a velocity to the robot "
939  "in the camera frame: "
940  "functionality not implemented");
941  throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot "
942  "in the camera frame:"
943  "functionality not implemented");
944  }
946  if (q_dot.getRows() != 2) {
947  vpERROR_TRACE("Bad dimension fo speed vector in articular frame");
948  throw vpRobotException(vpRobotException::wrongStateError, "Bad dimension for speed vector "
949  "in articular frame");
950  }
951  break;
952  }
954  vpERROR_TRACE("Cannot send a velocity to the robot "
955  "in the reference frame: "
956  "functionality not implemented");
957  throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot "
958  "in the reference frame:"
959  "functionality not implemented");
960  }
961  case vpRobot::MIXT_FRAME: {
962  vpERROR_TRACE("Cannot send a velocity to the robot "
963  "in the mixt frame: "
964  "functionality not implemented");
965  throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot "
966  "in the mixt frame:"
967  "functionality not implemented");
968  }
969  default: {
970  vpERROR_TRACE("Error in spec of vpRobot. "
971  "Case not taken in account.");
972  throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot ");
973  }
974  }
975 
976  vpDEBUG_TRACE(12, "Velocity limitation.");
977  bool norm = false; // Flag to indicate when velocities need to be nomalized
978 
979  // Saturate articular speed
980  double max = vpBiclops::speedLimit;
981  vpColVector q_dot_sat(vpBiclops::ndof);
982 
983  // init q_dot_saturated
984  q_dot_sat = q_dot;
985 
986  for (unsigned int i = 0; i < vpBiclops::ndof; ++i) // q1 and q2
987  {
988  if (fabs(q_dot[i]) > max) {
989  norm = true;
990  max = fabs(q_dot[i]);
991  vpERROR_TRACE("Excess velocity: ROTATION "
992  "(axe nr.%d).",
993  i);
994  }
995  }
996  // Rotations velocities normalisation
997  if (norm == true) {
998  max = vpBiclops::speedLimit / max;
999  q_dot_sat = q_dot * max;
1000  }
1001 
1002  vpCDEBUG(12) << "send velocity: " << q_dot_sat.t() << std::endl;
1003 
1004  vpRobotBiclopsController::shmType shm;
1005 
1006  vpDEBUG_TRACE(12, "Lock mutex vpShm_mutex");
1007  pthread_mutex_lock(&vpShm_mutex);
1008 
1009  shm = controller.readShm();
1010 
1011  for (unsigned int i = 0; i < vpBiclops::ndof; i++)
1012  shm.q_dot[i] = q_dot[i];
1013 
1014  controller.writeShm(shm);
1015 
1016  vpDEBUG_TRACE(12, "unlock mutex vpShm_mutex");
1017  pthread_mutex_unlock(&vpShm_mutex);
1018 
1019  return;
1020 }
1021 
1022 /* -------------------------------------------------------------------------
1023  */
1024 /* --- GET -----------------------------------------------------------------
1025  */
1026 /* -------------------------------------------------------------------------
1027  */
1028 
1041 {
1042  switch (frame) {
1043  case vpRobot::CAMERA_FRAME:
1044  vpERROR_TRACE("Cannot get position in camera frame: not implemented");
1045  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in camera frame: "
1046  "not implemented");
1047  break;
1049  vpERROR_TRACE("Cannot get position in reference frame: "
1050  "not implemented");
1051  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in reference frame: "
1052  "not implemented");
1053  break;
1054  case vpRobot::MIXT_FRAME:
1055  vpERROR_TRACE("Cannot get position in mixt frame: "
1056  "not implemented");
1057  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in mixt frame: "
1058  "not implemented");
1059  break;
1061  break;
1062  }
1063 
1065  state = vpRobot::getRobotState();
1066 
1067  switch (state) {
1068  case STATE_STOP:
1070  q_dot = controller.getVelocity();
1071 
1072  break;
1075  default:
1076  q_dot.resize(vpBiclops::ndof);
1077 
1078  vpDEBUG_TRACE(12, "Lock mutex vpMeasure_mutex");
1079  pthread_mutex_lock(&vpMeasure_mutex); // Wait until a position is available
1080 
1081  vpRobotBiclopsController::shmType shm;
1082 
1083  vpDEBUG_TRACE(12, "Lock mutex vpShm_mutex");
1084  pthread_mutex_lock(&vpShm_mutex);
1085 
1086  shm = controller.readShm();
1087 
1088  vpDEBUG_TRACE(12, "unlock mutex vpShm_mutex");
1089  pthread_mutex_unlock(&vpShm_mutex);
1090 
1091  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
1092  q_dot[i] = shm.actual_q_dot[i];
1093  }
1094 
1095  vpCDEBUG(11) << "++++++++ Velocity actuals: " << q_dot.t();
1096 
1097  vpDEBUG_TRACE(12, "unlock mutex vpMeasure_mutex");
1098  pthread_mutex_unlock(&vpMeasure_mutex); // A position is available
1099 
1100  break;
1101  }
1102 }
1103 
1116 {
1117  vpColVector q_dot;
1118  getVelocity(frame, q_dot);
1119 
1120  return q_dot;
1121 }
1122 
1142 bool vpRobotBiclops::readPositionFile(const std::string &filename, vpColVector &q)
1143 {
1144  std::ifstream fd(filename.c_str(), std::ios::in);
1145 
1146  if (!fd.is_open()) {
1147  return false;
1148  }
1149 
1150  std::string line;
1151  std::string key("R:");
1152  std::string id("#PTU-EVI - Position");
1153  bool pos_found = false;
1154  int lineNum = 0;
1155 
1157 
1158  while (std::getline(fd, line)) {
1159  lineNum++;
1160  if (lineNum == 1) {
1161  if (!(line.compare(0, id.size(), id) == 0)) { // check if Biclops position file
1162  std::cout << "Error: this position file " << filename << " is not for Biclops robot" << std::endl;
1163  return false;
1164  }
1165  }
1166  if ((line.compare(0, 1, "#") == 0)) { // skip comment
1167  continue;
1168  }
1169  if ((line.compare(0, key.size(), key) == 0)) { // decode position
1170  // check if there are at least njoint values in the line
1171  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
1172  if (chain.size() < vpBiclops::ndof + 1) // try to split with tab separator
1173  chain = vpIoTools::splitChain(line, std::string("\t"));
1174  if (chain.size() < vpBiclops::ndof + 1)
1175  continue;
1176 
1177  std::istringstream ss(line);
1178  std::string key_;
1179  ss >> key_;
1180  for (unsigned int i = 0; i < vpBiclops::ndof; i++)
1181  ss >> q[i];
1182  pos_found = true;
1183  break;
1184  }
1185  }
1186 
1187  // converts rotations from degrees into radians
1188  q.deg2rad();
1189 
1190  fd.close();
1191 
1192  if (!pos_found) {
1193  std::cout << "Error: unable to find a position for Biclops robot in " << filename << std::endl;
1194  return false;
1195  }
1196 
1197  return true;
1198 }
1199 
1223 {
1224  vpColVector q_current; // current position
1225 
1227 
1228  switch (frame) {
1231  d = q_current - q_previous;
1232  break;
1233 
1234  case vpRobot::CAMERA_FRAME: {
1235  d.resize(6);
1236  vpHomogeneousMatrix fMc_current;
1237  vpHomogeneousMatrix fMc_previous;
1238  fMc_current = vpBiclops::get_fMc(q_current);
1239  fMc_previous = vpBiclops::get_fMc(q_previous);
1240  vpHomogeneousMatrix c_previousMc_current;
1241  // fMc_c = fMc_p * c_pMc_c
1242  // => c_pMc_c = (fMc_p)^-1 * fMc_c
1243  c_previousMc_current = fMc_previous.inverse() * fMc_current;
1244 
1245  // Compute the instantaneous velocity from this homogeneous matrix.
1246  d = vpExponentialMap::inverse(c_previousMc_current);
1247  break;
1248  }
1249 
1251  vpERROR_TRACE("Cannot get a velocity in the reference frame: "
1252  "functionality not implemented");
1253  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a velocity in the reference frame:"
1254  "functionality not implemented");
1255  break;
1256  case vpRobot::MIXT_FRAME:
1257  vpERROR_TRACE("Cannot get a velocity in the mixt frame: "
1258  "functionality not implemented");
1259  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a velocity in the mixt frame:"
1260  "functionality not implemented");
1261  break;
1262  }
1263 
1264  q_previous = q_current; // Update for next call of this method
1265 }
1266 
1267 #elif !defined(VISP_BUILD_SHARED_LIBS)
1268 // Work arround to avoid warning: libvisp_robot.a(vpRobotBiclops.cpp.o) has no
1269 // symbols
1270 void dummy_vpRobotBiclops(){};
1271 #endif
Jacobian, geometric model functionnalities... for biclops, pan, tilt head.
Definition: vpBiclops.h:77
vpHomogeneousMatrix get_cMe() const
Definition: vpBiclops.h:157
static vpColVector inverse(const vpHomogeneousMatrix &M)
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:104
bool readPositionFile(const std::string &filename, vpColVector &q)
VISP_EXPORT int wait(double t0, double t)
Definition: vpTime.cpp:150
Error that can be emited by the vpRobot class and its derivates.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &q_dot)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q)
#define vpCERROR
Definition: vpDebug.h:365
static const unsigned int ndof
Definition: vpBiclops.h:126
void get_eJe(vpMatrix &_eJe)
Implementation of an homogeneous matrix and operations on such kind of matrices.
static const float tiltJointLimit
Definition: vpBiclops.h:132
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &q_dot)
static const float speedLimit
Definition: vpBiclops.h:133
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpBiclops.cpp:360
#define vpERROR_TRACE
Definition: vpDebug.h:393
Initialize the position controller.
Definition: vpRobot.h:68
void setConfigFile(const std::string &filename="/usr/share/BiclopsDefault.cfg")
unsigned int getRows() const
Definition: vpArray2D.h:156
vpHomogeneousMatrix inverse() const
vpRowVector t() const
Class that defines a generic virtual robot.
Definition: vpRobot.h:58
void get_fJe(vpMatrix &_fJe)
vpControlFrameType
Definition: vpRobot.h:75
static const double defaultPositioningVelocity
No copy constructor allowed.
virtual ~vpRobotBiclops(void)
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
void get_cVe(vpVelocityTwistMatrix &_cVe) const
vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
void deg2rad()
Definition: vpColVector.h:134
static Type maximum(const Type &a, const Type &b)
Definition: vpMath.h:137
static const float panJointLimit
Definition: vpBiclops.h:131
Initialize the velocity controller.
Definition: vpRobot.h:67
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:139
vpRobotStateType
Definition: vpRobot.h:64
Initialize the acceleration controller.
Definition: vpRobot.h:69
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
#define vpCDEBUG(level)
Definition: vpDebug.h:511
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1665
void get_fMc(const vpColVector &q, vpHomogeneousMatrix &fMc) const
Definition: vpBiclops.cpp:95
static double rad(double deg)
Definition: vpMath.h:102
static double deg(double rad)
Definition: vpMath.h:95
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &d)
double getPositioningVelocity(void)
#define vpDEBUG_TRACE
Definition: vpDebug.h:487
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpBiclops.cpp:394
static void * vpRobotBiclopsSpeedControlLoop(void *arg)
void setPositioningVelocity(const double velocity)
void resize(const unsigned int i, const bool flagNullify=true)
Definition: vpColVector.h:241