Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpRobotViper850.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 Viper S850 robot.
32 */
33
34#include <visp3/core/vpConfig.h>
35
36#ifdef VISP_HAVE_VIPER850
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/vpThetaUVector.h>
47#include <visp3/core/vpVelocityTwistMatrix.h>
48#include <visp3/robot/vpRobot.h>
49#include <visp3/robot/vpRobotException.h>
50#include <visp3/robot/vpRobotViper850.h>
51
53/* ---------------------------------------------------------------------- */
54/* --- STATIC ----------------------------------------------------------- */
55/* ---------------------------------------------------------------------- */
56
57bool vpRobotViper850::m_robotAlreadyCreated = false;
58
67
68/* ---------------------------------------------------------------------- */
69/* --- EMERGENCY STOP --------------------------------------------------- */
70/* ---------------------------------------------------------------------- */
71
79void emergencyStopViper850(int signo)
80{
81 std::cout << "Stop the Viper850 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_Viper850();
103 PrimitiveSTOP_Viper850();
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
176vpRobotViper850::vpRobotViper850(bool verbose) : vpViper850(), vpRobot()
177{
178
179 /*
180 #define SIGHUP 1 // hangup
181 #define SIGINT 2 // interrupt (rubout)
182 #define SIGQUIT 3 // quit (ASCII FS)
183 #define SIGILL 4 // illegal instruction (not reset when caught)
184 #define SIGTRAP 5 // trace trap (not reset when caught)
185 #define SIGIOT 6 // IOT instruction
186 #define SIGABRT 6 // used by abort, replace SIGIOT in the future
187 #define SIGEMT 7 // EMT instruction
188 #define SIGFPE 8 // floating point exception
189 #define SIGKILL 9 // kill (cannot be caught or ignored)
190 #define SIGBUS 10 // bus error
191 #define SIGSEGV 11 // segmentation violation
192 #define SIGSYS 12 // bad argument to system call
193 #define SIGPIPE 13 // write on a pipe with no one to read it
194 #define SIGALRM 14 // alarm clock
195 #define SIGTERM 15 // software termination signal from kill
196 */
197
198 signal(SIGINT, emergencyStopViper850);
199 signal(SIGBUS, emergencyStopViper850);
200 signal(SIGSEGV, emergencyStopViper850);
201 signal(SIGKILL, emergencyStopViper850);
202 signal(SIGQUIT, emergencyStopViper850);
203
204 setVerbose(verbose);
205 if (verbose_)
206 std::cout << "Open communication with MotionBlox.\n";
207 try {
208 this->init();
210 }
211 catch (...) {
212 // vpERROR_TRACE("Error caught") ;
213 throw;
214 }
215 m_positioningVelocity = m_defaultPositioningVelocity;
216
217 maxRotationVelocity_joint6 = maxRotationVelocity;
218
219 vpRobotViper850::m_robotAlreadyCreated = true;
220
221 return;
222}
223
224/* ------------------------------------------------------------------------ */
225/* --- INITIALISATION ----------------------------------------------------- */
226/* ------------------------------------------------------------------------ */
227
253{
254 InitTry;
255
256 // Initialise private variables used to compute the measured velocities
257 m_q_prev_getvel.resize(6);
258 m_q_prev_getvel = 0;
259 m_time_prev_getvel = 0;
260 m_first_time_getvel = true;
261
262 // Initialise private variables used to compute the measured displacement
263 m_q_prev_getdis.resize(6);
264 m_q_prev_getdis = 0;
265 m_first_time_getdis = true;
266
267#if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
268 std::string calibfile;
269#ifdef VISP_HAVE_VIPER850_DATA
270 calibfile = std::string(VISP_VIPER850_DATA_PATH) + std::string("/ati/FT17824.cal");
271 if (!vpIoTools::checkFilename(calibfile))
272 throw(vpException(vpException::ioError, "ATI F/T calib file \"%s\" doesn't exist", calibfile.c_str()));
273#else
274 throw(vpException(vpException::ioError, "You don't have access to Viper850 "
275 "data to retrieve ATI F/T calib "
276 "file"));
277#endif
278 m_ati.setCalibrationFile(calibfile);
279 m_ati.open();
280#endif
281
282 // Initialize the firewire connection
283 Try(InitializeConnection(verbose_));
284
285 // Connect to the servoboard using the servo board GUID
286 Try(InitializeNode_Viper850());
287
288 Try(PrimitiveRESET_Viper850());
289
290 // Enable the joint limits on axis 6
291 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0));
292
293 // Update the eMc matrix in the low level controller
295
296 // Look if the power is on or off
297 UInt32 HIPowerStatus;
298 UInt32 EStopStatus;
299 Try(PrimitiveSTATUS_Viper850(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus));
300 CAL_Wait(0.1);
301
302 // Print the robot status
303 if (verbose_) {
304 std::cout << "Robot status: ";
305 switch (EStopStatus) {
306 case ESTOP_AUTO:
307 m_controlMode = AUTO;
308 if (HIPowerStatus == 0)
309 std::cout << "Power is OFF" << std::endl;
310 else
311 std::cout << "Power is ON" << std::endl;
312 break;
313
314 case ESTOP_MANUAL:
315 m_controlMode = MANUAL;
316 if (HIPowerStatus == 0)
317 std::cout << "Power is OFF" << std::endl;
318 else
319 std::cout << "Power is ON" << std::endl;
320 break;
321 case ESTOP_ACTIVATED:
322 m_controlMode = ESTOP;
323 std::cout << "Emergency stop is activated" << std::endl;
324 break;
325 default:
326 std::cout << "Sorry there is an error on the emergency chain." << std::endl;
327 std::cout << "You have to call Adept for maintenance..." << std::endl;
328 // Free allocated resources
329 }
330 std::cout << std::endl;
331 }
332 // get real joint min/max from the MotionBlox
333 Try(PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data));
334 // Convert units from degrees to radians
335 joint_min.deg2rad();
336 joint_max.deg2rad();
337
338 // for (unsigned int i=0; i < njoint; i++) {
339 // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
340 // joint_max[i]);
341 // }
342
343 // If an error occur in the low level controller, goto here
344 // CatchPrint();
345 Catch();
346
347 // Test if an error occurs
348 if (TryStt == -20001)
349 printf("No connection detected. Check if the robot is powered on \n"
350 "and if the firewire link exist between the MotionBlox and this "
351 "computer.\n");
352 else if (TryStt == -675)
353 printf(" Timeout enabling power...\n");
354
355 if (TryStt < 0) {
356 // Power off the robot
357 PrimitivePOWEROFF_Viper850();
358 // Free allocated resources
359 ShutDownConnection();
360
361 std::cout << "Cannot open connection with the motionblox..." << std::endl;
362 throw vpRobotException(vpRobotException::constructionError, "Cannot open connection with the motionblox");
363 }
364 return;
365}
366
428{
429 // Read the robot constants from files
430 // - joint [min,max], coupl_56, long_56
431 // - camera extrinsic parameters relative to eMc
433
434 InitTry;
435
436 // get real joint min/max from the MotionBlox
437 Try(PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data));
438 // Convert units from degrees to radians
439 joint_min.deg2rad();
440 joint_max.deg2rad();
441
442 // for (unsigned int i=0; i < njoint; i++) {
443 // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
444 // joint_max[i]);
445 // }
446
447 // Set the camera constant (eMc pose) in the MotionBlox
448 double eMc_pose[6];
449 for (unsigned int i = 0; i < 3; i++) {
450 eMc_pose[i] = etc[i]; // translation in meters
451 eMc_pose[i + 3] = erc[i]; // rotation in rad
452 }
453 // Update the eMc pose in the low level controller
454 Try(PrimitiveCONST_Viper850(eMc_pose));
455
456 CatchPrint();
457 return;
458}
459
514void vpRobotViper850::init(vpViper850::vpToolType tool, const std::string &filename)
515{
516 vpViper850::init(tool, filename);
517
518 InitTry;
519
520 // Get real joint min/max from the MotionBlox
521 Try(PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data));
522 // Convert units from degrees to radians
523 joint_min.deg2rad();
524 joint_max.deg2rad();
525
526 // for (unsigned int i=0; i < njoint; i++) {
527 // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
528 // joint_max[i]);
529 // }
530
531 // Set the camera constant (eMc pose) in the MotionBlox
532 double eMc_pose[6];
533 for (unsigned int i = 0; i < 3; i++) {
534 eMc_pose[i] = etc[i]; // translation in meters
535 eMc_pose[i + 3] = erc[i]; // rotation in rad
536 }
537 // Update the eMc pose in the low level controller
538 Try(PrimitiveCONST_Viper850(eMc_pose));
539
540 CatchPrint();
541 return;
542}
543
585{
586 vpViper850::init(tool, eMc_);
587
588 InitTry;
589
590 // Get real joint min/max from the MotionBlox
591 Try(PrimitiveJOINT_MINMAX_Viper850(joint_min.data, joint_max.data));
592 // Convert units from degrees to radians
593 joint_min.deg2rad();
594 joint_max.deg2rad();
595
596 // for (unsigned int i=0; i < njoint; i++) {
597 // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
598 // joint_max[i]);
599 // }
600
601 // Set the camera constant (eMc pose) in the MotionBlox
602 double eMc_pose[6];
603 for (unsigned int i = 0; i < 3; i++) {
604 eMc_pose[i] = etc[i]; // translation in meters
605 eMc_pose[i + 3] = erc[i]; // rotation in rad
606 }
607 // Update the eMc pose in the low level controller
608 Try(PrimitiveCONST_Viper850(eMc_pose));
609
610 CatchPrint();
611 return;
612}
613
626{
627 this->vpViper850::set_eMc(eMc_);
628
629 InitTry;
630
631 // Set the camera constant (eMc pose) in the MotionBlox
632 double eMc_pose[6];
633 for (unsigned int i = 0; i < 3; i++) {
634 eMc_pose[i] = etc[i]; // translation in meters
635 eMc_pose[i + 3] = erc[i]; // rotation in rad
636 }
637 // Update the eMc pose in the low level controller
638 Try(PrimitiveCONST_Viper850(eMc_pose));
639
640 CatchPrint();
641
642 return;
643}
644
658{
659 this->vpViper850::set_eMc(etc_, erc_);
660
661 InitTry;
662
663 // Set the camera constant (eMc pose) in the MotionBlox
664 double eMc_pose[6];
665 for (unsigned int i = 0; i < 3; i++) {
666 eMc_pose[i] = etc[i]; // translation in meters
667 eMc_pose[i + 3] = erc[i]; // rotation in rad
668 }
669 // Update the eMc pose in the low level controller
670 Try(PrimitiveCONST_Viper850(eMc_pose));
671
672 CatchPrint();
673
674 return;
675}
676
677/* ------------------------------------------------------------------------ */
678/* --- DESTRUCTOR --------------------------------------------------------- */
679/* ------------------------------------------------------------------------ */
680
688{
689#if defined(USE_ATI_DAQ) && defined(VISP_HAVE_COMEDI)
690 m_ati.close();
691#endif
692
693 InitTry;
694
696
697 // Look if the power is on or off
698 UInt32 HIPowerStatus;
699 Try(PrimitiveSTATUS_Viper850(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus));
700 CAL_Wait(0.1);
701
702 // if (HIPowerStatus == 1) {
703 // fprintf(stdout, "Power OFF the robot\n");
704 // fflush(stdout);
705
706 // Try( PrimitivePOWEROFF_Viper850() );
707 // }
708
709 // Free allocated resources
710 ShutDownConnection();
711
712 vpRobotViper850::m_robotAlreadyCreated = false;
713
714 CatchPrint();
715 return;
716}
717
725{
726 InitTry;
727
728 switch (newState) {
729 case vpRobot::STATE_STOP: {
730 // Start primitive STOP only if the current state is Velocity
732 Try(PrimitiveSTOP_Viper850());
733 vpTime::sleepMs(100); // needed to ensure velocity task ends up on low level
734 }
735 break;
736 }
739 std::cout << "Change the control mode from velocity to position control.\n";
740 Try(PrimitiveSTOP_Viper850());
741 }
742 else {
743 // std::cout << "Change the control mode from stop to position
744 // control.\n";
745 }
746 this->powerOn();
747 break;
748 }
751 std::cout << "Change the control mode from stop to velocity control.\n";
752 }
753 this->powerOn();
754 break;
755 }
756 default:
757 break;
758 }
759
760 CatchPrint();
761
762 return vpRobot::setRobotState(newState);
763}
764
765/* ------------------------------------------------------------------------ */
766/* --- STOP --------------------------------------------------------------- */
767/* ------------------------------------------------------------------------ */
768
777{
779 return;
780
781 InitTry;
782 Try(PrimitiveSTOP_Viper850());
784
785 CatchPrint();
786 if (TryStt < 0) {
787 vpERROR_TRACE("Cannot stop robot motion");
788 throw vpRobotException(vpRobotException::lowLevelError, "Cannot stop robot motion.");
789 }
790}
791
802{
803 InitTry;
804
805 // Look if the power is on or off
806 UInt32 HIPowerStatus;
807 UInt32 EStopStatus;
808 bool firsttime = true;
809 unsigned int nitermax = 10;
810
811 for (unsigned int i = 0; i < nitermax; i++) {
812 Try(PrimitiveSTATUS_Viper850(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus));
813 if (EStopStatus == ESTOP_AUTO) {
814 m_controlMode = AUTO;
815 break; // exit for loop
816 }
817 else if (EStopStatus == ESTOP_MANUAL) {
818 m_controlMode = MANUAL;
819 break; // exit for loop
820 }
821 else if (EStopStatus == ESTOP_ACTIVATED) {
822 m_controlMode = ESTOP;
823 if (firsttime) {
824 std::cout << "Emergency stop is activated! \n"
825 << "Check the emergency stop button and push the yellow "
826 "button before continuing."
827 << std::endl;
828 firsttime = false;
829 }
830 fprintf(stdout, "Remaining time %us \r", nitermax - i);
831 fflush(stdout);
832 CAL_Wait(1);
833 }
834 else {
835 std::cout << "Sorry there is an error on the emergency chain." << std::endl;
836 std::cout << "You have to call Adept for maintenance..." << std::endl;
837 // Free allocated resources
838 ShutDownConnection();
839 throw(vpRobotException(vpRobotException::lowLevelError, "Error on the emergency chain"));
840 }
841 }
842
843 if (EStopStatus == ESTOP_ACTIVATED)
844 std::cout << std::endl;
845
846 if (EStopStatus == ESTOP_ACTIVATED) {
847 std::cout << "Sorry, cannot power on the robot." << std::endl;
848 throw(vpRobotException(vpRobotException::lowLevelError, "Cannot power on the robot."));
849 }
850
851 if (HIPowerStatus == 0) {
852 fprintf(stdout, "Power ON the Viper850 robot\n");
853 fflush(stdout);
854
855 Try(PrimitivePOWERON_Viper850());
856 }
857
858 CatchPrint();
859 if (TryStt < 0) {
860 vpERROR_TRACE("Cannot power on the robot");
861 throw(vpRobotException(vpRobotException::lowLevelError, "Cannot power off the robot."));
862 }
863}
864
875{
876 InitTry;
877
878 // Look if the power is on or off
879 UInt32 HIPowerStatus;
880 Try(PrimitiveSTATUS_Viper850(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus));
881 CAL_Wait(0.1);
882
883 if (HIPowerStatus == 1) {
884 fprintf(stdout, "Power OFF the Viper850 robot\n");
885 fflush(stdout);
886
887 Try(PrimitivePOWEROFF_Viper850());
888 }
889
890 CatchPrint();
891 if (TryStt < 0) {
892 vpERROR_TRACE("Cannot power off the robot");
893 throw vpRobotException(vpRobotException::lowLevelError, "Cannot power off the robot.");
894 }
895}
896
909{
910 InitTry;
911 bool status = false;
912 // Look if the power is on or off
913 UInt32 HIPowerStatus;
914 Try(PrimitiveSTATUS_Viper850(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus));
915 CAL_Wait(0.1);
916
917 if (HIPowerStatus == 1) {
918 status = true;
919 }
920
921 CatchPrint();
922 if (TryStt < 0) {
923 vpERROR_TRACE("Cannot get the power status");
924 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get the power status.");
925 }
926 return status;
927}
928
939{
942
943 cVe.buildFrom(cMe);
944}
945
958
971{
972
973 double position[6];
974 double timestamp;
975
976 InitTry;
977 Try(PrimitiveACQ_POS_J_Viper850(position, &timestamp));
978 CatchPrint();
979
980 vpColVector q(6);
981 for (unsigned int i = 0; i < njoint; i++)
982 q[i] = vpMath::rad(position[i]);
983
984 try {
986 }
987 catch (...) {
988 vpERROR_TRACE("catch exception ");
989 throw;
990 }
991}
992
1003
1005{
1006
1007 double position[6];
1008 double timestamp;
1009
1010 InitTry;
1011 Try(PrimitiveACQ_POS_Viper850(position, &timestamp));
1012 CatchPrint();
1013
1014 vpColVector q(6);
1015 for (unsigned int i = 0; i < njoint; i++)
1016 q[i] = position[i];
1017
1018 try {
1020 }
1021 catch (...) {
1022 vpERROR_TRACE("Error caught");
1023 throw;
1024 }
1025}
1026
1067void vpRobotViper850::setPositioningVelocity(double velocity) { m_positioningVelocity = velocity; }
1068
1074double vpRobotViper850::getPositioningVelocity(void) const { return m_positioningVelocity; }
1075
1157{
1158
1160 vpERROR_TRACE("Robot was not in position-based control\n"
1161 "Modification of the robot state");
1163 }
1164
1165 vpColVector destination(njoint);
1166 int error = 0;
1167 double timestamp;
1168
1169 InitTry;
1170 switch (frame) {
1171 case vpRobot::CAMERA_FRAME: {
1173 Try(PrimitiveACQ_POS_Viper850(q.data, &timestamp));
1174
1175 // Convert degrees into rad
1176 q.deg2rad();
1177
1178 // Get fMc from the inverse kinematics
1180 vpViper850::get_fMc(q, fMc);
1181
1182 // Set cMc from the input position
1184 vpRxyzVector rxyz;
1185 for (unsigned int i = 0; i < 3; i++) {
1186 txyz[i] = position[i];
1187 rxyz[i] = position[i + 3];
1188 }
1189
1190 // Compute cMc2
1191 vpRotationMatrix cRc2(rxyz);
1192 vpHomogeneousMatrix cMc2(txyz, cRc2);
1193
1194 // Compute the new position to reach: fMc*cMc2
1195 vpHomogeneousMatrix fMc2 = fMc * cMc2;
1196
1197 // Compute the corresponding joint position from the inverse kinematics
1198 unsigned int solution = this->getInverseKinematics(fMc2, q);
1199 if (solution) { // Position is reachable
1200 destination = q;
1201 // convert rad to deg requested for the low level controller
1202 destination.rad2deg();
1203 Try(PrimitiveMOVE_J_Viper850(destination.data, m_positioningVelocity));
1204 Try(WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000));
1205 }
1206 else {
1207 // Cartesian position is out of range
1208 error = -1;
1209 }
1210
1211 break;
1212 }
1214 destination = position;
1215 // convert rad to deg requested for the low level controller
1216 destination.rad2deg();
1217
1218 // std::cout << "Joint destination (deg): " << destination.t() <<
1219 // std::endl;
1220 Try(PrimitiveMOVE_J_Viper850(destination.data, m_positioningVelocity));
1221 Try(WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000));
1222 break;
1223 }
1225 // Convert angles from Rxyz representation to Rzyz representation
1226 vpRxyzVector rxyz(position[3], position[4], position[5]);
1227 vpRotationMatrix R(rxyz);
1228 vpRzyzVector rzyz(R);
1229
1230 for (unsigned int i = 0; i < 3; i++) {
1231 destination[i] = position[i];
1232 destination[i + 3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1233 }
1234 int configuration = 0; // keep the actual configuration
1235
1236 // std::cout << "Base frame destination Rzyz (deg): " << destination.t()
1237 // << std::endl;
1238 Try(PrimitiveMOVE_C_Viper850(destination.data, configuration, m_positioningVelocity));
1239 Try(WaitState_Viper850(ETAT_ATTENTE_VIPER850, 1000));
1240
1241 break;
1242 }
1243 case vpRobot::MIXT_FRAME: {
1244 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1245 "Mixt frame not implemented.");
1246 }
1248 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1249 "End-effector frame not implemented.");
1250 }
1251 }
1252
1253 CatchPrint();
1254 if (TryStt == InvalidPosition || TryStt == -1023)
1255 std::cout << " : Position out of range.\n";
1256 else if (TryStt == -3019) {
1257 if (frame == vpRobot::ARTICULAR_FRAME)
1258 std::cout << " : Joint position out of range.\n";
1259 else
1260 std::cout << " : Cartesian position leads to a joint position out of "
1261 "range.\n";
1262 }
1263 else if (TryStt < 0)
1264 std::cout << " : Unknown error (see Fabien).\n";
1265 else if (error == -1)
1266 std::cout << "Position out of range.\n";
1267
1268 if (TryStt < 0 || error < 0) {
1269 vpERROR_TRACE("Positioning error.");
1270 throw vpRobotException(vpRobotException::positionOutOfRangeError, "Position out of range.");
1271 }
1272
1273 return;
1274}
1275
1344void vpRobotViper850::setPosition(const vpRobot::vpControlFrameType frame, double pos1, double pos2, double pos3,
1345 double pos4, double pos5, double pos6)
1346{
1347 try {
1348 vpColVector position(6);
1349 position[0] = pos1;
1350 position[1] = pos2;
1351 position[2] = pos3;
1352 position[3] = pos4;
1353 position[4] = pos5;
1354 position[5] = pos6;
1355
1356 setPosition(frame, position);
1357 }
1358 catch (...) {
1359 vpERROR_TRACE("Error caught");
1360 throw;
1361 }
1362}
1363
1406void vpRobotViper850::setPosition(const std::string &filename)
1407{
1408 vpColVector q;
1409 bool ret;
1410
1411 ret = this->readPosFile(filename, q);
1412
1413 if (ret == false) {
1414 vpERROR_TRACE("Bad position in \"%s\"", filename.c_str());
1415 throw vpRobotException(vpRobotException::lowLevelError, "Bad position in filename.");
1416 }
1419}
1420
1492void vpRobotViper850::getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position, double &timestamp)
1493{
1494
1495 InitTry;
1496
1497 position.resize(6);
1498
1499 switch (frame) {
1500 case vpRobot::CAMERA_FRAME: {
1501 position = 0;
1502 return;
1503 }
1505 Try(PrimitiveACQ_POS_J_Viper850(position.data, &timestamp));
1506 // vpCTRACE << "Get joint position (deg)" << position.t() << std::endl;
1507 position.deg2rad();
1508
1509 return;
1510 }
1513 Try(PrimitiveACQ_POS_J_Viper850(q.data, &timestamp));
1514
1515 // Compute fMc
1517
1518 // From fMc extract the pose
1519 vpRotationMatrix fRc;
1520 fMc.extract(fRc);
1521 vpRxyzVector rxyz;
1522 rxyz.buildFrom(fRc);
1523
1524 for (unsigned int i = 0; i < 3; i++) {
1525 position[i] = fMc[i][3]; // translation x,y,z
1526 position[i + 3] = rxyz[i]; // Euler rotation x,y,z
1527 }
1528
1529 break;
1530 }
1531 case vpRobot::MIXT_FRAME: {
1532 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in mixt frame: "
1533 "not implemented");
1534 }
1536 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in end-effector frame: "
1537 "not implemented");
1538 }
1539 }
1540
1541 CatchPrint();
1542 if (TryStt < 0) {
1543 vpERROR_TRACE("Cannot get position.");
1544 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position.");
1545 }
1546
1547 return;
1548}
1549
1555{
1556 double timestamp;
1557 PrimitiveACQ_TIME_Viper850(&timestamp);
1558 return timestamp;
1559}
1560
1572{
1573 double timestamp;
1574 getPosition(frame, position, timestamp);
1575}
1576
1588void vpRobotViper850::getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position, double &timestamp)
1589{
1590 vpColVector posRxyz;
1591 // recupere position en Rxyz
1592 this->getPosition(frame, posRxyz, timestamp);
1593 vpRxyzVector RxyzVect;
1594 for (unsigned int j = 0; j < 3; j++)
1595 RxyzVect[j] = posRxyz[j + 3];
1596 // recupere le vecteur thetaU correspondant
1597 vpThetaUVector RtuVect(RxyzVect);
1598
1599 // remplit le vpPoseVector avec translation et rotation ThetaU
1600 for (unsigned int j = 0; j < 3; j++) {
1601 position[j] = posRxyz[j];
1602 position[j + 3] = RtuVect[j];
1603 }
1604}
1605
1617{
1618 vpColVector posRxyz;
1619 double timestamp;
1620 // recupere position en Rxyz
1621 this->getPosition(frame, posRxyz, timestamp);
1622 vpRxyzVector RxyzVect;
1623 for (unsigned int j = 0; j < 3; j++)
1624 RxyzVect[j] = posRxyz[j + 3];
1625 // recupere le vecteur thetaU correspondant
1626 vpThetaUVector RtuVect(RxyzVect);
1627
1628 // remplit le vpPoseVector avec translation et rotation ThetaU
1629 for (unsigned int j = 0; j < 3; j++) {
1630 position[j] = posRxyz[j];
1631 position[j + 3] = RtuVect[j];
1632 }
1633}
1634
1717{
1719 vpERROR_TRACE("Cannot send a velocity to the robot "
1720 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1722 "Cannot send a velocity to the robot "
1723 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1724 }
1725
1726 vpColVector vel_sat(6);
1727
1728 // Velocity saturation
1729 switch (frame) {
1730 // saturation in cartesian space
1734 case vpRobot::MIXT_FRAME: {
1735 vpColVector vel_max(6);
1736
1737 for (unsigned int i = 0; i < 3; i++)
1738 vel_max[i] = getMaxTranslationVelocity();
1739 for (unsigned int i = 3; i < 6; i++)
1740 vel_max[i] = getMaxRotationVelocity();
1741
1742 vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1743
1744 break;
1745 }
1746 // saturation in joint space
1748 vpColVector vel_max(6);
1749
1750 // if (getMaxRotationVelocity() == getMaxRotationVelocityJoint6()) {
1751 if (std::fabs(getMaxRotationVelocity() - getMaxRotationVelocityJoint6()) < std::numeric_limits<double>::epsilon()) {
1752
1753 for (unsigned int i = 0; i < 6; i++)
1754 vel_max[i] = getMaxRotationVelocity();
1755 }
1756 else {
1757 for (unsigned int i = 0; i < 5; i++)
1758 vel_max[i] = getMaxRotationVelocity();
1759 vel_max[5] = getMaxRotationVelocityJoint6();
1760 }
1761
1762 vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1763 }
1764 }
1765
1766 InitTry;
1767
1768 switch (frame) {
1769 case vpRobot::CAMERA_FRAME: {
1770 // Send velocities in m/s and rad/s
1771 // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1772 Try(PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPCAM_VIPER850));
1773 break;
1774 }
1776 // Transform in camera frame
1778 this->get_cMe(cMe);
1779 vpVelocityTwistMatrix cVe(cMe);
1780 vpColVector v_c = cVe * vel_sat;
1781 // Send velocities in m/s and rad/s
1782 Try(PrimitiveMOVESPEED_CART_Viper850(v_c.data, REPCAM_VIPER850));
1783 break;
1784 }
1786 // Convert all the velocities from rad/s into deg/s
1787 vel_sat.rad2deg();
1788 // std::cout << "Vitesse appliquee: " << vel_sat.t();
1789 // Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER850) );
1790 Try(PrimitiveMOVESPEED_Viper850(vel_sat.data));
1791 break;
1792 }
1794 // Send velocities in m/s and rad/s
1795 // std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1796 Try(PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPFIX_VIPER850));
1797 break;
1798 }
1799 case vpRobot::MIXT_FRAME: {
1800 // Try( PrimitiveMOVESPEED_CART_Viper850(vel_sat.data, REPMIX_VIPER850) );
1801 break;
1802 }
1803 default: {
1804 vpERROR_TRACE("Error in spec of vpRobot. "
1805 "Case not taken in account.");
1806 return;
1807 }
1808 }
1809
1810 Catch();
1811 if (TryStt < 0) {
1812 if (TryStt == VelStopOnJoint) {
1813 UInt32 axisInJoint[njoint];
1814 PrimitiveSTATUS_Viper850(nullptr, nullptr, nullptr, nullptr, nullptr, axisInJoint, nullptr);
1815 for (unsigned int i = 0; i < njoint; i++) {
1816 if (axisInJoint[i])
1817 std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl;
1818 }
1819 }
1820 else {
1821 printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1822 if (TryString != nullptr) {
1823 // The statement is in TryString, but we need to check the validity
1824 printf(" Error sentence %s\n", TryString); // Print the TryString
1825 }
1826 else {
1827 printf("\n");
1828 }
1829 }
1830 }
1831
1832 return;
1833}
1834
1835/* ------------------------------------------------------------------------ */
1836/* --- GET ---------------------------------------------------------------- */
1837/* ------------------------------------------------------------------------ */
1838
1899void vpRobotViper850::getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity, double &timestamp)
1900{
1901 velocity.resize(6);
1902 velocity = 0;
1903
1904 vpColVector q_cur(6);
1905 vpHomogeneousMatrix fMe_cur, fMc_cur;
1906 vpHomogeneousMatrix eMe, cMc; // camera displacement
1907 double time_cur;
1908
1909 InitTry;
1910
1911 // Get the current joint position
1912 Try(PrimitiveACQ_POS_J_Viper850(q_cur.data, &timestamp));
1913 time_cur = timestamp;
1914 q_cur.deg2rad();
1915
1916 // Get the end-effector pose from the direct kinematics
1917 vpViper850::get_fMe(q_cur, fMe_cur);
1918 // Get the camera pose from the direct kinematics
1919 vpViper850::get_fMc(q_cur, fMc_cur);
1920
1921 if (!m_first_time_getvel) {
1922
1923 switch (frame) {
1925 // Compute the displacement of the end-effector since the previous call
1926 eMe = m_fMe_prev_getvel.inverse() * fMe_cur;
1927
1928 // Compute the velocity of the end-effector from this displacement
1929 velocity = vpExponentialMap::inverse(eMe, time_cur - m_time_prev_getvel);
1930
1931 break;
1932 }
1933
1934 case vpRobot::CAMERA_FRAME: {
1935 // Compute the displacement of the camera since the previous call
1936 cMc = m_fMc_prev_getvel.inverse() * fMc_cur;
1937
1938 // Compute the velocity of the camera from this displacement
1939 velocity = vpExponentialMap::inverse(cMc, time_cur - m_time_prev_getvel);
1940
1941 break;
1942 }
1943
1945 velocity = (q_cur - m_q_prev_getvel) / (time_cur - m_time_prev_getvel);
1946 break;
1947 }
1948
1950 // Compute the displacement of the camera since the previous call
1951 cMc = m_fMc_prev_getvel.inverse() * fMc_cur;
1952
1953 // Compute the velocity of the camera from this displacement
1954 vpColVector v;
1955 v = vpExponentialMap::inverse(cMc, time_cur - m_time_prev_getvel);
1956
1957 // Express this velocity in the reference frame
1958 vpVelocityTwistMatrix fVc(fMc_cur);
1959 velocity = fVc * v;
1960
1961 break;
1962 }
1963
1964 case vpRobot::MIXT_FRAME: {
1965 // Compute the displacement of the camera since the previous call
1966 cMc = m_fMc_prev_getvel.inverse() * fMc_cur;
1967
1968 // Compute the ThetaU representation for the rotation
1969 vpRotationMatrix cRc;
1970 cMc.extract(cRc);
1971 vpThetaUVector thetaU;
1972 thetaU.buildFrom(cRc);
1973
1974 for (unsigned int i = 0; i < 3; i++) {
1975 // Compute the translation displacement in the reference frame
1976 velocity[i] = m_fMc_prev_getvel[i][3] - fMc_cur[i][3];
1977 // Update the rotation displacement in the camera frame
1978 velocity[i + 3] = thetaU[i];
1979 }
1980
1981 // Compute the velocity
1982 velocity /= (time_cur - m_time_prev_getvel);
1983 break;
1984 }
1985 default: {
1987 "vpRobotViper850::getVelocity() not implemented in end-effector"));
1988 }
1989 }
1990 }
1991 else {
1992 m_first_time_getvel = false;
1993 }
1994
1995 // Memorize the end-effector pose for the next call
1996 m_fMe_prev_getvel = fMe_cur;
1997 // Memorize the camera pose for the next call
1998 m_fMc_prev_getvel = fMc_cur;
1999
2000 // Memorize the joint position for the next call
2001 m_q_prev_getvel = q_cur;
2002
2003 // Memorize the time associated to the joint position for the next call
2004 m_time_prev_getvel = time_cur;
2005
2006 CatchPrint();
2007 if (TryStt < 0) {
2008 vpERROR_TRACE("Cannot get velocity.");
2009 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get velocity.");
2010 }
2011}
2012
2022{
2023 double timestamp;
2024 getVelocity(frame, velocity, timestamp);
2025}
2026
2081{
2082 vpColVector velocity;
2083 getVelocity(frame, velocity, timestamp);
2084
2085 return velocity;
2086}
2087
2097{
2098 vpColVector velocity;
2099 double timestamp;
2100 getVelocity(frame, velocity, timestamp);
2101
2102 return velocity;
2103}
2104
2173
2174bool vpRobotViper850::readPosFile(const std::string &filename, vpColVector &q)
2175{
2176 std::ifstream fd(filename.c_str(), std::ios::in);
2177
2178 if (!fd.is_open()) {
2179 return false;
2180 }
2181
2182 std::string line;
2183 std::string key("R:");
2184 std::string id("#Viper850 - Position");
2185 bool pos_found = false;
2186 int lineNum = 0;
2187
2188 q.resize(njoint);
2189
2190 while (std::getline(fd, line)) {
2191 lineNum++;
2192 if (lineNum == 1) {
2193 if (!(line.compare(0, id.size(), id) == 0)) { // check if Viper850 position file
2194 std::cout << "Error: this position file " << filename << " is not for Viper850 robot" << std::endl;
2195 return false;
2196 }
2197 }
2198 if ((line.compare(0, 1, "#") == 0)) { // skip comment
2199 continue;
2200 }
2201 if ((line.compare(0, key.size(), key) == 0)) { // decode position
2202 // check if there are at least njoint values in the line
2203 std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
2204 if (chain.size() < njoint + 1) // try to split with tab separator
2205 chain = vpIoTools::splitChain(line, std::string("\t"));
2206 if (chain.size() < njoint + 1)
2207 continue;
2208
2209 std::istringstream ss(line);
2210 std::string key_;
2211 ss >> key_;
2212 for (unsigned int i = 0; i < njoint; i++)
2213 ss >> q[i];
2214 pos_found = true;
2215 break;
2216 }
2217 }
2218
2219 // converts rotations from degrees into radians
2220 q.deg2rad();
2221
2222 fd.close();
2223
2224 if (!pos_found) {
2225 std::cout << "Error: unable to find a position for Viper850 robot in " << filename << std::endl;
2226 return false;
2227 }
2228
2229 return true;
2230}
2231
2254
2255bool vpRobotViper850::savePosFile(const std::string &filename, const vpColVector &q)
2256{
2257
2258 FILE *fd;
2259 fd = fopen(filename.c_str(), "w");
2260 if (fd == nullptr)
2261 return false;
2262
2263 fprintf(fd, "\
2264#Viper850 - Position - Version 1.00\n\
2265#\n\
2266# R: A B C D E F\n\
2267# Joint position in degrees\n\
2268#\n\
2269#\n\n");
2270
2271 // Save positions in mm and deg
2272 fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n", vpMath::deg(q[0]), vpMath::deg(q[1]), vpMath::deg(q[2]),
2273 vpMath::deg(q[3]), vpMath::deg(q[4]), vpMath::deg(q[5]));
2274
2275 fclose(fd);
2276 return (true);
2277}
2278
2289void vpRobotViper850::move(const std::string &filename)
2290{
2291 vpColVector q;
2292
2293 try {
2294 this->readPosFile(filename, q);
2296 this->setPositioningVelocity(10);
2298 }
2299 catch (...) {
2300 throw;
2301 }
2302}
2303
2323{
2324 displacement.resize(6);
2325 displacement = 0;
2326
2327 double q[6];
2328 vpColVector q_cur(6);
2329 double timestamp;
2330
2331 InitTry;
2332
2333 // Get the current joint position
2334 Try(PrimitiveACQ_POS_Viper850(q, &timestamp));
2335 for (unsigned int i = 0; i < njoint; i++) {
2336 q_cur[i] = q[i];
2337 }
2338
2339 if (!m_first_time_getdis) {
2340 switch (frame) {
2341 case vpRobot::CAMERA_FRAME: {
2342 std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2343 return;
2344 }
2345
2347 displacement = q_cur - m_q_prev_getdis;
2348 break;
2349 }
2350
2352 std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2353 return;
2354 }
2355
2356 case vpRobot::MIXT_FRAME: {
2357 std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2358 return;
2359 }
2361 std::cout << "getDisplacement() END_EFFECTOR_FRAME not implemented\n";
2362 return;
2363 }
2364 }
2365 }
2366 else {
2367 m_first_time_getdis = false;
2368 }
2369
2370 // Memorize the joint position for the next call
2371 m_q_prev_getdis = q_cur;
2372
2373 CatchPrint();
2374 if (TryStt < 0) {
2375 vpERROR_TRACE("Cannot get velocity.");
2376 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get velocity.");
2377 }
2378}
2379
2388{
2389#if defined(USE_ATI_DAQ)
2390#if defined(VISP_HAVE_COMEDI)
2391 m_ati.bias();
2392#else
2393 throw(vpException(vpException::fatalError, "Cannot use ATI F/T if comedi is not installed. Try sudo "
2394 "apt-get install libcomedi-dev"));
2395#endif
2396#else // Use serial link
2397 InitTry;
2398
2399 Try(PrimitiveTFS_BIAS_Viper850());
2400
2401 // Wait 500 ms to be sure the next measures take into account the bias
2402 vpTime::wait(500);
2403
2404 CatchPrint();
2405 if (TryStt < 0) {
2406 vpERROR_TRACE("Cannot bias the force/torque sensor.");
2407 throw vpRobotException(vpRobotException::lowLevelError, "Cannot bias the force/torque sensor.");
2408 }
2409#endif
2410}
2411
2420{
2421#if defined(USE_ATI_DAQ)
2422#if defined(VISP_HAVE_COMEDI)
2423 m_ati.unbias();
2424#else
2425 throw(vpException(vpException::fatalError, "Cannot use ATI F/T if comedi is not installed. Try sudo "
2426 "apt-get install libcomedi-dev"));
2427#endif
2428#else // Use serial link
2429// Not implemented
2430#endif
2431}
2432
2477{
2478#if defined(USE_ATI_DAQ)
2479#if defined(VISP_HAVE_COMEDI)
2480 H = m_ati.getForceTorque();
2481#else
2482 (void)H;
2483 throw(vpException(vpException::fatalError, "Cannot use ATI F/T if comedi is not installed. Try sudo "
2484 "apt-get install libcomedi-dev"));
2485#endif
2486#else // Use serial link
2487 InitTry;
2488
2489 H.resize(6);
2490
2491 Try(PrimitiveTFS_ACQ_Viper850(H.data));
2492
2493 CatchPrint();
2494 if (TryStt < 0) {
2495 vpERROR_TRACE("Cannot get the force/torque measures.");
2496 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get force/torque measures.");
2497 }
2498#endif
2499}
2500
2543{
2544#if defined(USE_ATI_DAQ)
2545#if defined(VISP_HAVE_COMEDI)
2546 vpColVector H = m_ati.getForceTorque();
2547 return H;
2548#else
2549 throw(vpException(vpException::fatalError, "Cannot use ATI F/T if comedi is not installed. Try sudo "
2550 "apt-get install libcomedi-dev"));
2551#endif
2552#else // Use serial link
2553 InitTry;
2554
2555 vpColVector H(6);
2556
2557 Try(PrimitiveTFS_ACQ_Viper850(H.data));
2558 return H;
2559
2560 CatchPrint();
2561 if (TryStt < 0) {
2562 vpERROR_TRACE("Cannot get the force/torque measures.");
2563 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get force/torque measures.");
2564 }
2565 return H; // Here to avoid a warning, but should never be called
2566#endif
2567}
2568
2576{
2577 InitTry;
2578 Try(PrimitivePneumaticGripper_Viper850(1));
2579 std::cout << "Open the pneumatic gripper..." << std::endl;
2580 CatchPrint();
2581 if (TryStt < 0) {
2582 throw vpRobotException(vpRobotException::lowLevelError, "Cannot open the gripper.");
2583 }
2584}
2585
2594{
2595 InitTry;
2596 Try(PrimitivePneumaticGripper_Viper850(0));
2597 std::cout << "Close the pneumatic gripper..." << std::endl;
2598 CatchPrint();
2599 if (TryStt < 0) {
2600 throw vpRobotException(vpRobotException::lowLevelError, "Cannot close the gripper.");
2601 }
2602}
2603
2610{
2611 InitTry;
2612 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper850(0));
2613 std::cout << "Enable joint limits on axis 6..." << std::endl;
2614 CatchPrint();
2615 if (TryStt < 0) {
2616 vpERROR_TRACE("Cannot enable joint limits on axis 6");
2617 throw vpRobotException(vpRobotException::lowLevelError, "Cannot enable joint limits on axis 6.");
2618 }
2619}
2620
2632{
2633 InitTry;
2634 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper850(1));
2635 std::cout << "Warning: Disable joint limits on axis 6..." << std::endl;
2636 CatchPrint();
2637 if (TryStt < 0) {
2638 vpERROR_TRACE("Cannot disable joint limits on axis 6");
2639 throw vpRobotException(vpRobotException::lowLevelError, "Cannot disable joint limits on axis 6.");
2640 }
2641}
2642
2650
2652{
2655
2656 return;
2657}
2658
2678
2680{
2681 maxRotationVelocity_joint6 = w6_max;
2682 return;
2683}
2684
2692double vpRobotViper850::getMaxRotationVelocityJoint6() const { return maxRotationVelocity_joint6; }
2693END_VISP_NAMESPACE
2694#elif !defined(VISP_BUILD_SHARED_LIBS)
2695// Work around to avoid warning: libvisp_robot.a(vpRobotViper850.cpp.o) has
2696// no symbols
2697void dummy_vpRobotViper850() { }
2698#endif
Type * data
Address of the first element of the data array.
Definition vpArray2D.h:149
Implementation of column vector and the associated operations.
vpColVector & rad2deg()
vpColVector & deg2rad()
void resize(unsigned int i, bool flagNullify=true)
error that can be emitted by ViSP classes.
Definition vpException.h:60
@ ioError
I/O error.
Definition vpException.h:67
@ functionNotImplementedError
Function not implemented.
Definition vpException.h:66
@ fatalError
Fatal error.
Definition vpException.h:72
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 bool checkFilename(const std::string &filename)
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.
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.
vpColVector getForceTorque() const
void get_cVe(vpVelocityTwistMatrix &cVe) const
virtual ~vpRobotViper850(void)
static const double m_defaultPositioningVelocity
double getTime() const
bool getPowerState() const
void set_eMc(const vpHomogeneousMatrix &eMc_)
void setMaxRotationVelocity(double w_max)
void closeGripper() const
void setMaxRotationVelocityJoint6(double w6_max)
void disableJoint6Limits() const
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position) VP_OVERRIDE
void enableJoint6Limits() const
@ AUTO
Automatic control mode (default).
@ ESTOP
Emergency stop activated.
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
void get_fJe(vpMatrix &fJe) VP_OVERRIDE
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
double getPositioningVelocity(void) const
static bool readPosFile(const std::string &filename, vpColVector &q)
void setPositioningVelocity(double velocity)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE
void get_cMe(vpHomogeneousMatrix &cMe) const
void move(const std::string &filename)
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
double getMaxRotationVelocityJoint6() const
static bool savePosFile(const std::string &filename, const vpColVector &q)
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
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
double maxRotationVelocity
Definition vpRobot.h:97
void setMaxRotationVelocity(double maxVr)
Definition vpRobot.cpp:259
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 Euler angle minimal representation.
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)
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition vpViper850.h:129
vpCameraParameters::vpCameraParametersProjType projModel
Definition vpViper850.h:168
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition vpViper850.h:120
void init(void)
virtual void set_eMc(const vpHomogeneousMatrix &eMc_)
Definition vpViper.cpp:1250
vpTranslationVector etc
Definition vpViper.h:158
static const unsigned int njoint
Number of joint.
Definition vpViper.h:153
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition vpViper.cpp:942
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition vpViper.cpp:1179
vpColVector joint_max
Definition vpViper.h:171
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
Definition vpViper.cpp:589
vpRxyzVector erc
Definition vpViper.h:159
vpColVector joint_min
Definition vpViper.h:172
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition vpViper.cpp:990
void get_fMe(const vpColVector &q, vpHomogeneousMatrix &fMe) const
Definition vpViper.cpp:745
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition vpViper.cpp:626
#define vpERROR_TRACE
Definition vpDebug.h:423
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT void sleepMs(double t)