Visual Servoing Platform  version 3.6.1 under development (2024-07-27)
vpRobotPtu46.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 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 https://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 ptu-46 robot.
33  *
34 *****************************************************************************/
35 
36 #include <signal.h>
37 #include <string.h>
38 
39 #include <visp3/core/vpConfig.h>
40 #ifdef VISP_HAVE_PTU46
41 
42 /* Headers des fonctions implementees. */
43 #include <visp3/core/vpDebug.h>
44 #include <visp3/core/vpIoTools.h>
45 #include <visp3/robot/vpPtu46.h>
46 #include <visp3/robot/vpRobotException.h>
47 #include <visp3/robot/vpRobotPtu46.h>
48 
50 /* ---------------------------------------------------------------------- */
51 /* --- STATIC ------------------------------------------------------------ */
52 /* ------------------------------------------------------------------------ */
53 
54 bool vpRobotPtu46::robotAlreadyCreated = false;
56 
57 /* ----------------------------------------------------------------------- */
58 /* --- CONSTRUCTOR ------------------------------------------------------ */
59 /* ---------------------------------------------------------------------- */
60 
70 vpRobotPtu46::vpRobotPtu46(const std::string &device) : vpRobot()
71 {
72  this->device = device;
73 
74  vpDEBUG_TRACE(12, "Open communication with Ptu-46.");
75  try {
76  init();
77  }
78  catch (...) {
79  vpERROR_TRACE("Error caught");
80  throw;
81  }
82 
83  try {
85  }
86  catch (...) {
87  vpERROR_TRACE("Error caught");
88  throw;
89  }
90  positioningVelocity = defaultPositioningVelocity;
91  return;
92 }
93 
94 /* ------------------------------------------------------------------------ */
95 /* --- DESTRUCTOR -------------------------------------------------------- */
96 /* ------------------------------------------------------------------------ */
97 
105 {
106 
108 
109  if (0 != ptu.close()) {
110  vpERROR_TRACE("Error while closing communications with the robot ptu-46.");
111  }
112 
113  vpRobotPtu46::robotAlreadyCreated = false;
114 
115  return;
116 }
117 
118 /* --------------------------------------------------------------------------
119  */
120 /* --- INITIALISATION -------------------------------------------------------
121  */
122 /* --------------------------------------------------------------------------
123  */
124 
135 {
136  vpDEBUG_TRACE(12, "Open connection Ptu-46.");
137  if (0 != ptu.init(device.c_str())) {
138  vpERROR_TRACE("Cannot open connection with ptu-46.");
139  throw vpRobotException(vpRobotException::constructionError, "Cannot open connection with ptu-46");
140  }
141 
142  return;
143 }
144 
152 {
153  switch (newState) {
154  case vpRobot::STATE_STOP: {
156  ptu.stop();
157  }
158  break;
159  }
162  vpDEBUG_TRACE(12, "Passage vitesse -> position.");
163  ptu.stop();
164  }
165  else {
166  vpDEBUG_TRACE(1, "Passage arret -> position.");
167  }
168  break;
169  }
172  vpDEBUG_TRACE(10, "Arret du robot...");
173  ptu.stop();
174  }
175  break;
176  }
177  default:
178  break;
179  }
180 
181  return vpRobot::setRobotState(newState);
182 }
183 
190 {
191  ptu.stop();
193 }
194 
206 {
208  vpPtu46::get_cMe(cMe);
209 
210  cVe.build(cMe);
211 }
212 
223 
235 {
236  vpColVector q(2);
238 
239  try {
240  vpPtu46::get_eJe(q, eJe);
241  }
242  catch (...) {
243  vpERROR_TRACE("catch exception ");
244  throw;
245  }
246 }
247 
256 {
257  vpColVector q(2);
259 
260  try {
261  vpPtu46::get_fJe(q, fJe);
262  }
263  catch (...) {
264  vpERROR_TRACE("Error caught");
265  throw;
266  }
267 }
268 
275 void vpRobotPtu46::setPositioningVelocity(double velocity) { positioningVelocity = velocity; }
282 double vpRobotPtu46::getPositioningVelocity(void) { return positioningVelocity; }
283 
301 {
302 
304  vpERROR_TRACE("Robot was not in position-based control\n"
305  "Modification of the robot state");
307  }
308 
309  switch (frame) {
311  throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in camera frame: "
312  "not implemented");
313  break;
315  throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in reference frame: "
316  "not implemented");
317  break;
318  case vpRobot::MIXT_FRAME:
319  throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in mixt frame: "
320  "not implemented");
321  break;
323  throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in end-effector frame: "
324  "not implemented");
325  break;
327  break;
328  }
329 
330  // Interface for the controller
331  double artpos[2];
332 
333  artpos[0] = q[0];
334  artpos[1] = q[1];
335 
336  if (0 != ptu.move(artpos, positioningVelocity, PTU_ABSOLUTE_MODE)) {
337  vpERROR_TRACE("Positioning error.");
338  throw vpRobotException(vpRobotException::lowLevelError, "Positioning error.");
339  }
340 
341  return;
342 }
343 
360 void vpRobotPtu46::setPosition(const vpRobot::vpControlFrameType frame, const double &q1, const double &q2)
361 {
362  try {
363  vpColVector q(2);
364  q[0] = q1;
365  q[1] = q2;
366 
367  setPosition(frame, q);
368  }
369  catch (...) {
370  vpERROR_TRACE("Error caught");
371  throw;
372  }
373 }
374 
388 void vpRobotPtu46::setPosition(const char *filename)
389 {
390  vpColVector q;
391  if (readPositionFile(filename, q) == false) {
392  vpERROR_TRACE("Cannot get ptu-46 position from file");
393  throw vpRobotException(vpRobotException::readingParametersError, "Cannot get ptu-46 position from file");
394  }
396 }
397 
412 {
413  vpDEBUG_TRACE(9, "# Entree.");
414 
415  switch (frame) {
417  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in camera frame: "
418  "not implemented");
419  break;
421  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in reference frame: "
422  "not implemented");
423  break;
424  case vpRobot::MIXT_FRAME:
425  throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in mixt frame: "
426  "not implemented");
427  break;
429  throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in end-effector frame: "
430  "not implemented");
431  break;
433  break;
434  }
435 
436  double artpos[2];
437 
438  if (0 != ptu.getCurrentPosition(artpos)) {
439  vpERROR_TRACE("Error when calling recup_posit_Afma4.");
440  throw vpRobotException(vpRobotException::lowLevelError, "Error when calling recup_posit_Afma4.");
441  }
442 
444 
445  q[0] = artpos[0];
446  q[1] = artpos[1];
447 }
448 
480 {
481  TPtuFrame ptuFrameInterface;
482 
484  vpERROR_TRACE("Cannot send a velocity to the robot "
485  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
487  "Cannot send a velocity to the robot "
488  "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
489  }
490 
491  switch (frame) {
492  case vpRobot::CAMERA_FRAME: {
493  ptuFrameInterface = PTU_CAMERA_FRAME;
494  if (v.getRows() != 2) {
495  vpERROR_TRACE("Bad dimension fo speed vector in camera frame");
496  throw vpRobotException(vpRobotException::wrongStateError, "Bad dimension for speed vector "
497  "in camera frame");
498  }
499  break;
500  }
502  ptuFrameInterface = PTU_ARTICULAR_FRAME;
503  if (v.getRows() != 2) {
504  throw vpRobotException(vpRobotException::wrongStateError, "Bad dimension for speed vector "
505  "in articular frame");
506  }
507  break;
508  }
510  throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot "
511  "in the reference frame:"
512  "functionality not implemented");
513  }
514  case vpRobot::MIXT_FRAME: {
515  throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot "
516  "in the mixt frame:"
517  "functionality not implemented");
518  }
520  throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot "
521  "in the end-effector frame:"
522  "functionality not implemented");
523  }
524  default: {
525  throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot ");
526  }
527  }
528 
529  vpDEBUG_TRACE(12, "Velocity limitation.");
530  double ptuSpeedInterface[2];
531 
532  switch (frame) {
534  case vpRobot::CAMERA_FRAME: {
535  double max = this->maxRotationVelocity;
536  bool norm = false; // Flag to indicate when velocities need to be normalized
537  for (unsigned int i = 0; i < 2; ++i) // rx and ry of the camera
538  {
539  if (fabs(v[i]) > max) {
540  norm = true;
541  max = fabs(v[i]);
542  vpERROR_TRACE("Excess velocity: ROTATION "
543  "(axe nr.%d).",
544  i);
545  }
546  }
547  // Rotations velocities normalization
548  if (norm == true) {
549  max = this->maxRotationVelocity / max;
550  for (unsigned int i = 0; i < 2; ++i)
551  ptuSpeedInterface[i] = v[i] * max;
552  }
553  break;
554  }
555  default:
556  // Should never occur
557  break;
558  }
559 
560  vpCDEBUG(12) << "v: " << ptuSpeedInterface[0] << " " << ptuSpeedInterface[1] << std::endl;
561  ptu.move(ptuSpeedInterface, ptuFrameInterface);
562  return;
563 }
564 
565 /* -------------------------------------------------------------------------
566  */
567 /* --- GET -----------------------------------------------------------------
568  */
569 /* -------------------------------------------------------------------------
570  */
571 
584 {
585 
586  TPtuFrame ptuFrameInterface = PTU_ARTICULAR_FRAME;
587 
588  switch (frame) {
589  case vpRobot::CAMERA_FRAME: {
590  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a velocity in the camera frame:"
591  "functionality not implemented");
592  }
594  ptuFrameInterface = PTU_ARTICULAR_FRAME;
595  break;
596  }
598  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a velocity in the reference frame:"
599  "functionality not implemented");
600  }
601  case vpRobot::MIXT_FRAME: {
602  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a velocity in the mixt frame:"
603  "functionality not implemented");
604  }
606  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a velocity in the end-effector frame:"
607  "functionality not implemented");
608  }
609  }
610 
611  q_dot.resize(vpPtu46::ndof);
612  double ptuSpeedInterface[2];
613 
614  ptu.getCurrentSpeed(ptuSpeedInterface, ptuFrameInterface);
615 
616  q_dot[0] = ptuSpeedInterface[0];
617  q_dot[1] = ptuSpeedInterface[1];
618 }
619 
632 {
633  vpColVector q_dot;
634  getVelocity(frame, q_dot);
635 
636  return q_dot;
637 }
638 
658 bool vpRobotPtu46::readPositionFile(const std::string &filename, vpColVector &q)
659 {
660  std::ifstream fd(filename.c_str(), std::ios::in);
661 
662  if (!fd.is_open()) {
663  return false;
664  }
665 
666  std::string line;
667  std::string key("R:");
668  std::string id("#PTU-EVI - Position");
669  bool pos_found = false;
670  int lineNum = 0;
671 
673 
674  while (std::getline(fd, line)) {
675  lineNum++;
676  if (lineNum == 1) {
677  if (!(line.compare(0, id.size(), id) == 0)) { // check if Ptu-46 position file
678  std::cout << "Error: this position file " << filename << " is not for Ptu-46 robot" << std::endl;
679  return false;
680  }
681  }
682  if ((line.compare(0, 1, "#") == 0)) { // skip comment
683  continue;
684  }
685  if ((line.compare(0, key.size(), key) == 0)) { // decode position
686  // check if there are at least njoint values in the line
687  std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
688  if (chain.size() < vpPtu46::ndof + 1) // try to split with tab separator
689  chain = vpIoTools::splitChain(line, std::string("\t"));
690  if (chain.size() < vpPtu46::ndof + 1)
691  continue;
692 
693  std::istringstream ss(line);
694  std::string key_;
695  ss >> key_;
696  for (unsigned int i = 0; i < vpPtu46::ndof; i++)
697  ss >> q[i];
698  pos_found = true;
699  break;
700  }
701  }
702 
703  // converts rotations from degrees into radians
704  q.deg2rad();
705 
706  fd.close();
707 
708  if (!pos_found) {
709  std::cout << "Error: unable to find a position for Ptu-46 robot in " << filename << std::endl;
710  return false;
711  }
712 
713  return true;
714 }
715 
736 {
737  double d_[6];
738 
739  switch (frame) {
740  case vpRobot::CAMERA_FRAME: {
741  d.resize(6);
742  ptu.measureDpl(d_, PTU_CAMERA_FRAME);
743  d[0] = d_[0];
744  d[1] = d_[1];
745  d[2] = d_[2];
746  d[3] = d_[3];
747  d[4] = d_[4];
748  d[5] = d_[5];
749  break;
750  }
752  ptu.measureDpl(d_, PTU_ARTICULAR_FRAME);
753  d.resize(vpPtu46::ndof);
754  d[0] = d_[0]; // pan
755  d[1] = d_[1]; // tilt
756  break;
757  }
759  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a displacement in the reference frame:"
760  "functionality not implemented");
761  }
762  case vpRobot::MIXT_FRAME: {
763  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a displacement in the reference frame:"
764  "functionality not implemented");
765  }
767  throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a displacement in the end-effector frame:"
768  "functionality not implemented");
769  }
770  }
771 }
772 END_VISP_NAMESPACE
773 #elif !defined(VISP_BUILD_SHARED_LIBS)
774 // Work around to avoid warning: libvisp_robot.a(vpRobotPtu46.cpp.o) has no symbols
775 void dummy_vpRobotPtu46() { };
776 #endif
unsigned int getRows() const
Definition: vpArray2D.h:347
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
vpColVector & deg2rad()
Definition: vpColVector.h:380
void resize(unsigned int i, bool flagNullify=true)
Definition: vpColVector.h:1143
Implementation of an homogeneous matrix and operations on such kind of matrices.
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1661
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
static const unsigned int ndof
Definition: vpPtu46.h:76
void get_cMe(vpHomogeneousMatrix &_cMe) const
Definition: vpPtu46.cpp:208
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition: vpPtu46.cpp:276
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition: vpPtu46.cpp:247
Error that can be emitted by the vpRobot class and its derivatives.
@ wrongStateError
Wrong robot state.
@ constructionError
Error from constructor.
@ readingParametersError
Cannot parse parameters.
@ lowLevelError
Error thrown by the low level sdk.
void get_fJe(vpMatrix &_fJe) VP_OVERRIDE
void setPositioningVelocity(double velocity)
void get_eJe(vpMatrix &_eJe) VP_OVERRIDE
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &q_dot) VP_OVERRIDE
double getPositioningVelocity(void)
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &q_dot)
void get_cVe(vpVelocityTwistMatrix &_cVe) const
static const double defaultPositioningVelocity
Definition: vpRobotPtu46.h:94
virtual ~vpRobotPtu46(void)
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q) VP_OVERRIDE
void get_cMe(vpHomogeneousMatrix &_cMe) const
bool readPositionFile(const std::string &filename, vpColVector &q)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) VP_OVERRIDE
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &q)
void init(void)
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
@ ARTICULAR_FRAME
Definition: vpRobot.h:80
@ 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_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
double maxRotationVelocity
Definition: vpRobot.h:100
vpVelocityTwistMatrix & build(const vpTranslationVector &t, const vpRotationMatrix &R)
#define vpCDEBUG(level)
Definition: vpDebug.h:540
#define vpDEBUG_TRACE
Definition: vpDebug.h:512
#define vpERROR_TRACE
Definition: vpDebug.h:409