Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpRobotPtu46.cpp
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 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 ptu-46 robot.
32 */
33
34#include <signal.h>
35#include <string.h>
36
37#include <visp3/core/vpConfig.h>
38#ifdef VISP_HAVE_PTU46
39
40/* Headers des fonctions implementees. */
41#include <visp3/core/vpDebug.h>
42#include <visp3/core/vpIoTools.h>
43#include <visp3/robot/vpPtu46.h>
44#include <visp3/robot/vpRobotException.h>
45#include <visp3/robot/vpRobotPtu46.h>
46
48/* ---------------------------------------------------------------------- */
49/* --- STATIC ------------------------------------------------------------ */
50/* ------------------------------------------------------------------------ */
51
52bool vpRobotPtu46::robotAlreadyCreated = false;
54
55/* ----------------------------------------------------------------------- */
56/* --- CONSTRUCTOR ------------------------------------------------------ */
57/* ---------------------------------------------------------------------- */
58
68vpRobotPtu46::vpRobotPtu46(const std::string &device) : vpRobot()
69{
70 this->device = device;
71
72 vpDEBUG_TRACE(12, "Open communication with Ptu-46.");
73 try {
74 init();
75 }
76 catch (...) {
77 vpERROR_TRACE("Error caught");
78 throw;
79 }
80
81 try {
83 }
84 catch (...) {
85 vpERROR_TRACE("Error caught");
86 throw;
87 }
88 positioningVelocity = defaultPositioningVelocity;
89 return;
90}
91
92/* ------------------------------------------------------------------------ */
93/* --- DESTRUCTOR -------------------------------------------------------- */
94/* ------------------------------------------------------------------------ */
95
103{
104
106
107 if (0 != ptu.close()) {
108 vpERROR_TRACE("Error while closing communications with the robot ptu-46.");
109 }
110
111 vpRobotPtu46::robotAlreadyCreated = false;
112
113 return;
114}
115
116/* --------------------------------------------------------------------------
117 */
118/* --- INITIALISATION -------------------------------------------------------
119 */
120/* --------------------------------------------------------------------------
121 */
122
133{
134 vpDEBUG_TRACE(12, "Open connection Ptu-46.");
135 if (0 != ptu.init(device.c_str())) {
136 vpERROR_TRACE("Cannot open connection with ptu-46.");
137 throw vpRobotException(vpRobotException::constructionError, "Cannot open connection with ptu-46");
138 }
139
140 return;
141}
142
150{
151 switch (newState) {
152 case vpRobot::STATE_STOP: {
154 ptu.stop();
155 }
156 break;
157 }
160 vpDEBUG_TRACE(12, "Passage vitesse -> position.");
161 ptu.stop();
162 }
163 else {
164 vpDEBUG_TRACE(1, "Passage arret -> position.");
165 }
166 break;
167 }
170 vpDEBUG_TRACE(10, "Arret du robot...");
171 ptu.stop();
172 }
173 break;
174 }
175 default:
176 break;
177 }
178
179 return vpRobot::setRobotState(newState);
180}
181
188{
189 ptu.stop();
191}
192
204{
206 vpPtu46::get_cMe(cMe);
207
208 cVe.buildFrom(cMe);
209}
210
221
233{
234 vpColVector q(2);
236
237 try {
239 }
240 catch (...) {
241 vpERROR_TRACE("catch exception ");
242 throw;
243 }
244}
245
254{
255 vpColVector q(2);
257
258 try {
260 }
261 catch (...) {
262 vpERROR_TRACE("Error caught");
263 throw;
264 }
265}
266
273void vpRobotPtu46::setPositioningVelocity(double velocity) { positioningVelocity = velocity; }
280double vpRobotPtu46::getPositioningVelocity(void) { return positioningVelocity; }
281
297
299{
300
302 vpERROR_TRACE("Robot was not in position-based control\n"
303 "Modification of the robot state");
305 }
306
307 switch (frame) {
309 throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in camera frame: "
310 "not implemented");
311 break;
313 throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in reference frame: "
314 "not implemented");
315 break;
317 throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in mixt frame: "
318 "not implemented");
319 break;
321 throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in end-effector frame: "
322 "not implemented");
323 break;
325 break;
326 }
327
328 // Interface for the controller
329 double artpos[2];
330
331 artpos[0] = q[0];
332 artpos[1] = q[1];
333
334 if (0 != ptu.move(artpos, positioningVelocity, PTU_ABSOLUTE_MODE)) {
335 vpERROR_TRACE("Positioning error.");
336 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error.");
337 }
338
339 return;
340}
341
358void vpRobotPtu46::setPosition(const vpRobot::vpControlFrameType frame, const double &q1, const double &q2)
359{
360 try {
361 vpColVector q(2);
362 q[0] = q1;
363 q[1] = q2;
364
365 setPosition(frame, q);
366 }
367 catch (...) {
368 vpERROR_TRACE("Error caught");
369 throw;
370 }
371}
372
386void vpRobotPtu46::setPosition(const char *filename)
387{
388 vpColVector q;
389 if (readPositionFile(filename, q) == false) {
390 vpERROR_TRACE("Cannot get ptu-46 position from file");
391 throw vpRobotException(vpRobotException::readingParametersError, "Cannot get ptu-46 position from file");
392 }
394}
395
410{
411 vpDEBUG_TRACE(9, "# Entree.");
412
413 switch (frame) {
415 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in camera frame: "
416 "not implemented");
417 break;
419 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in reference frame: "
420 "not implemented");
421 break;
423 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in mixt frame: "
424 "not implemented");
425 break;
427 throw vpRobotException(vpRobotException::wrongStateError, "Cannot move the robot in end-effector frame: "
428 "not implemented");
429 break;
431 break;
432 }
433
434 double artpos[2];
435
436 if (0 != ptu.getCurrentPosition(artpos)) {
437 vpERROR_TRACE("Error when calling vpRobotPtu46::getPosition()");
438 throw vpRobotException(vpRobotException::lowLevelError, "Error when calling vpRobotPtu46::getPosition().");
439 }
440
442
443 q[0] = artpos[0];
444 q[1] = artpos[1];
445}
446
476
478{
479 TPtuFrame ptuFrameInterface;
480
482 vpERROR_TRACE("Cannot send a velocity to the robot "
483 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
485 "Cannot send a velocity to the robot "
486 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
487 }
488
489 switch (frame) {
491 ptuFrameInterface = PTU_CAMERA_FRAME;
492 if (v.getRows() != 2) {
493 vpERROR_TRACE("Bad dimension fo speed vector in camera frame");
494 throw vpRobotException(vpRobotException::wrongStateError, "Bad dimension for speed vector "
495 "in camera frame");
496 }
497 break;
498 }
500 ptuFrameInterface = PTU_ARTICULAR_FRAME;
501 if (v.getRows() != 2) {
502 throw vpRobotException(vpRobotException::wrongStateError, "Bad dimension for speed vector "
503 "in articular frame");
504 }
505 break;
506 }
508 throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot "
509 "in the reference frame:"
510 "functionality not implemented");
511 }
512 case vpRobot::MIXT_FRAME: {
513 throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot "
514 "in the mixt frame:"
515 "functionality not implemented");
516 }
518 throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot "
519 "in the end-effector frame:"
520 "functionality not implemented");
521 }
522 default: {
523 throw vpRobotException(vpRobotException::wrongStateError, "Cannot send a velocity to the robot ");
524 }
525 }
526
527 vpDEBUG_TRACE(12, "Velocity limitation.");
528 double ptuSpeedInterface[2];
529
530 switch (frame) {
533 double max = this->maxRotationVelocity;
534 bool norm = false; // Flag to indicate when velocities need to be normalized
535 for (unsigned int i = 0; i < 2; ++i) // rx and ry of the camera
536 {
537 if (fabs(v[i]) > max) {
538 norm = true;
539 max = fabs(v[i]);
540 vpERROR_TRACE("Excess velocity: ROTATION "
541 "(axe nr.%d).",
542 i);
543 }
544 }
545 // Rotations velocities normalization
546 if (norm == true) {
547 max = this->maxRotationVelocity / max;
548 for (unsigned int i = 0; i < 2; ++i)
549 ptuSpeedInterface[i] = v[i] * max;
550 }
551 break;
552 }
553 default:
554 // Should never occur
555 break;
556 }
557
558 vpCDEBUG(12) << "v: " << ptuSpeedInterface[0] << " " << ptuSpeedInterface[1] << std::endl;
559 ptu.move(ptuSpeedInterface, ptuFrameInterface);
560 return;
561}
562
563/* -------------------------------------------------------------------------
564 */
565/* --- GET -----------------------------------------------------------------
566 */
567/* -------------------------------------------------------------------------
568 */
569
582{
583
584 TPtuFrame ptuFrameInterface = PTU_ARTICULAR_FRAME;
585
586 switch (frame) {
588 throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a velocity in the camera frame:"
589 "functionality not implemented");
590 }
592 ptuFrameInterface = PTU_ARTICULAR_FRAME;
593 break;
594 }
596 throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a velocity in the reference frame:"
597 "functionality not implemented");
598 }
599 case vpRobot::MIXT_FRAME: {
600 throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a velocity in the mixt frame:"
601 "functionality not implemented");
602 }
604 throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a velocity in the end-effector frame:"
605 "functionality not implemented");
606 }
607 }
608
609 q_dot.resize(vpPtu46::ndof);
610 double ptuSpeedInterface[2];
611
612 ptu.getCurrentSpeed(ptuSpeedInterface, ptuFrameInterface);
613
614 q_dot[0] = ptuSpeedInterface[0];
615 q_dot[1] = ptuSpeedInterface[1];
616}
617
630{
631 vpColVector q_dot;
632 getVelocity(frame, q_dot);
633
634 return q_dot;
635}
636
656bool vpRobotPtu46::readPositionFile(const std::string &filename, vpColVector &q)
657{
658 std::ifstream fd(filename.c_str(), std::ios::in);
659
660 if (!fd.is_open()) {
661 return false;
662 }
663
664 std::string line;
665 std::string key("R:");
666 std::string id("#PTU-EVI - Position");
667 bool pos_found = false;
668 int lineNum = 0;
669
671
672 while (std::getline(fd, line)) {
673 lineNum++;
674 if (lineNum == 1) {
675 if (!(line.compare(0, id.size(), id) == 0)) { // check if Ptu-46 position file
676 std::cout << "Error: this position file " << filename << " is not for Ptu-46 robot" << std::endl;
677 return false;
678 }
679 }
680 if ((line.compare(0, 1, "#") == 0)) { // skip comment
681 continue;
682 }
683 if ((line.compare(0, key.size(), key) == 0)) { // decode position
684 // check if there are at least njoint values in the line
685 std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
686 if (chain.size() < vpPtu46::ndof + 1) // try to split with tab separator
687 chain = vpIoTools::splitChain(line, std::string("\t"));
688 if (chain.size() < vpPtu46::ndof + 1)
689 continue;
690
691 std::istringstream ss(line);
692 std::string key_;
693 ss >> key_;
694 for (unsigned int i = 0; i < vpPtu46::ndof; i++)
695 ss >> q[i];
696 pos_found = true;
697 break;
698 }
699 }
700
701 // converts rotations from degrees into radians
702 q.deg2rad();
703
704 fd.close();
705
706 if (!pos_found) {
707 std::cout << "Error: unable to find a position for Ptu-46 robot in " << filename << std::endl;
708 return false;
709 }
710
711 return true;
712}
713
734{
735 double d_[6];
736
737 switch (frame) {
739 d.resize(6);
740 ptu.measureDpl(d_, PTU_CAMERA_FRAME);
741 d[0] = d_[0];
742 d[1] = d_[1];
743 d[2] = d_[2];
744 d[3] = d_[3];
745 d[4] = d_[4];
746 d[5] = d_[5];
747 break;
748 }
750 ptu.measureDpl(d_, PTU_ARTICULAR_FRAME);
751 d.resize(vpPtu46::ndof);
752 d[0] = d_[0]; // pan
753 d[1] = d_[1]; // tilt
754 break;
755 }
757 throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a displacement in the reference frame:"
758 "functionality not implemented");
759 }
760 case vpRobot::MIXT_FRAME: {
761 throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a displacement in the reference frame:"
762 "functionality not implemented");
763 }
765 throw vpRobotException(vpRobotException::wrongStateError, "Cannot get a displacement in the end-effector frame:"
766 "functionality not implemented");
767 }
768 }
769}
770END_VISP_NAMESPACE
771#elif !defined(VISP_BUILD_SHARED_LIBS)
772// Work around to avoid warning: libvisp_robot.a(vpRobotPtu46.cpp.o) has no symbols
773void dummy_vpRobotPtu46() { }
774#endif
Implementation of column vector and the associated operations.
vpColVector & deg2rad()
void resize(unsigned int i, bool flagNullify=true)
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)
Implementation of a matrix and operations on matrices.
Definition vpMatrix.h:175
static const unsigned int ndof
Definition vpPtu46.h:74
void get_cMe(vpHomogeneousMatrix &_cMe) const
Definition vpPtu46.cpp:206
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition vpPtu46.cpp:274
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition vpPtu46.cpp:245
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
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)
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
Definition vpRobot.h:103
virtual vpRobotStateType getRobotState(void) const
Definition vpRobot.h:152
vpControlFrameType
Definition vpRobot.h:74
@ REFERENCE_FRAME
Definition vpRobot.h:75
@ ARTICULAR_FRAME
Definition vpRobot.h:77
@ MIXT_FRAME
Definition vpRobot.h:85
@ CAMERA_FRAME
Definition vpRobot.h:81
@ END_EFFECTOR_FRAME
Definition vpRobot.h:80
vpRobotStateType
Definition vpRobot.h:62
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition vpRobot.h:65
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition vpRobot.h:64
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition vpRobot.h:63
vpMatrix fJe
robot Jacobian expressed in the robot reference frame available
Definition vpRobot.h:107
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition vpRobot.cpp:200
vpRobot(void)
Definition vpRobot.cpp:49
double maxRotationVelocity
Definition vpRobot.h:97
vpVelocityTwistMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
#define vpCDEBUG(level)
Definition vpDebug.h:554
#define vpDEBUG_TRACE
Definition vpDebug.h:526
#define vpERROR_TRACE
Definition vpDebug.h:423