Visual Servoing Platform  version 3.6.1 under development (2024-07-27)
vpRobotBiclops.cpp
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
4  *
5  * This software is free software; you can redistribute it and/or modify
6  * it under the terms of the GNU General Public License as published by
7  * the Free Software Foundation; either version 2 of the License, or
8  * (at your option) any later version.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See https://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Interface for the Biclops robot.
32  */
33 
34 #include <visp3/core/vpConfig.h>
35 
36 #if defined(VISP_HAVE_BICLOPS) && defined(VISP_HAVE_THREADS)
37 
38 #include <cmath> // std::fabs
39 #include <errno.h>
40 #include <limits> // numeric_limits
41 #include <signal.h>
42 #include <string.h>
43 #include <mutex>
44 
45 #include <visp3/core/vpExponentialMap.h>
46 #include <visp3/core/vpIoTools.h>
47 #include <visp3/core/vpTime.h>
48 #include <visp3/robot/vpBiclops.h>
49 #include <visp3/robot/vpRobotBiclops.h>
50 #include <visp3/robot/vpRobotException.h>
51 
52 #include "private/vpRobotBiclopsController_impl.h"
53 
54 //#define VP_DEBUG // Activate the debug mode
55 //#define VP_DEBUG_MODE 12 // Activate debug level up to 12
56 #include <visp3/core/vpDebug.h>
57 
59 /* ---------------------------------------------------------------------- */
60 /* --- STATIC ------------------------------------------------------------ */
61 /* ------------------------------------------------------------------------ */
62 
64 
65 static std::mutex m_mutex_end_thread;
66 static std::mutex m_mutex_shm;
67 static std::mutex m_mutex_measure;
68 
69 /* ----------------------------------------------------------------------- */
70 /* --- CONSTRUCTOR ------------------------------------------------------ */
71 /* ---------------------------------------------------------------------- */
72 
74  : vpBiclops(), vpRobot(), m_control_thread(), m_positioningVelocity(defaultPositioningVelocity),
75  m_q_previous()
76 {
77  vpDEBUG_TRACE(12, "Begin default constructor.");
78 
79  m_controller = new vpRobotBiclopsController;
80  setConfigFile("/usr/share/BiclopsDefault.cfg");
81 }
82 
83 vpRobotBiclops::vpRobotBiclops(const std::string &filename)
84  : vpBiclops(), vpRobot(), m_control_thread(), m_positioningVelocity(defaultPositioningVelocity),
85  m_q_previous()
86 {
87  vpDEBUG_TRACE(12, "Begin default constructor.");
88 
89  m_controller = new vpRobotBiclopsController;
90  setConfigFile(filename);
91 
92  init();
93 }
94 
96 {
97  vpDEBUG_TRACE(12, "Start vpRobotBiclops::~vpRobotBiclops()");
99 
100  vpDEBUG_TRACE(12, "Unlock mutex vpEndThread_mutex");
101  m_mutex_end_thread.unlock();
102 
103  /* wait the end of the control thread */
104  vpDEBUG_TRACE(12, "Wait end of control thread");
105 
106  if (m_control_thread.joinable()) {
107  m_control_thread.join();
108  }
109 
110  delete m_controller;
111  vpDEBUG_TRACE(12, "Stop vpRobotBiclops::~vpRobotBiclops()");
112 }
113 
114 void vpRobotBiclops::setConfigFile(const std::string &filename) { m_configfile = filename; }
115 
117 {
118  // test if the config file exists
119  FILE *fd = fopen(m_configfile.c_str(), "r");
120  if (fd == nullptr) {
121  vpCERROR << "Cannot open Biclops config file: " << m_configfile << std::endl;
122  throw vpRobotException(vpRobotException::constructionError, "Cannot open connection with biclops");
123  }
124  fclose(fd);
125 
126  // Initialize the controller
127  m_controller->init(m_configfile);
128 
129  try {
131  }
132  catch (...) {
133  vpERROR_TRACE("Error caught");
134  throw;
135  }
136 
137  // Initialize previous articular position to manage getDisplacement()
138  m_q_previous.resize(vpBiclops::ndof);
139  m_q_previous = 0;
140 
141  return;
142 }
143 
145 {
146  vpRobotBiclopsController *controller = static_cast<vpRobotBiclopsController *>(arg);
147 
148  // PMDAxisControl *m_panAxis = controller->getPanAxis();
149  // PMDAxisControl *m_tiltAxis = controller->getTiltAxis();
150  vpRobotBiclopsController::shmType shm;
151 
152  vpDEBUG_TRACE(10, "Start control loop");
153  vpColVector mes_q;
154  vpColVector mes_q_dot;
155  vpColVector softLimit(vpBiclops::ndof);
157  bool *new_q_dot = new bool[vpBiclops::ndof];
158  bool *change_dir = new bool[vpBiclops::ndof]; // change of direction
159  bool *force_halt = new bool[vpBiclops::ndof]; // force an axis to halt
160  bool *enable_limit = new bool[vpBiclops::ndof]; // enable soft limit
161  vpColVector prev_q_dot(vpBiclops::ndof); // previous desired speed
162  double secure = vpMath::rad(2); // add a security angle before joint limit
163 
164  // Set the soft limits
165  softLimit[0] = vpBiclops::panJointLimit - secure;
166  softLimit[1] = vpBiclops::tiltJointLimit - secure;
167  vpDEBUG_TRACE(12, "soft limit pan: %f tilt: %f", vpMath::deg(softLimit[0]), vpMath::deg(softLimit[1]));
168 
169  // Initialization
170  vpDEBUG_TRACE(11, "Lock mutex vpShm_mutex");
171  m_mutex_shm.lock();
172 
173  shm = controller->readShm();
174 
175  vpDEBUG_TRACE(11, "unlock mutex vpShm_mutex");
176  m_mutex_shm.unlock();
177 
178  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
179  prev_q_dot[i] = shm.q_dot[i];
180  new_q_dot[i] = false;
181  change_dir[i] = false;
182  force_halt[i] = false;
183  enable_limit[i] = true;
184  }
185 
186  // Initialize actual position and velocity
187  mes_q = controller->getActualPosition();
188  mes_q_dot = controller->getActualVelocity();
189 
190  vpDEBUG_TRACE(11, "Lock mutex vpShm_mutex");
191  m_mutex_shm.lock();
192 
193  shm = controller->readShm();
194  // Updates the shm
195  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
196  shm.actual_q[i] = mes_q[i];
197  shm.actual_q_dot[i] = mes_q_dot[i];
198  }
199  // Update current positions
200  controller->writeShm(shm);
201 
202  vpDEBUG_TRACE(11, "unlock mutex vpShm_mutex");
203  m_mutex_shm.unlock();
204 
205  vpDEBUG_TRACE(11, "unlock mutex vpMeasure_mutex");
206  m_mutex_measure.unlock(); // A position is available
207 
208  while (!controller->isStopRequested()) {
209 
210  // Get actual position and velocity
211  mes_q = controller->getActualPosition();
212  mes_q_dot = controller->getActualVelocity();
213 
214  vpDEBUG_TRACE(11, "Lock mutex vpShm_mutex");
215  m_mutex_shm.lock();
216 
217  shm = controller->readShm();
218 
219  // Updates the shm
220  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
221  shm.actual_q[i] = mes_q[i];
222  shm.actual_q_dot[i] = mes_q_dot[i];
223  }
224 
225  vpDEBUG_TRACE(12, "mes pan: %f tilt: %f", vpMath::deg(mes_q[0]), vpMath::deg(mes_q[1]));
226  vpDEBUG_TRACE(13, "mes pan vel: %f tilt vel: %f", vpMath::deg(mes_q_dot[0]), vpMath::deg(mes_q_dot[1]));
227  vpDEBUG_TRACE(12, "desired q_dot : %f %f", vpMath::deg(shm.q_dot[0]), vpMath::deg(shm.q_dot[1]));
228  vpDEBUG_TRACE(13, "previous q_dot : %f %f", vpMath::deg(prev_q_dot[0]), vpMath::deg(prev_q_dot[1]));
229 
230  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
231  // test if joint limits are reached
232  if (mes_q[i] < -softLimit[i]) {
233  vpDEBUG_TRACE(12, "Axe %d in low joint limit", i);
234  shm.status[i] = vpRobotBiclopsController::STOP;
235  shm.jointLimit[i] = true;
236  }
237  else if (mes_q[i] > softLimit[i]) {
238  vpDEBUG_TRACE(12, "Axe %d in hight joint limit", i);
239  shm.status[i] = vpRobotBiclopsController::STOP;
240  shm.jointLimit[i] = true;
241  }
242  else {
243  shm.status[i] = vpRobotBiclopsController::SPEED;
244  shm.jointLimit[i] = false;
245  }
246 
247  // Test if new a speed is demanded
248  // if (shm.q_dot[i] != prev_q_dot[i])
249  if (std::fabs(shm.q_dot[i] - prev_q_dot[i]) >
250  std::fabs(vpMath::maximum(shm.q_dot[i], prev_q_dot[i])) * std::numeric_limits<double>::epsilon())
251  new_q_dot[i] = true;
252  else
253  new_q_dot[i] = false;
254 
255  // Test if desired speed change of sign
256  if ((shm.q_dot[i] * prev_q_dot[i]) < 0.)
257  change_dir[i] = true;
258  else
259  change_dir[i] = false;
260  }
261  vpDEBUG_TRACE(13, "status : %d %d", shm.status[0], shm.status[1]);
262  vpDEBUG_TRACE(13, "joint : %d %d", shm.jointLimit[0], shm.jointLimit[1]);
263  vpDEBUG_TRACE(13, "new q_dot : %d %d", new_q_dot[0], new_q_dot[1]);
264  vpDEBUG_TRACE(13, "new dir : %d %d", change_dir[0], change_dir[1]);
265  vpDEBUG_TRACE(13, "force halt : %d %d", force_halt[0], force_halt[1]);
266  vpDEBUG_TRACE(13, "enable limit: %d %d", enable_limit[0], enable_limit[1]);
267 
268  bool updateVelocity = false;
269  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
270  // Test if a new desired speed is to apply
271  if (new_q_dot[i]) {
272  // A new desired speed is to apply
273  if (shm.status[i] == vpRobotBiclopsController::STOP) {
274  // Axis in joint limit
275  if (change_dir[i] == false) {
276  // New desired speed without change of direction
277  // We go in the joint limit
278  if (enable_limit[i] == true) { // limit detection active
279  // We have to stop this axis
280  // Test if this axis was stopped before
281  if (force_halt[i] == false) {
282  q_dot[i] = 0.;
283  force_halt[i] = true; // indicate that it will be stopped
284  updateVelocity = true; // We have to send this new speed
285  }
286  }
287  else {
288  // We have to apply the desired speed to go away the joint
289  // Update the desired speed
290  q_dot[i] = shm.q_dot[i];
291  shm.status[i] = vpRobotBiclopsController::SPEED;
292  force_halt[i] = false;
293  updateVelocity = true; // We have to send this new speed
294  }
295  }
296  else {
297  // New desired speed and change of direction.
298  if (enable_limit[i] == true) { // limit detection active
299  // Update the desired speed to go away the joint limit
300  q_dot[i] = shm.q_dot[i];
301  shm.status[i] = vpRobotBiclopsController::SPEED;
302  force_halt[i] = false;
303  enable_limit[i] = false; // Disable joint limit detection
304  updateVelocity = true; // We have to send this new speed
305  }
306  else {
307  // We have to stop this axis
308  // Test if this axis was stopped before
309  if (force_halt[i] == false) {
310  q_dot[i] = 0.;
311  force_halt[i] = true; // indicate that it will be stopped
312  enable_limit[i] = true; // Joint limit detection must be active
313  updateVelocity = true; // We have to send this new speed
314  }
315  }
316  }
317  }
318  else {
319  // Axis not in joint limit
320 
321  // Update the desired speed
322  q_dot[i] = shm.q_dot[i];
323  shm.status[i] = vpRobotBiclopsController::SPEED;
324  enable_limit[i] = true; // Joint limit detection must be active
325  updateVelocity = true; // We have to send this new speed
326  }
327  }
328  else {
329  // No change of the desired speed. We have to stop the robot in case
330  // of joint limit
331  if (shm.status[i] == vpRobotBiclopsController::STOP) { // axis limit
332  if (enable_limit[i] == true) { // limit detection active
333 
334  // Test if this axis was stopped before
335  if (force_halt[i] == false) {
336  // We have to stop this axis
337  q_dot[i] = 0.;
338  force_halt[i] = true; // indicate that it will be stopped
339  updateVelocity = true; // We have to send this new speed
340  }
341  }
342  }
343  else {
344  // No need to stop the robot
345  enable_limit[i] = true; // Normal situation, activate limit detection
346  }
347  }
348  }
349  // Update the actual positions
350  controller->writeShm(shm);
351 
352  vpDEBUG_TRACE(11, "unlock mutex vpShm_mutex");
353  m_mutex_shm.unlock();
354 
355  if (updateVelocity) {
356  vpDEBUG_TRACE(12, "apply q_dot : %f %f", vpMath::deg(q_dot[0]), vpMath::deg(q_dot[1]));
357 
358  // Apply the velocity
359  controller->setVelocity(q_dot);
360  }
361 
362  // Update the previous speed for next iteration
363  for (unsigned int i = 0; i < vpBiclops::ndof; i++)
364  prev_q_dot[i] = shm.q_dot[i];
365 
366  // wait 5 ms
367  vpTime::wait(5.0);
368  }
369  controller->stopRequest(false);
370  // Stop the robot
371  vpDEBUG_TRACE(10, "End of the control thread: stop the robot");
372  q_dot = 0;
373  controller->setVelocity(q_dot);
374 
375  delete[] new_q_dot;
376  delete[] change_dir;
377  delete[] force_halt;
378  delete[] enable_limit;
379  vpDEBUG_TRACE(11, "unlock vpEndThread_mutex");
380  m_mutex_end_thread.unlock();
381 }
382 
384 {
385  switch (newState) {
386  case vpRobot::STATE_STOP: {
388  stopMotion();
389  }
390  break;
391  }
394  vpDEBUG_TRACE(12, "Speed to position control.");
395  stopMotion();
396  }
397 
398  break;
399  }
401 
403  vpDEBUG_TRACE(12, "Lock mutex vpEndThread_mutex");
404  m_mutex_end_thread.lock();
405 
406  vpDEBUG_TRACE(12, "Create speed control thread");
407  m_control_thread = std::thread(&vpRobotBiclops::vpRobotBiclopsSpeedControlLoop, m_controller);
408  vpTime::wait(100.0);
409 
410  vpDEBUG_TRACE(12, "Speed control thread created");
411  }
412  break;
413  }
414  default:
415  break;
416  }
417 
418  return vpRobot::setRobotState(newState);
419 }
420 
422 {
424  q_dot = 0;
425  m_controller->setVelocity(q_dot);
426  // std::cout << "Request to stop the velocity controller thread...." << std::endl;
427  m_controller->stopRequest(true);
428 }
429 
431 {
433  cMe = vpBiclops::get_cMe();
434 
435  cVe.build(cMe);
436 }
437 
439 
441 {
442  vpColVector q(2);
444 
446 }
447 
449 {
450  vpColVector q(2);
452 
454 }
455 
457 {
458  if (velocity < 0 || velocity > 100) {
459  vpERROR_TRACE("Bad positioning velocity");
460  throw vpRobotException(vpRobotException::constructionError, "Bad positioning velocity");
461  }
462 
463  m_positioningVelocity = velocity;
464 }
465 
466 double vpRobotBiclops::getPositioningVelocity(void) { return m_positioningVelocity; }
467 
469 {
470 
472  vpERROR_TRACE("Robot was not in position-based control\n"
473  "Modification of the robot state");
475  }
476 
477  switch (frame) {
479  throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in camera frame: "
480  "not implemented");
481  break;
483  throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in reference frame: "
484  "not implemented");
485  break;
486  case vpRobot::MIXT_FRAME:
487  throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in mixt frame: "
488  "not implemented");
489  break;
491  throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in end-effector frame: "
492  "not implemented");
493  break;
495  break;
496  }
497 
498  vpDEBUG_TRACE(12, "Lock mutex vpEndThread_mutex");
499  m_mutex_end_thread.lock();
500  m_controller->setPosition(q, m_positioningVelocity);
501  vpDEBUG_TRACE(12, "Unlock mutex vpEndThread_mutex");
502  m_mutex_end_thread.unlock();
503  return;
504 }
505 
506 void vpRobotBiclops::setPosition(const vpRobot::vpControlFrameType frame, const double &q1, const double &q2)
507 {
508  try {
509  vpColVector q(2);
510  q[0] = q1;
511  q[1] = q2;
512 
513  setPosition(frame, q);
514  }
515  catch (...) {
516  vpERROR_TRACE("Error caught");
517  throw;
518  }
519 }
520 
521 void vpRobotBiclops::setPosition(const std::string &filename)
522 {
523  vpColVector q;
524  if (readPositionFile(filename.c_str(), q) == false) {
525  vpERROR_TRACE("Cannot get Biclops position from file");
526  throw vpRobotException(vpRobotException::readingParametersError, "Cannot get Biclops position from file");
527  }
529 }
530 
532 {
533  switch (frame) {
535  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in camera frame: "
536  "not implemented");
537  break;
539  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in reference frame: "
540  "not implemented");
541  break;
542  case vpRobot::MIXT_FRAME:
543  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in mixt frame: "
544  "not implemented");
545  break;
547  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in end-effector frame: "
548  "not implemented");
549  break;
551  break;
552  }
553 
555  state = vpRobot::getRobotState();
556 
557  switch (state) {
558  case STATE_STOP:
560  q = m_controller->getPosition();
561 
562  break;
565  default:
567 
568  vpDEBUG_TRACE(12, "Lock mutex vpMeasure_mutex");
569  m_mutex_measure.lock(); // Wait until a position is available
570 
571  vpRobotBiclopsController::shmType shm;
572 
573  vpDEBUG_TRACE(12, "Lock mutex vpShm_mutex");
574  m_mutex_shm.lock();
575 
576  shm = m_controller->readShm();
577 
578  vpDEBUG_TRACE(12, "unlock mutex vpShm_mutex");
579  m_mutex_shm.unlock();
580 
581  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
582  q[i] = shm.actual_q[i];
583  }
584 
585  vpCDEBUG(11) << "++++++++ Measure actuals: " << q.t();
586 
587  vpDEBUG_TRACE(12, "unlock mutex vpMeasure_mutex");
588  m_mutex_measure.unlock(); // A position is available
589 
590  break;
591  }
592 }
593 
595 {
597  vpERROR_TRACE("Cannot send a velocity to the robot "
598  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
600  "Cannot send a velocity to the robot "
601  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
602  }
603 
604  switch (frame) {
605  case vpRobot::CAMERA_FRAME: {
606  throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot "
607  "in the camera frame:"
608  "functionality not implemented");
609  }
610  case vpRobot::JOINT_STATE: {
611  if (q_dot.getRows() != 2) {
612  throw vpRobotException(vpRobotException::wrongStateError, "Bad dimension for speed vector "
613  "in joint state");
614  }
615  break;
616  }
618  throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot "
619  "in the reference frame:"
620  "functionality not implemented");
621  }
622  case vpRobot::MIXT_FRAME: {
623  throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot "
624  "in the mixt frame:"
625  "functionality not implemented");
626  }
628  throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot "
629  "in the end-effector frame:"
630  "functionality not implemented");
631  }
632  default: {
633  throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot ");
634  }
635  }
636 
637  vpDEBUG_TRACE(12, "Velocity limitation.");
638  bool norm = false; // Flag to indicate when velocities need to be normalized
639 
640  // Saturate joint speed
641  double max = vpBiclops::speedLimit;
642  vpColVector q_dot_sat(vpBiclops::ndof);
643 
644  // init q_dot_saturated
645  q_dot_sat = q_dot;
646 
647  for (unsigned int i = 0; i < vpBiclops::ndof; ++i) // q1 and q2
648  {
649  if (fabs(q_dot[i]) > max) {
650  norm = true;
651  max = fabs(q_dot[i]);
652  vpERROR_TRACE("Excess velocity: ROTATION "
653  "(axe nr.%d).",
654  i);
655  }
656  }
657  // Rotations velocities normalization
658  if (norm == true) {
659  max = vpBiclops::speedLimit / max;
660  q_dot_sat = q_dot * max;
661  }
662 
663  vpCDEBUG(12) << "send velocity: " << q_dot_sat.t() << std::endl;
664 
665  vpRobotBiclopsController::shmType shm;
666 
667  vpDEBUG_TRACE(12, "Lock mutex vpShm_mutex");
668  m_mutex_shm.lock();
669 
670  shm = m_controller->readShm();
671 
672  for (unsigned int i = 0; i < vpBiclops::ndof; i++)
673  shm.q_dot[i] = q_dot[i];
674 
675  m_controller->writeShm(shm);
676 
677  vpDEBUG_TRACE(12, "unlock mutex vpShm_mutex");
678  m_mutex_shm.unlock();
679 
680  return;
681 }
682 
684 {
685  switch (frame) {
687  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in camera frame: "
688  "not implemented");
689  break;
691  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in reference frame: "
692  "not implemented");
693  break;
694  case vpRobot::MIXT_FRAME:
695  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in mixt frame: "
696  "not implemented");
697  break;
699  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get position in end-effector frame: "
700  "not implemented");
701  break;
703  break;
704  }
705 
707  state = vpRobot::getRobotState();
708 
709  switch (state) {
710  case STATE_STOP:
712  q_dot = m_controller->getVelocity();
713 
714  break;
717  default:
718  q_dot.resize(vpBiclops::ndof);
719 
720  vpDEBUG_TRACE(12, "Lock mutex vpMeasure_mutex");
721  m_mutex_measure.lock(); // Wait until a position is available
722 
723  vpRobotBiclopsController::shmType shm;
724 
725  vpDEBUG_TRACE(12, "Lock mutex vpShm_mutex");
726  m_mutex_shm.lock();
727 
728  shm = m_controller->readShm();
729 
730  vpDEBUG_TRACE(12, "unlock mutex vpShm_mutex");
731  m_mutex_shm.unlock();
732 
733  for (unsigned int i = 0; i < vpBiclops::ndof; i++) {
734  q_dot[i] = shm.actual_q_dot[i];
735  }
736 
737  vpCDEBUG(11) << "++++++++ Velocity actuals: " << q_dot.t();
738 
739  vpDEBUG_TRACE(12, "unlock mutex vpMeasure_mutex");
740  m_mutex_measure.unlock(); // A position is available
741 
742  break;
743  }
744 }
745 
747 {
748  vpColVector q_dot;
749  getVelocity(frame, q_dot);
750 
751  return q_dot;
752 }
753 
754 bool vpRobotBiclops::readPositionFile(const std::string &filename, vpColVector &q)
755 {
756  std::ifstream fd(filename.c_str(), std::ios::in);
757 
758  if (!fd.is_open()) {
759  return false;
760  }
761 
762  std::string line;
763  std::string key("R:");
764  std::string id("#PTU-EVI - Position");
765  bool pos_found = false;
766  int lineNum = 0;
767 
769 
770  while (std::getline(fd, line)) {
771  lineNum++;
772  if (lineNum == 1) {
773  if (!(line.compare(0, id.size(), id) == 0)) { // check if Biclops position file
774  std::cout << "Error: this position file " << filename << " is not for Biclops robot" << std::endl;
775  return false;
776  }
777  }
778  if ((line.compare(0, 1, "#") == 0)) { // skip comment
779  continue;
780  }
781  if ((line.compare(0, key.size(), key) == 0)) { // decode position
782  // check if there are at least njoint values in the line
783  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
784  if (chain.size() < vpBiclops::ndof + 1) // try to split with tab separator
785  chain = vpIoTools::splitChain(line, std::string("\t"));
786  if (chain.size() < vpBiclops::ndof + 1)
787  continue;
788 
789  std::istringstream ss(line);
790  std::string key_;
791  ss >> key_;
792  for (unsigned int i = 0; i < vpBiclops::ndof; i++)
793  ss >> q[i];
794  pos_found = true;
795  break;
796  }
797  }
798 
799  // converts rotations from degrees into radians
800  q.deg2rad();
801 
802  fd.close();
803 
804  if (!pos_found) {
805  std::cout << "Error: unable to find a position for Biclops robot in " << filename << std::endl;
806  return false;
807  }
808 
809  return true;
810 }
811 
813 {
814  vpColVector q_current; // current position
815 
816  getPosition(vpRobot::JOINT_STATE, q_current);
817 
818  switch (frame) {
820  d.resize(vpBiclops::ndof);
821  d = q_current - m_q_previous;
822  break;
823 
824  case vpRobot::CAMERA_FRAME: {
825  d.resize(6);
826  vpHomogeneousMatrix fMc_current;
827  vpHomogeneousMatrix fMc_previous;
828  fMc_current = vpBiclops::get_fMc(q_current);
829  fMc_previous = vpBiclops::get_fMc(m_q_previous);
830  vpHomogeneousMatrix c_previousMc_current;
831  // fMc_c = fMc_p * c_pMc_c
832  // => c_pMc_c = (fMc_p)^-1 * fMc_c
833  c_previousMc_current = fMc_previous.inverse() * fMc_current;
834 
835  // Compute the instantaneous velocity from this homogeneous matrix.
836  d = vpExponentialMap::inverse(c_previousMc_current);
837  break;
838  }
839 
841  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a velocity in the reference frame:"
842  "functionality not implemented");
843  break;
844  case vpRobot::MIXT_FRAME:
845  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a velocity in the mixt frame:"
846  "functionality not implemented");
847  break;
849  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a velocity in the end-effector frame:"
850  "functionality not implemented");
851  break;
852  }
853 
854  m_q_previous = q_current; // Update for next call of this method
855 }
856 END_VISP_NAMESPACE
857 #elif !defined(VISP_BUILD_SHARED_LIBS)
858 // Work around to avoid warning: libvisp_robot.a(vpRobotBiclops.cpp.o) has no symbols
859 void dummy_vpRobotBiclops() { };
860 #endif
unsigned int getRows() const
Definition: vpArray2D.h:347
Jacobian, geometric model functionalities... for Biclops, pan, tilt head.
Definition: vpBiclops.h:64
static const float speedLimit
Pan and tilt axis max velocity in rad/s to perform a displacement.
Definition: vpBiclops.h:107
static const float tiltJointLimit
Tilt axis +/- joint limit in rad.
Definition: vpBiclops.h:106
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpBiclops.cpp:237
void get_fMc(const vpColVector &q, vpHomogeneousMatrix &fMc) const
Definition: vpBiclops.cpp:57
vpHomogeneousMatrix get_cMe() const
Definition: vpBiclops.h:195
static const float panJointLimit
Pan axis +/- joint limit in rad.
Definition: vpBiclops.h:105
static const unsigned int ndof
Number of dof.
Definition: vpBiclops.h:101
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpBiclops.cpp:212
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
vpColVector & deg2rad()
Definition: vpColVector.h:380
vpRowVector t() const
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:1143
static vpColVector inverse(const vpHomogeneousMatrix &M)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1661
static double rad(double deg)
Definition: vpMath.h:129
static Type maximum(const Type &a, const Type &b)
Definition: vpMath.h:254
static double deg(double rad)
Definition: vpMath.h:119
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
void setPositioningVelocity(double velocity)
virtual ~vpRobotBiclops()
double getPositioningVelocity(void)
void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &d) VP_OVERRIDE
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &q_dot)
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
bool readPositionFile(const std::string &filename, vpColVector &q)
void get_cVe(vpVelocityTwistMatrix &cVe) const
vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState) VP_OVERRIDE
void get_fJe(vpMatrix &fJe) VP_OVERRIDE
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) VP_OVERRIDE
static const double defaultPositioningVelocity
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &q_dot) VP_OVERRIDE
void setConfigFile(const std::string &filename="/usr/share/BiclopsDefault.cfg")
void init() VP_OVERRIDE
static void vpRobotBiclopsSpeedControlLoop(void *arg)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q) VP_OVERRIDE
Error that can be emitted by the vpRobot class and its derivatives.
@ wrongStateError
Wrong robot state.
@ constructionError
Error from constructor.
@ readingParametersError
Cannot parse parameters.
Class that defines a generic virtual robot.
Definition: vpRobot.h:59
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
Definition: vpRobot.h:106
virtual vpRobotStateType getRobotState(void) const
Definition: vpRobot.h:155
vpControlFrameType
Definition: vpRobot.h:77
@ REFERENCE_FRAME
Definition: vpRobot.h:78
@ JOINT_STATE
Definition: vpRobot.h:82
@ MIXT_FRAME
Definition: vpRobot.h:88
@ CAMERA_FRAME
Definition: vpRobot.h:84
@ END_EFFECTOR_FRAME
Definition: vpRobot.h:83
vpRobotStateType
Definition: vpRobot.h:65
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition: vpRobot.h:68
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:67
@ STATE_ACCELERATION_CONTROL
Initialize the acceleration controller.
Definition: vpRobot.h:69
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition: vpRobot.h:66
vpMatrix fJe
robot Jacobian expressed in the robot reference frame available
Definition: vpRobot.h:110
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:202
vpVelocityTwistMatrix & build(const vpTranslationVector &t, const vpRotationMatrix &R)
#define vpCDEBUG(level)
Definition: vpDebug.h:540
#define vpCERROR
Definition: vpDebug.h:379
#define vpDEBUG_TRACE
Definition: vpDebug.h:512
#define vpERROR_TRACE
Definition: vpDebug.h:409
VISP_EXPORT int wait(double t0, double t)