Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpRobotAfma6.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 Irisa's Afma6 robot.
32 */
33
34#include <visp3/core/vpConfig.h>
35
36#ifdef VISP_HAVE_AFMA6
37
38#include <signal.h>
39#include <stdlib.h>
40#include <sys/types.h>
41#include <unistd.h>
42
43#include <visp3/core/vpDebug.h>
44#include <visp3/core/vpExponentialMap.h>
45#include <visp3/core/vpIoTools.h>
46#include <visp3/core/vpRotationMatrix.h>
47#include <visp3/core/vpThetaUVector.h>
48#include <visp3/core/vpVelocityTwistMatrix.h>
49#include <visp3/robot/vpRobotAfma6.h>
50#include <visp3/robot/vpRobotException.h>
51
53/* ---------------------------------------------------------------------- */
54/* --- STATIC ----------------------------------------------------------- */
55/* ---------------------------------------------------------------------- */
56
57bool vpRobotAfma6::robotAlreadyCreated = false;
58
67
68/* ---------------------------------------------------------------------- */
69/* --- EMERGENCY STOP --------------------------------------------------- */
70/* ---------------------------------------------------------------------- */
71
79void emergencyStopAfma6(int signo)
80{
81 std::cout << "Stop the Afma6 application by signal (" << signo << "): " << static_cast<char>(7);
82 switch (signo) {
83 case SIGINT:
84 std::cout << "SIGINT (stop by ^C) " << std::endl;
85 break;
86 case SIGBUS:
87 std::cout << "SIGBUS (stop due to a bus error) " << std::endl;
88 break;
89 case SIGSEGV:
90 std::cout << "SIGSEGV (stop due to a segmentation fault) " << std::endl;
91 break;
92 case SIGKILL:
93 std::cout << "SIGKILL (stop by CTRL \\) " << std::endl;
94 break;
95 case SIGQUIT:
96 std::cout << "SIGQUIT " << std::endl;
97 break;
98 default:
99 std::cout << signo << std::endl;
100 }
101 // std::cout << "Emergency stop called\n";
102 // PrimitiveESTOP_Afma6();
103 PrimitiveSTOP_Afma6();
104 std::cout << "Robot was stopped\n";
105
106 // Free allocated resources
107 // ShutDownConnection(); // Some times cannot exit here when Ctrl-C
108
109 fprintf(stdout, "Application ");
110 fflush(stdout);
111 kill(getpid(), SIGKILL);
112 exit(1);
113}
114
115/* ---------------------------------------------------------------------- */
116/* --- CONSTRUCTOR ------------------------------------------------------ */
117/* ---------------------------------------------------------------------- */
118
155vpRobotAfma6::vpRobotAfma6(bool verbose) : vpAfma6(), vpRobot()
156{
157
158 /*
159 #define SIGHUP 1 // hangup
160 #define SIGINT 2 // interrupt (rubout)
161 #define SIGQUIT 3 // quit (ASCII FS)
162 #define SIGILL 4 // illegal instruction (not reset when caught)
163 #define SIGTRAP 5 // trace trap (not reset when caught)
164 #define SIGIOT 6 // IOT instruction
165 #define SIGABRT 6 // used by abort, replace SIGIOT in the future
166 #define SIGEMT 7 // EMT instruction
167 #define SIGFPE 8 // floating point exception
168 #define SIGKILL 9 // kill (cannot be caught or ignored)
169 #define SIGBUS 10 // bus error
170 #define SIGSEGV 11 // segmentation violation
171 #define SIGSYS 12 // bad argument to system call
172 #define SIGPIPE 13 // write on a pipe with no one to read it
173 #define SIGALRM 14 // alarm clock
174 #define SIGTERM 15 // software termination signal from kill
175 */
176
177 signal(SIGINT, emergencyStopAfma6);
178 signal(SIGBUS, emergencyStopAfma6);
179 signal(SIGSEGV, emergencyStopAfma6);
180 signal(SIGKILL, emergencyStopAfma6);
181 signal(SIGQUIT, emergencyStopAfma6);
182
183 setVerbose(verbose);
184 if (verbose_)
185 std::cout << "Open communication with MotionBlox.\n";
186 try {
187 this->init();
189 }
190 catch (...) {
191 // vpERROR_TRACE("Error caught") ;
192 throw;
193 }
194 positioningVelocity = defaultPositioningVelocity;
195
196 vpRobotAfma6::robotAlreadyCreated = true;
197
198 return;
199}
200
201/* ------------------------------------------------------------------------ */
202/* --- INITIALISATION ----------------------------------------------------- */
203/* ------------------------------------------------------------------------ */
204
225{
226 InitTry;
227
228 // Initialise private variables used to compute the measured velocities
229 q_prev_getvel.resize(6);
230 q_prev_getvel = 0;
231 time_prev_getvel = 0;
232 first_time_getvel = true;
233
234 // Initialise private variables used to compute the measured displacement
235 q_prev_getdis.resize(6);
236 q_prev_getdis = 0;
237 first_time_getdis = true;
238
239 // Initialize the firewire connection
240 Try(InitializeConnection(verbose_));
241
242 // Connect to the servoboard using the servo board GUID
243 Try(InitializeNode_Afma6());
244
245 Try(PrimitiveRESET_Afma6());
246
247 // Update the eMc matrix in the low level controller
249
250 // Look if the power is on or off
251 UInt32 HIPowerStatus;
252 UInt32 EStopStatus;
253 Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus));
254 CAL_Wait(0.1);
255
256 // Print the robot status
257 if (verbose_) {
258 std::cout << "Robot status: ";
259 switch (EStopStatus) {
260 case ESTOP_AUTO:
261 case ESTOP_MANUAL:
262 if (HIPowerStatus == 0)
263 std::cout << "Power is OFF" << std::endl;
264 else
265 std::cout << "Power is ON" << std::endl;
266 break;
267 case ESTOP_ACTIVATED:
268 std::cout << "Emergency stop is activated" << std::endl;
269 break;
270 default:
271 std::cout << "Sorry there is an error on the emergency chain." << std::endl;
272 std::cout << "You have to call Adept for maintenance..." << std::endl;
273 // Free allocated resources
274 }
275 std::cout << std::endl;
276 }
277 // get real joint min/max from the MotionBlox
278 Try(PrimitiveJOINT_MINMAX_Afma6(_joint_min, _joint_max));
279 // for (unsigned int i=0; i < njoint; i++) {
280 // printf("axis %d: joint min %lf, max %lf\n", i, _joint_min[i],
281 // _joint_max[i]);
282 // }
283
284 // If an error occur in the low level controller, goto here
285 // CatchPrint();
286 Catch();
287
288 // Test if an error occurs
289 if (TryStt == -20001)
290 printf("No connection detected. Check if the robot is powered on \n"
291 "and if the firewire link exist between the MotionBlox and this "
292 "computer.\n");
293 else if (TryStt == -675)
294 printf(" Timeout enabling power...\n");
295
296 if (TryStt < 0) {
297 // Power off the robot
298 PrimitivePOWEROFF_Afma6();
299 // Free allocated resources
300 ShutDownConnection();
301
302 std::cout << "Cannot open connection with the motionblox..." << std::endl;
303 throw vpRobotException(vpRobotException::constructionError, "Cannot open connection with the motionblox");
304 }
305 return;
306}
307
345{
346 InitTry;
347 // Read the robot constants from files
348 // - joint [min,max], coupl_56, long_56
349 // - camera extrinsic parameters relative to eMc
351
352 // Set the robot constant (coupl_56, long_56) in the MotionBlox
353 Try(PrimitiveROBOT_CONST_Afma6(_coupl_56, _long_56));
354
355 // Set the camera constant (eMc pose) in the MotionBlox
356 double eMc_pose[6];
357 for (unsigned int i = 0; i < 3; i++) {
358 eMc_pose[i] = _etc[i]; // translation in meters
359 eMc_pose[i + 3] = _erc[i]; // rotation in rad
360 }
361 // Update the eMc pose in the low level controller
362 Try(PrimitiveCAMERA_CONST_Afma6(eMc_pose));
363
364 // get real joint min/max from the MotionBlox
365 Try(PrimitiveJOINT_MINMAX_Afma6(_joint_min, _joint_max));
366 // for (unsigned int i=0; i < njoint; i++) {
367 // printf("axis %d: joint min %lf, max %lf\n", i, _joint_min[i],
368 // _joint_max[i]);
369 // }
370
371 setToolType(tool);
372
373 CatchPrint();
374 return;
375}
376
389{
390 InitTry;
391 // Set camera extrinsic parameters equal to eMc
392 this->vpAfma6::set_eMc(eMc);
393
394 // Set the camera constant (eMc pose) in the MotionBlox
395 double eMc_pose[6];
396 for (unsigned int i = 0; i < 3; i++) {
397 eMc_pose[i] = _etc[i]; // translation in meters
398 eMc_pose[i + 3] = _erc[i]; // rotation in rad
399 }
400 // Update the eMc pose in the low level controller
401 Try(PrimitiveCAMERA_CONST_Afma6(eMc_pose));
402
403 CatchPrint();
404}
405
446{
447 InitTry;
448 // Read the robot constants from files
449 // - joint [min,max], coupl_56, long_56
450 // ans set camera extrinsic parameters equal to eMc
451 vpAfma6::init(tool, eMc);
452
453 // Set the robot constant (coupl_56, long_56) in the MotionBlox
454 Try(PrimitiveROBOT_CONST_Afma6(_coupl_56, _long_56));
455
456 // Set the camera constant (eMc pose) in the MotionBlox
457 double eMc_pose[6];
458 for (unsigned int i = 0; i < 3; i++) {
459 eMc_pose[i] = _etc[i]; // translation in meters
460 eMc_pose[i + 3] = _erc[i]; // rotation in rad
461 }
462 // Update the eMc pose in the low level controller
463 Try(PrimitiveCAMERA_CONST_Afma6(eMc_pose));
464
465 // get real joint min/max from the MotionBlox
466 Try(PrimitiveJOINT_MINMAX_Afma6(_joint_min, _joint_max));
467
468 setToolType(tool);
469
470 CatchPrint();
471}
472
527void vpRobotAfma6::init(vpAfma6::vpAfma6ToolType tool, const std::string &filename)
528{
529 InitTry;
530 // Read the robot constants from files
531 // - joint [min,max], coupl_56, long_56
532 // ans set camera extrinsic parameters from file name
533 vpAfma6::init(tool, filename);
534
535 // Set the robot constant (coupl_56, long_56) in the MotionBlox
536 Try(PrimitiveROBOT_CONST_Afma6(_coupl_56, _long_56));
537
538 // Set the camera constant (eMc pose) in the MotionBlox
539 double eMc_pose[6];
540 for (unsigned int i = 0; i < 3; i++) {
541 eMc_pose[i] = _etc[i]; // translation in meters
542 eMc_pose[i + 3] = _erc[i]; // rotation in rad
543 }
544 // Update the eMc pose in the low level controller
545 Try(PrimitiveCAMERA_CONST_Afma6(eMc_pose));
546
547 // get real joint min/max from the MotionBlox
548 Try(PrimitiveJOINT_MINMAX_Afma6(_joint_min, _joint_max));
549
550 setToolType(tool);
551
552 CatchPrint();
553}
554
555/* ------------------------------------------------------------------------ */
556/* --- DESTRUCTOR --------------------------------------------------------- */
557/* ------------------------------------------------------------------------ */
558
566{
567 InitTry;
568
570
571 // Look if the power is on or off
572 UInt32 HIPowerStatus;
573 Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus));
574 CAL_Wait(0.1);
575
576 // if (HIPowerStatus == 1) {
577 // fprintf(stdout, "Power OFF the robot\n");
578 // fflush(stdout);
579
580 // Try( PrimitivePOWEROFF_Afma6() );
581 // }
582
583 // Free allocated resources
584 ShutDownConnection();
585
586 vpRobotAfma6::robotAlreadyCreated = false;
587
588 CatchPrint();
589 return;
590}
591
599{
600 InitTry;
601
602 switch (newState) {
603 case vpRobot::STATE_STOP: {
605 Try(PrimitiveSTOP_Afma6());
606 }
607 break;
608 }
611 std::cout << "Change the control mode from velocity to position control.\n";
612 Try(PrimitiveSTOP_Afma6());
613 }
614 else {
615 // std::cout << "Change the control mode from stop to position
616 // control.\n";
617 }
618 this->powerOn();
619 break;
620 }
623 std::cout << "Change the control mode from stop to velocity control.\n";
624 }
625 this->powerOn();
626 break;
627 }
628 default:
629 break;
630 }
631
632 CatchPrint();
633
634 return vpRobot::setRobotState(newState);
635}
636
637/* ------------------------------------------------------------------------ */
638/* --- STOP --------------------------------------------------------------- */
639/* ------------------------------------------------------------------------ */
640
649{
650 InitTry;
651 Try(PrimitiveSTOP_Afma6());
653
654 CatchPrint();
655 if (TryStt < 0) {
656 vpERROR_TRACE("Cannot stop robot motion");
657 throw vpRobotException(vpRobotException::lowLevelError, "Cannot stop robot motion.");
658 }
659}
660
671{
672 InitTry;
673
674 // Look if the power is on or off
675 UInt32 HIPowerStatus;
676 UInt32 EStopStatus;
677 bool firsttime = true;
678 unsigned int nitermax = 10;
679
680 for (unsigned int i = 0; i < nitermax; i++) {
681 Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus));
682 if (EStopStatus == ESTOP_AUTO) {
683 break; // exit for loop
684 }
685 else if (EStopStatus == ESTOP_MANUAL) {
686 break; // exit for loop
687 }
688 else if (EStopStatus == ESTOP_ACTIVATED) {
689 if (firsttime) {
690 std::cout << "Emergency stop is activated! \n"
691 << "Check the emergency stop button and push the yellow "
692 "button before continuing."
693 << std::endl;
694 firsttime = false;
695 }
696 fprintf(stdout, "Remaining time %us \r", nitermax - i);
697 fflush(stdout);
698 CAL_Wait(1);
699 }
700 else {
701 std::cout << "Sorry there is an error on the emergency chain." << std::endl;
702 std::cout << "You have to call Adept for maintenance..." << std::endl;
703 // Free allocated resources
704 ShutDownConnection();
705 throw(vpRobotException(vpRobotException::lowLevelError, "Error on the emergency chain"));
706 }
707 }
708
709 if (EStopStatus == ESTOP_ACTIVATED)
710 std::cout << std::endl;
711
712 if (EStopStatus == ESTOP_ACTIVATED) {
713 std::cout << "Sorry, cannot power on the robot." << std::endl;
714 throw(vpRobotException(vpRobotException::lowLevelError, "Cannot power on the robot."));
715 }
716
717 if (HIPowerStatus == 0) {
718 fprintf(stdout, "Power ON the Afma6 robot\n");
719 fflush(stdout);
720
721 Try(PrimitivePOWERON_Afma6());
722 }
723
724 CatchPrint();
725 if (TryStt < 0) {
726 vpERROR_TRACE("Cannot power on the robot");
727 throw(vpRobotException(vpRobotException::lowLevelError, "Cannot power off the robot."));
728 }
729}
730
741{
742 InitTry;
743
744 // Look if the power is on or off
745 UInt32 HIPowerStatus;
746 Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus));
747 CAL_Wait(0.1);
748
749 if (HIPowerStatus == 1) {
750 fprintf(stdout, "Power OFF the Afma6 robot\n");
751 fflush(stdout);
752
753 Try(PrimitivePOWEROFF_Afma6());
754 }
755
756 CatchPrint();
757 if (TryStt < 0) {
758 vpERROR_TRACE("Cannot power off the robot");
759 throw vpRobotException(vpRobotException::lowLevelError, "Cannot power off the robot.");
760 }
761}
762
775{
776 InitTry;
777 bool status = false;
778 // Look if the power is on or off
779 UInt32 HIPowerStatus;
780 Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus));
781 CAL_Wait(0.1);
782
783 if (HIPowerStatus == 1) {
784 status = true;
785 }
786
787 CatchPrint();
788 if (TryStt < 0) {
789 vpERROR_TRACE("Cannot get the power status");
790 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get the power status.");
791 }
792 return status;
793}
794
805{
807 vpAfma6::get_cMe(cMe);
808
809 cVe.buildFrom(cMe);
810}
811
823
835{
836
837 double position[6];
838 double timestamp;
839
840 InitTry;
841 Try(PrimitiveACQ_POS_Afma6(position, &timestamp));
842 CatchPrint();
843
844 vpColVector q(6);
845 for (unsigned int i = 0; i < njoint; i++)
846 q[i] = position[i];
847
848 try {
850 }
851 catch (...) {
852 vpERROR_TRACE("catch exception ");
853 throw;
854 }
855}
856
878
880{
881
882 double position[6];
883 double timestamp;
884
885 InitTry;
886 Try(PrimitiveACQ_POS_Afma6(position, &timestamp));
887 CatchPrint();
888
889 vpColVector q(6);
890 for (unsigned int i = 0; i < njoint; i++)
891 q[i] = position[i];
892
893 try {
895 }
896 catch (...) {
897 vpERROR_TRACE("Error caught");
898 throw;
899 }
900}
901
930void vpRobotAfma6::setPositioningVelocity(double velocity) { positioningVelocity = velocity; }
931
937double vpRobotAfma6::getPositioningVelocity(void) { return positioningVelocity; }
938
1017
1018{
1019 vpColVector position(6);
1020 vpRxyzVector rxyz;
1022
1023 R.buildFrom(pose[3], pose[4], pose[5]); // thetau
1024 rxyz.buildFrom(R);
1025
1026 for (unsigned int i = 0; i < 3; i++) {
1027 position[i] = pose[i];
1028 position[i + 3] = rxyz[i];
1029 }
1030 if (frame == vpRobot::ARTICULAR_FRAME) {
1031 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1032 "Joint frame not implemented for pose positioning.");
1033 }
1034 setPosition(frame, position);
1035}
1036
1121
1123{
1124
1126 vpERROR_TRACE("Robot was not in position-based control\n"
1127 "Modification of the robot state");
1129 }
1130
1131 double _destination[6];
1132 int error = 0;
1133 double timestamp;
1134
1135 InitTry;
1136 switch (frame) {
1137 case vpRobot::CAMERA_FRAME: {
1138 double _q[njoint];
1139 Try(PrimitiveACQ_POS_Afma6(_q, &timestamp));
1140
1142 for (unsigned int i = 0; i < njoint; i++)
1143 q[i] = _q[i];
1144
1145 // Get fMc from the inverse kinematics
1147 vpAfma6::get_fMc(q, fMc);
1148
1149 // Set cMc from the input position
1151 vpRxyzVector rxyz;
1152 for (unsigned int i = 0; i < 3; i++) {
1153 txyz[i] = position[i];
1154 rxyz[i] = position[i + 3];
1155 }
1156
1157 // Compute cMc2
1158 vpRotationMatrix cRc2(rxyz);
1159 vpHomogeneousMatrix cMc2(txyz, cRc2);
1160
1161 // Compute the new position to reach: fMc*cMc2
1162 vpHomogeneousMatrix fMc2 = fMc * cMc2;
1163
1164 // Compute the corresponding joint position from the inverse kinematics
1165 bool nearest = true;
1166 int solution = this->getInverseKinematics(fMc2, q, nearest);
1167 if (solution) { // Position is reachable
1168 for (unsigned int i = 0; i < njoint; i++) {
1169 _destination[i] = q[i];
1170 }
1171 Try(PrimitiveMOVE_Afma6(_destination, positioningVelocity));
1172 Try(WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000));
1173 }
1174 else {
1175 // Cartesian position is out of range
1176 error = -1;
1177 }
1178
1179 break;
1180 }
1182 for (unsigned int i = 0; i < njoint; i++) {
1183 _destination[i] = position[i];
1184 }
1185 Try(PrimitiveMOVE_Afma6(_destination, positioningVelocity));
1186 Try(WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000));
1187 break;
1188 }
1190 // Set fMc from the input position
1192 vpRxyzVector rxyz;
1193 for (unsigned int i = 0; i < 3; i++) {
1194 txyz[i] = position[i];
1195 rxyz[i] = position[i + 3];
1196 }
1197 // Compute fMc from the input position
1198 vpRotationMatrix fRc(rxyz);
1199 vpHomogeneousMatrix fMc(txyz, fRc);
1200
1201 // Compute the corresponding joint position from the inverse kinematics
1202 vpColVector q(6);
1203 bool nearest = true;
1204 int solution = this->getInverseKinematics(fMc, q, nearest);
1205 if (solution) { // Position is reachable
1206 for (unsigned int i = 0; i < njoint; i++) {
1207 _destination[i] = q[i];
1208 }
1209 Try(PrimitiveMOVE_Afma6(_destination, positioningVelocity));
1210 Try(WaitState_Afma6(ETAT_ATTENTE_AFMA6, 1000));
1211 }
1212 else {
1213 // Cartesian position is out of range
1214 error = -1;
1215 }
1216
1217 break;
1218 }
1219 case vpRobot::MIXT_FRAME: {
1220 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1221 "Mixt frame not implemented.");
1222 }
1224 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1225 "end-effector frame not implemented.");
1226 }
1227 }
1228
1229 CatchPrint();
1230 if (TryStt == InvalidPosition || TryStt == -1023)
1231 std::cout << " : Position out of range.\n";
1232 else if (TryStt < 0)
1233 std::cout << " : Unknown error (see Fabien).\n";
1234 else if (error == -1)
1235 std::cout << "Position out of range.\n";
1236
1237 if (TryStt < 0 || error < 0) {
1238 vpERROR_TRACE("Positioning error.");
1239 throw vpRobotException(vpRobotException::positionOutOfRangeError, "Position out of range.");
1240 }
1241
1242 return;
1243}
1244
1314void vpRobotAfma6::setPosition(const vpRobot::vpControlFrameType frame, double pos1, double pos2, double pos3,
1315 double pos4, double pos5, double pos6)
1316{
1317 try {
1318 vpColVector position(6);
1319 position[0] = pos1;
1320 position[1] = pos2;
1321 position[2] = pos3;
1322 position[3] = pos4;
1323 position[4] = pos5;
1324 position[5] = pos6;
1325
1326 setPosition(frame, position);
1327 }
1328 catch (...) {
1329 vpERROR_TRACE("Error caught");
1330 throw;
1331 }
1332}
1333
1378void vpRobotAfma6::setPosition(const std::string &filename)
1379{
1380 vpColVector q;
1381 bool ret;
1382
1383 ret = this->readPosFile(filename, q);
1384
1385 if (ret == false) {
1386 vpERROR_TRACE("Bad position in \"%s\"", filename.c_str());
1387 throw vpRobotException(vpRobotException::lowLevelError, "Bad position in filename.");
1388 }
1391}
1392
1447void vpRobotAfma6::getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position, double &timestamp)
1448{
1449
1450 InitTry;
1451
1452 position.resize(6);
1453
1454 switch (frame) {
1455 case vpRobot::CAMERA_FRAME: {
1456 position = 0;
1457 return;
1458 }
1460 double _q[njoint];
1461 Try(PrimitiveACQ_POS_Afma6(_q, &timestamp));
1462 for (unsigned int i = 0; i < njoint; i++) {
1463 position[i] = _q[i];
1464 }
1465
1466 return;
1467 }
1469 double _q[njoint];
1470 Try(PrimitiveACQ_POS_Afma6(_q, &timestamp));
1471
1473 for (unsigned int i = 0; i < njoint; i++)
1474 q[i] = _q[i];
1475
1476 // Compute fMc
1478 vpAfma6::get_fMc(q, fMc);
1479
1480 // From fMc extract the pose
1481 vpRotationMatrix fRc;
1482 fMc.extract(fRc);
1483 vpRxyzVector rxyz;
1484 rxyz.buildFrom(fRc);
1485
1486 for (unsigned int i = 0; i < 3; i++) {
1487 position[i] = fMc[i][3]; // translation x,y,z
1488 position[i + 3] = rxyz[i]; // Euler rotation x,y,z
1489 }
1490 break;
1491 }
1492 case vpRobot::MIXT_FRAME: {
1493 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in mixt frame: "
1494 "not implemented");
1495 }
1497 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in end-effector frame: "
1498 "not implemented");
1499 }
1500 }
1501
1502 CatchPrint();
1503 if (TryStt < 0) {
1504 vpERROR_TRACE("Cannot get position.");
1505 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position.");
1506 }
1507
1508 return;
1509}
1510
1515{
1516 double timestamp;
1517 PrimitiveACQ_TIME_Afma6(&timestamp);
1518 return timestamp;
1519}
1520
1532{
1533 double timestamp;
1534 getPosition(frame, position, timestamp);
1535}
1536
1546void vpRobotAfma6::getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position, double &timestamp)
1547{
1548 vpColVector posRxyz;
1549 // recupere position en Rxyz
1550 this->getPosition(frame, posRxyz, timestamp);
1551 vpRxyzVector RxyzVect;
1552 for (unsigned int j = 0; j < 3; j++)
1553 RxyzVect[j] = posRxyz[j + 3];
1554 // recupere le vecteur thetaU correspondant
1555 vpThetaUVector RtuVect(RxyzVect);
1556
1557 // remplit le vpPoseVector avec translation et rotation ThetaU
1558 for (unsigned int j = 0; j < 3; j++) {
1559 position[j] = posRxyz[j];
1560 position[j + 3] = RtuVect[j];
1561 }
1562}
1563
1575{
1576 double timestamp;
1577 getPosition(frame, position, timestamp);
1578}
1579
1644{
1646 vpERROR_TRACE("Cannot send a velocity to the robot "
1647 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1649 "Cannot send a velocity to the robot "
1650 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1651 }
1652
1653 vpColVector vel_max(6);
1654
1655 for (unsigned int i = 0; i < 3; i++)
1656 vel_max[i] = getMaxTranslationVelocity();
1657 for (unsigned int i = 3; i < 6; i++)
1658 vel_max[i] = getMaxRotationVelocity();
1659
1660 vpColVector vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1661
1662 InitTry;
1663
1664 switch (frame) {
1665 case vpRobot::CAMERA_FRAME: {
1666 Try(PrimitiveMOVESPEED_CART_Afma6(vel_sat.data, REPCAM_AFMA6));
1667 break;
1668 }
1670 // Transform in camera frame
1672 this->get_cMe(cMe);
1673 vpVelocityTwistMatrix cVe(cMe);
1674 vpColVector v_c = cVe * vel_sat;
1675 // Send velocities in m/s and rad/s
1676 Try(PrimitiveMOVESPEED_CART_Afma6(v_c.data, REPCAM_AFMA6));
1677 break;
1678 }
1680 // Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_AFMA6) );
1681 Try(PrimitiveMOVESPEED_Afma6(vel_sat.data));
1682 break;
1683 }
1685 Try(PrimitiveMOVESPEED_CART_Afma6(vel_sat.data, REPFIX_AFMA6));
1686 break;
1687 }
1688 case vpRobot::MIXT_FRAME: {
1689 Try(PrimitiveMOVESPEED_CART_Afma6(vel_sat.data, REPMIX_AFMA6));
1690 break;
1691 }
1692 default: {
1693 vpERROR_TRACE("Error in spec of vpRobot. "
1694 "Case not taken in account.");
1695 return;
1696 }
1697 }
1698
1699 Catch();
1700 if (TryStt < 0) {
1701 if (TryStt == VelStopOnJoint) {
1702 Int32 axisInJoint[njoint];
1703 PrimitiveSTATUS_Afma6(nullptr, nullptr, nullptr, nullptr, nullptr, axisInJoint, nullptr);
1704 for (unsigned int i = 0; i < njoint; i++) {
1705 if (axisInJoint[i])
1706 std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl;
1707 }
1708 }
1709 else {
1710 printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1711 if (TryString != nullptr) {
1712 // The statement is in TryString, but we need to check the validity
1713 printf(" Error sentence %s\n", TryString); // Print the TryString
1714 }
1715 else {
1716 printf("\n");
1717 }
1718 }
1719 }
1720
1721 return;
1722}
1723
1724/* ------------------------------------------------------------------------ */
1725/* --- GET ---------------------------------------------------------------- */
1726/* ------------------------------------------------------------------------ */
1727
1777void vpRobotAfma6::getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity, double &timestamp)
1778{
1779 velocity.resize(6);
1780 velocity = 0;
1781
1782 double q[6];
1783 vpColVector q_cur(6);
1784 vpHomogeneousMatrix fMc_cur;
1785 vpHomogeneousMatrix cMc; // camera displacement
1786 double time_cur;
1787
1788 InitTry;
1789
1790 // Get the current joint position
1791 Try(PrimitiveACQ_POS_Afma6(q, &timestamp));
1792 time_cur = timestamp;
1793 for (unsigned int i = 0; i < njoint; i++) {
1794 q_cur[i] = q[i];
1795 }
1796
1797 // Get the camera pose from the direct kinematics
1798 vpAfma6::get_fMc(q_cur, fMc_cur);
1799
1800 if (!first_time_getvel) {
1801
1802 switch (frame) {
1803 case vpRobot::CAMERA_FRAME: {
1804 // Compute the displacement of the camera since the previous call
1805 cMc = fMc_prev_getvel.inverse() * fMc_cur;
1806
1807 // Compute the velocity of the camera from this displacement
1808 velocity = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1809
1810 break;
1811 }
1812
1814 velocity = (q_cur - q_prev_getvel) / (time_cur - time_prev_getvel);
1815 break;
1816 }
1817
1819 // Compute the displacement of the camera since the previous call
1820 cMc = fMc_prev_getvel.inverse() * fMc_cur;
1821
1822 // Compute the velocity of the camera from this displacement
1823 vpColVector v;
1824 v = vpExponentialMap::inverse(cMc, time_cur - time_prev_getvel);
1825
1826 // Express this velocity in the reference frame
1827 vpVelocityTwistMatrix fVc(fMc_cur);
1828 velocity = fVc * v;
1829
1830 break;
1831 }
1832
1833 case vpRobot::MIXT_FRAME: {
1834 // Compute the displacement of the camera since the previous call
1835 cMc = fMc_prev_getvel.inverse() * fMc_cur;
1836
1837 // Compute the ThetaU representation for the rotation
1838 vpRotationMatrix cRc;
1839 cMc.extract(cRc);
1840 vpThetaUVector thetaU;
1841 thetaU.buildFrom(cRc);
1842
1843 for (unsigned int i = 0; i < 3; i++) {
1844 // Compute the translation displacement in the reference frame
1845 velocity[i] = fMc_prev_getvel[i][3] - fMc_cur[i][3];
1846 // Update the rotation displacement in the camera frame
1847 velocity[i + 3] = thetaU[i];
1848 }
1849
1850 // Compute the velocity
1851 velocity /= (time_cur - time_prev_getvel);
1852 break;
1853 }
1854 default: {
1856 "vpRobotAfma6::getVelocity() not implemented in end-effector"));
1857 }
1858 }
1859 }
1860 else {
1861 first_time_getvel = false;
1862 }
1863
1864 // Memorize the camera pose for the next call
1865 fMc_prev_getvel = fMc_cur;
1866
1867 // Memorize the joint position for the next call
1868 q_prev_getvel = q_cur;
1869
1870 // Memorize the time associated to the joint position for the next call
1871 time_prev_getvel = time_cur;
1872
1873 CatchPrint();
1874 if (TryStt < 0) {
1875 vpERROR_TRACE("Cannot get velocity.");
1876 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get velocity.");
1877 }
1878}
1879
1889{
1890 double timestamp;
1891 getVelocity(frame, velocity, timestamp);
1892}
1893
1936{
1937 vpColVector velocity;
1938 getVelocity(frame, velocity, timestamp);
1939
1940 return velocity;
1941}
1942
1952{
1953 vpColVector velocity;
1954 double timestamp;
1955 getVelocity(frame, velocity, timestamp);
1956
1957 return velocity;
1958}
1959
2008
2009bool vpRobotAfma6::readPosFile(const std::string &filename, vpColVector &q)
2010{
2011 std::ifstream fd(filename.c_str(), std::ios::in);
2012
2013 if (!fd.is_open()) {
2014 return false;
2015 }
2016
2017 std::string line;
2018 std::string key("R:");
2019 std::string id("#AFMA6 - Position");
2020 bool pos_found = false;
2021 int lineNum = 0;
2022
2023 q.resize(njoint);
2024
2025 while (std::getline(fd, line)) {
2026 lineNum++;
2027 if (lineNum == 1) {
2028 if (!(line.compare(0, id.size(), id) == 0)) { // check if Afma6 position file
2029 std::cout << "Error: this position file " << filename << " is not for Afma6 robot" << std::endl;
2030 return false;
2031 }
2032 }
2033 if ((line.compare(0, 1, "#") == 0)) { // skip comment
2034 continue;
2035 }
2036 if ((line.compare(0, key.size(), key) == 0)) { // decode position
2037 // check if there are at least njoint values in the line
2038 std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
2039 if (chain.size() < njoint + 1) // try to split with tab separator
2040 chain = vpIoTools::splitChain(line, std::string("\t"));
2041 if (chain.size() < njoint + 1)
2042 continue;
2043
2044 std::istringstream ss(line);
2045 std::string key_;
2046 ss >> key_;
2047 for (unsigned int i = 0; i < njoint; i++)
2048 ss >> q[i];
2049 pos_found = true;
2050 break;
2051 }
2052 }
2053
2054 // converts rotations from degrees into radians
2055 q[3] = vpMath::rad(q[3]);
2056 q[4] = vpMath::rad(q[4]);
2057 q[5] = vpMath::rad(q[5]);
2058
2059 fd.close();
2060
2061 if (!pos_found) {
2062 std::cout << "Error: unable to find a position for Afma6 robot in " << filename << std::endl;
2063 return false;
2064 }
2065
2066 return true;
2067}
2068
2092
2093bool vpRobotAfma6::savePosFile(const std::string &filename, const vpColVector &q)
2094{
2095
2096 FILE *fd;
2097 fd = fopen(filename.c_str(), "w");
2098 if (fd == nullptr)
2099 return false;
2100
2101 fprintf(fd, "\
2102#AFMA6 - Position - Version 2.01\n\
2103#\n\
2104# R: X Y Z A B C\n\
2105# Joint position: X, Y, Z: translations in meters\n\
2106# A, B, C: rotations in degrees\n\
2107#\n\
2108#\n\n");
2109
2110 // Save positions in mm and deg
2111 fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n", q[0], q[1], q[2], vpMath::deg(q[3]), vpMath::deg(q[4]),
2112 vpMath::deg(q[5]));
2113
2114 fclose(fd);
2115 return (true);
2116}
2117
2128void vpRobotAfma6::move(const std::string &filename)
2129{
2130 vpColVector q;
2131
2132 this->readPosFile(filename, q);
2134 this->setPositioningVelocity(10);
2136}
2137
2150void vpRobotAfma6::move(const std::string &filename, double velocity)
2151{
2152 vpColVector q;
2153
2154 this->readPosFile(filename, q);
2156 this->setPositioningVelocity(velocity);
2158}
2159
2167{
2168 InitTry;
2169 Try(PrimitiveGripper_Afma6(1));
2170 std::cout << "Open the gripper..." << std::endl;
2171 CatchPrint();
2172 if (TryStt < 0) {
2173 vpERROR_TRACE("Cannot open the gripper");
2174 throw vpRobotException(vpRobotException::lowLevelError, "Cannot open the gripper.");
2175 }
2176}
2177
2186{
2187 InitTry;
2188 Try(PrimitiveGripper_Afma6(0));
2189 std::cout << "Close the gripper..." << std::endl;
2190 CatchPrint();
2191 if (TryStt < 0) {
2192 vpERROR_TRACE("Cannot close the gripper");
2193 throw vpRobotException(vpRobotException::lowLevelError, "Cannot close the gripper.");
2194 }
2195}
2196
2216{
2217 displacement.resize(6);
2218 displacement = 0;
2219
2220 double q[6];
2221 vpColVector q_cur(6);
2222 vpHomogeneousMatrix fMc_cur, c_prevMc_cur;
2223 double timestamp;
2224
2225 InitTry;
2226
2227 // Get the current joint position
2228 Try(PrimitiveACQ_POS_Afma6(q, &timestamp));
2229 for (unsigned int i = 0; i < njoint; i++) {
2230 q_cur[i] = q[i];
2231 }
2232
2233 // Compute the camera pose in the reference frame
2234 fMc_cur = get_fMc(q_cur);
2235
2236 if (!first_time_getdis) {
2237 switch (frame) {
2238 case vpRobot::CAMERA_FRAME: {
2239 // Compute the camera dispacement from the previous pose
2240 c_prevMc_cur = fMc_prev_getdis.inverse() * fMc_cur;
2241
2244 c_prevMc_cur.extract(t);
2245 c_prevMc_cur.extract(R);
2246
2247 vpRxyzVector rxyz;
2248 rxyz.buildFrom(R);
2249
2250 for (unsigned int i = 0; i < 3; i++) {
2251 displacement[i] = t[i];
2252 displacement[i + 3] = rxyz[i];
2253 }
2254 break;
2255 }
2256
2258 displacement = q_cur - q_prev_getdis;
2259 break;
2260 }
2261
2263 std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2264 return;
2265 }
2266
2267 case vpRobot::MIXT_FRAME: {
2268 std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2269 return;
2270 }
2272 std::cout << "getDisplacement() END_EFFECTOR_FRAME not implemented\n";
2273 return;
2274 }
2275 }
2276 }
2277 else {
2278 first_time_getdis = false;
2279 }
2280
2281 // Memorize the joint position for the next call
2282 q_prev_getdis = q_cur;
2283
2284 // Memorize the pose for the next call
2285 fMc_prev_getdis = fMc_cur;
2286
2287 CatchPrint();
2288 if (TryStt < 0) {
2289 vpERROR_TRACE("Cannot get velocity.");
2290 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get velocity.");
2291 }
2292}
2293
2305{
2306 Int32 axisInJoint[njoint];
2307 bool status = true;
2308 jointsStatus.resize(6);
2309 InitTry;
2310
2311 Try(PrimitiveSTATUS_Afma6(nullptr, nullptr, nullptr, nullptr, nullptr, axisInJoint, nullptr));
2312 for (unsigned int i = 0; i < njoint; i++) {
2313 if (axisInJoint[i]) {
2314 std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl;
2315 jointsStatus[i] = axisInJoint[i];
2316 status = false;
2317 }
2318 else {
2319 jointsStatus[i] = 0;
2320 }
2321 }
2322
2323 Catch();
2324 if (TryStt < 0) {
2325 vpERROR_TRACE("Cannot check joint limits.");
2326 throw vpRobotException(vpRobotException::lowLevelError, "Cannot check joint limits.");
2327 }
2328
2329 return status;
2330}
2331END_VISP_NAMESPACE
2332#elif !defined(VISP_BUILD_SHARED_LIBS)
2333// Work around to avoid warning: libvisp_robot.a(vpRobotAfma6.cpp.o) has no symbols
2334void dummy_vpRobotAfma6() { }
2335#endif
virtual void set_eMc(const vpHomogeneousMatrix &eMc)
Definition vpAfma6.cpp:1189
double _joint_min[6]
Definition vpAfma6.h:202
static const unsigned int njoint
Number of joint.
Definition vpAfma6.h:196
void init(void)
Definition vpAfma6.cpp:155
vpRxyzVector _erc
Definition vpAfma6.h:205
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false) const
Definition vpAfma6.cpp:596
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition vpAfma6.cpp:890
void setToolType(vpAfma6::vpAfma6ToolType tool)
Set the current tool type.
Definition vpAfma6.h:192
double _coupl_56
Definition vpAfma6.h:199
static const vpAfma6ToolType defaultTool
Default tool attached to the robot end effector.
Definition vpAfma6.h:134
double _long_56
Definition vpAfma6.h:200
vpTranslationVector _etc
Definition vpAfma6.h:204
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition vpAfma6.cpp:777
vpCameraParameters::vpCameraParametersProjType projModel
Definition vpAfma6.h:213
double _joint_max[6]
Definition vpAfma6.h:201
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition vpAfma6.cpp:934
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition vpAfma6.cpp:1004
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Definition vpAfma6.h:124
Type * data
Address of the first element of the data array.
Definition vpArray2D.h:149
Implementation of column vector and the associated operations.
void resize(unsigned int i, bool flagNullify=true)
error that can be emitted by ViSP classes.
Definition vpException.h:60
@ functionNotImplementedError
Function not implemented.
Definition vpException.h:66
static vpColVector inverse(const vpHomogeneousMatrix &M)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
void extract(vpRotationMatrix &R) const
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
static double rad(double deg)
Definition vpMath.h:129
static double deg(double rad)
Definition vpMath.h:119
Implementation of a matrix and operations on matrices.
Definition vpMatrix.h:175
Implementation of a pose vector and operations on poses.
void get_cVe(vpVelocityTwistMatrix &_cVe) const
bool checkJointLimits(vpColVector &jointsStatus)
void get_eJe(vpMatrix &_eJe) VP_OVERRIDE
static bool savePosFile(const std::string &filename, const vpColVector &q)
void setPosition(const vpRobot::vpControlFrameType frame, const vpPoseVector &pose)
void get_fJe(vpMatrix &_fJe) VP_OVERRIDE
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
double getTime() const
static const double defaultPositioningVelocity
void init(void)
void get_cMe(vpHomogeneousMatrix &_cMe) const
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
double getPositioningVelocity(void)
void set_eMc(const vpHomogeneousMatrix &eMc)
virtual ~vpRobotAfma6(void)
void move(const std::string &filename)
void setPositioningVelocity(double velocity)
static bool readPosFile(const std::string &filename, vpColVector &q)
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position) VP_OVERRIDE
Error that can be emitted by the vpRobot class and its derivatives.
@ wrongStateError
Wrong robot state.
@ constructionError
Error from constructor.
@ positionOutOfRangeError
Position is out of range.
@ lowLevelError
Error thrown by the low level sdk.
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
Definition vpRobot.h:103
void setVerbose(bool verbose)
Definition vpRobot.h:167
virtual vpRobotStateType getRobotState(void) const
Definition vpRobot.h:152
static vpColVector saturateVelocities(const vpColVector &v_in, const vpColVector &v_max, bool verbose=false)
Definition vpRobot.cpp:162
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
double getMaxRotationVelocity(void) const
Definition vpRobot.cpp:272
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
double getMaxTranslationVelocity(void) const
Definition vpRobot.cpp:250
vpRobot(void)
Definition vpRobot.cpp:49
bool verbose_
Definition vpRobot.h:115
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
vpRxyzVector & buildFrom(const vpRotationMatrix &R)
Implementation of a rotation vector as axis-angle minimal representation.
vpThetaUVector & buildFrom(const vpHomogeneousMatrix &M)
Class that consider the case of a translation vector.
vpVelocityTwistMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
#define vpERROR_TRACE
Definition vpDebug.h:423