Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpRobotViper650.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 S650 robot.
32 */
33
34#include <visp3/core/vpConfig.h>
35
36#ifdef VISP_HAVE_VIPER650
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/vpRobotViper650.h>
51
53/* ---------------------------------------------------------------------- */
54/* --- STATIC ----------------------------------------------------------- */
55/* ---------------------------------------------------------------------- */
56
57bool vpRobotViper650::m_robotAlreadyCreated = false;
58
67
68/* ---------------------------------------------------------------------- */
69/* --- EMERGENCY STOP --------------------------------------------------- */
70/* ---------------------------------------------------------------------- */
71
79void emergencyStopViper650(int signo)
80{
81 std::cout << "Stop the Viper650 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_Viper650();
103 PrimitiveSTOP_Viper650();
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
177vpRobotViper650::vpRobotViper650(bool verbose) : vpViper650(), vpRobot()
178{
179
180 /*
181 #define SIGHUP 1 // hangup
182 #define SIGINT 2 // interrupt (rubout)
183 #define SIGQUIT 3 // quit (ASCII FS)
184 #define SIGILL 4 // illegal instruction (not reset when caught)
185 #define SIGTRAP 5 // trace trap (not reset when caught)
186 #define SIGIOT 6 // IOT instruction
187 #define SIGABRT 6 // used by abort, replace SIGIOT in the future
188 #define SIGEMT 7 // EMT instruction
189 #define SIGFPE 8 // floating point exception
190 #define SIGKILL 9 // kill (cannot be caught or ignored)
191 #define SIGBUS 10 // bus error
192 #define SIGSEGV 11 // segmentation violation
193 #define SIGSYS 12 // bad argument to system call
194 #define SIGPIPE 13 // write on a pipe with no one to read it
195 #define SIGALRM 14 // alarm clock
196 #define SIGTERM 15 // software termination signal from kill
197 */
198
199 signal(SIGINT, emergencyStopViper650);
200 signal(SIGBUS, emergencyStopViper650);
201 signal(SIGSEGV, emergencyStopViper650);
202 signal(SIGKILL, emergencyStopViper650);
203 signal(SIGQUIT, emergencyStopViper650);
204
205 setVerbose(verbose);
206 if (verbose_)
207 std::cout << "Open communication with MotionBlox.\n";
208 try {
209 this->init();
211 }
212 catch (...) {
213 // vpERROR_TRACE("Error caught") ;
214 throw;
215 }
216 m_positioningVelocity = m_defaultPositioningVelocity;
217
218 m_maxRotationVelocity_joint6 = maxRotationVelocity;
219
220 vpRobotViper650::m_robotAlreadyCreated = true;
221
222 return;
223}
224
225/* ------------------------------------------------------------------------ */
226/* --- INITIALISATION ----------------------------------------------------- */
227/* ------------------------------------------------------------------------ */
228
252{
253 InitTry;
254
255 // Initialise private variables used to compute the measured velocities
256 m_q_prev_getvel.resize(6);
257 m_q_prev_getvel = 0;
258 m_time_prev_getvel = 0;
259 m_first_time_getvel = true;
260
261 // Initialise private variables used to compute the measured displacement
262 m_q_prev_getdis.resize(6);
263 m_q_prev_getdis = 0;
264 m_first_time_getdis = true;
265
266 // Initialize the firewire connection
267 Try(InitializeConnection(verbose_));
268
269 // Connect to the servoboard using the servo board GUID
270 Try(InitializeNode_Viper650());
271
272 Try(PrimitiveRESET_Viper650());
273
274 // Enable the joint limits on axis 6
275 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0));
276
277 // Update the eMc matrix in the low level controller
279
280 // Look if the power is on or off
281 UInt32 HIPowerStatus;
282 UInt32 EStopStatus;
283 Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus));
284 CAL_Wait(0.1);
285
286 // Print the robot status
287 if (verbose_) {
288 std::cout << "Robot status: ";
289 switch (EStopStatus) {
290 case ESTOP_AUTO:
291 m_controlMode = AUTO;
292 if (HIPowerStatus == 0)
293 std::cout << "Power is OFF" << std::endl;
294 else
295 std::cout << "Power is ON" << std::endl;
296 break;
297
298 case ESTOP_MANUAL:
299 m_controlMode = MANUAL;
300 if (HIPowerStatus == 0)
301 std::cout << "Power is OFF" << std::endl;
302 else
303 std::cout << "Power is ON" << std::endl;
304 break;
305 case ESTOP_ACTIVATED:
306 m_controlMode = ESTOP;
307 std::cout << "Emergency stop is activated" << std::endl;
308 break;
309 default:
310 std::cout << "Sorry there is an error on the emergency chain." << std::endl;
311 std::cout << "You have to call Adept for maintenance..." << std::endl;
312 // Free allocated resources
313 }
314 std::cout << std::endl;
315 }
316 // get real joint min/max from the MotionBlox
317 Try(PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data));
318 // Convert units from degrees to radians
319 joint_min.deg2rad();
320 joint_max.deg2rad();
321
322 // for (unsigned int i=0; i < njoint; i++) {
323 // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
324 // joint_max[i]);
325 // }
326
327 // If an error occur in the low level controller, goto here
328 // CatchPrint();
329 Catch();
330
331 // Test if an error occurs
332 if (TryStt == -20001)
333 printf("No connection detected. Check if the robot is powered on \n"
334 "and if the firewire link exist between the MotionBlox and this "
335 "computer.\n");
336 else if (TryStt == -675)
337 printf(" Timeout enabling power...\n");
338
339 if (TryStt < 0) {
340 // Power off the robot
341 PrimitivePOWEROFF_Viper650();
342 // Free allocated resources
343 ShutDownConnection();
344
345 std::cout << "Cannot open connection with the motionblox..." << std::endl;
346 throw vpRobotException(vpRobotException::constructionError, "Cannot open connection with the motionblox");
347 }
348 return;
349}
350
412{
413 // Read the robot constants from files
414 // - joint [min,max], coupl_56, long_56
415 // - camera extrinsic parameters relative to eMc
417
418 InitTry;
419
420 // Get real joint min/max from the MotionBlox
421 Try(PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data));
422 // Convert units from degrees to radians
423 joint_min.deg2rad();
424 joint_max.deg2rad();
425
426 // for (unsigned int i=0; i < njoint; i++) {
427 // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
428 // joint_max[i]);
429 // }
430
431 // Set the camera constant (eMc pose) in the MotionBlox
432 double eMc_pose[6];
433 for (unsigned int i = 0; i < 3; i++) {
434 eMc_pose[i] = etc[i]; // translation in meters
435 eMc_pose[i + 3] = erc[i]; // rotation in rad
436 }
437 // Update the eMc pose in the low level controller
438 Try(PrimitiveCONST_Viper650(eMc_pose));
439
440 CatchPrint();
441 return;
442}
443
498void vpRobotViper650::init(vpViper650::vpToolType tool, const std::string &filename)
499{
500 vpViper650::init(tool, filename);
501
502 InitTry;
503
504 // Get real joint min/max from the MotionBlox
505 Try(PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data));
506 // Convert units from degrees to radians
507 joint_min.deg2rad();
508 joint_max.deg2rad();
509
510 // for (unsigned int i=0; i < njoint; i++) {
511 // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
512 // joint_max[i]);
513 // }
514
515 // Set the camera constant (eMc pose) in the MotionBlox
516 double eMc_pose[6];
517 for (unsigned int i = 0; i < 3; i++) {
518 eMc_pose[i] = etc[i]; // translation in meters
519 eMc_pose[i + 3] = erc[i]; // rotation in rad
520 }
521 // Update the eMc pose in the low level controller
522 Try(PrimitiveCONST_Viper650(eMc_pose));
523
524 CatchPrint();
525 return;
526}
527
569{
570 vpViper650::init(tool, eMc_);
571
572 InitTry;
573
574 // Get real joint min/max from the MotionBlox
575 Try(PrimitiveJOINT_MINMAX_Viper650(joint_min.data, joint_max.data));
576 // Convert units from degrees to radians
577 joint_min.deg2rad();
578 joint_max.deg2rad();
579
580 // for (unsigned int i=0; i < njoint; i++) {
581 // printf("axis %d: joint min %lf, max %lf\n", i, joint_min[i],
582 // joint_max[i]);
583 // }
584
585 // Set the camera constant (eMc pose) in the MotionBlox
586 double eMc_pose[6];
587 for (unsigned int i = 0; i < 3; i++) {
588 eMc_pose[i] = etc[i]; // translation in meters
589 eMc_pose[i + 3] = erc[i]; // rotation in rad
590 }
591 // Update the eMc pose in the low level controller
592 Try(PrimitiveCONST_Viper650(eMc_pose));
593
594 CatchPrint();
595 return;
596}
597
610{
611 this->vpViper650::set_eMc(eMc_);
612
613 InitTry;
614
615 // Set the camera constant (eMc pose) in the MotionBlox
616 double eMc_pose[6];
617 for (unsigned int i = 0; i < 3; i++) {
618 eMc_pose[i] = etc[i]; // translation in meters
619 eMc_pose[i + 3] = erc[i]; // rotation in rad
620 }
621 // Update the eMc pose in the low level controller
622 Try(PrimitiveCONST_Viper650(eMc_pose));
623
624 CatchPrint();
625
626 return;
627}
628
642{
643 this->vpViper650::set_eMc(etc_, erc_);
644
645 InitTry;
646
647 // Set the camera constant (eMc pose) in the MotionBlox
648 double eMc_pose[6];
649 for (unsigned int i = 0; i < 3; i++) {
650 eMc_pose[i] = etc[i]; // translation in meters
651 eMc_pose[i + 3] = erc[i]; // rotation in rad
652 }
653 // Update the eMc pose in the low level controller
654 Try(PrimitiveCONST_Viper650(eMc_pose));
655
656 CatchPrint();
657
658 return;
659}
660
661/* ------------------------------------------------------------------------ */
662/* --- DESTRUCTOR --------------------------------------------------------- */
663/* ------------------------------------------------------------------------ */
664
672{
673 InitTry;
674
676
677 // Look if the power is on or off
678 UInt32 HIPowerStatus;
679 Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus));
680 CAL_Wait(0.1);
681
682 // if (HIPowerStatus == 1) {
683 // fprintf(stdout, "Power OFF the robot\n");
684 // fflush(stdout);
685
686 // Try( PrimitivePOWEROFF_Viper650() );
687 // }
688
689 // Free allocated resources
690 ShutDownConnection();
691
692 vpRobotViper650::m_robotAlreadyCreated = false;
693
694 CatchPrint();
695 return;
696}
697
705{
706 InitTry;
707
708 switch (newState) {
709 case vpRobot::STATE_STOP: {
710 // Start primitive STOP only if the current state is Velocity
712 Try(PrimitiveSTOP_Viper650());
713 vpTime::sleepMs(100); // needed to ensure velocity task ends up on low level
714 }
715 break;
716 }
719 std::cout << "Change the control mode from velocity to position control.\n";
720 Try(PrimitiveSTOP_Viper650());
721 }
722 else {
723 // std::cout << "Change the control mode from stop to position
724 // control.\n";
725 }
726 this->powerOn();
727 break;
728 }
731 std::cout << "Change the control mode from stop to velocity control.\n";
732 }
733 this->powerOn();
734 break;
735 }
736 default:
737 break;
738 }
739
740 CatchPrint();
741
742 return vpRobot::setRobotState(newState);
743}
744
745/* ------------------------------------------------------------------------ */
746/* --- STOP --------------------------------------------------------------- */
747/* ------------------------------------------------------------------------ */
748
757{
759 return;
760
761 InitTry;
762 Try(PrimitiveSTOP_Viper650());
764
765 CatchPrint();
766 if (TryStt < 0) {
767 vpERROR_TRACE("Cannot stop robot motion");
768 throw vpRobotException(vpRobotException::lowLevelError, "Cannot stop robot motion.");
769 }
770}
771
782{
783 InitTry;
784
785 // Look if the power is on or off
786 UInt32 HIPowerStatus;
787 UInt32 EStopStatus;
788 bool firsttime = true;
789 unsigned int nitermax = 10;
790
791 for (unsigned int i = 0; i < nitermax; i++) {
792 Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, &EStopStatus, nullptr, nullptr, nullptr, &HIPowerStatus));
793 if (EStopStatus == ESTOP_AUTO) {
794 m_controlMode = AUTO;
795 break; // exit for loop
796 }
797 else if (EStopStatus == ESTOP_MANUAL) {
798 m_controlMode = MANUAL;
799 break; // exit for loop
800 }
801 else if (EStopStatus == ESTOP_ACTIVATED) {
802 m_controlMode = ESTOP;
803 if (firsttime) {
804 std::cout << "Emergency stop is activated! \n"
805 << "Check the emergency stop button and push the yellow "
806 "button before continuing."
807 << std::endl;
808 firsttime = false;
809 }
810 fprintf(stdout, "Remaining time %us \r", nitermax - i);
811 fflush(stdout);
812 CAL_Wait(1);
813 }
814 else {
815 std::cout << "Sorry there is an error on the emergency chain." << std::endl;
816 std::cout << "You have to call Adept for maintenance..." << std::endl;
817 // Free allocated resources
818 ShutDownConnection();
819 throw(vpRobotException(vpRobotException::lowLevelError, "Error on the emergency chain"));
820 }
821 }
822
823 if (EStopStatus == ESTOP_ACTIVATED)
824 std::cout << std::endl;
825
826 if (EStopStatus == ESTOP_ACTIVATED) {
827 std::cout << "Sorry, cannot power on the robot." << std::endl;
828 throw(vpRobotException(vpRobotException::lowLevelError, "Cannot power on the robot."));
829 }
830
831 if (HIPowerStatus == 0) {
832 fprintf(stdout, "Power ON the Viper650 robot\n");
833 fflush(stdout);
834
835 Try(PrimitivePOWERON_Viper650());
836 }
837
838 CatchPrint();
839 if (TryStt < 0) {
840 vpERROR_TRACE("Cannot power on the robot");
841 throw(vpRobotException(vpRobotException::lowLevelError, "Cannot power off the robot."));
842 }
843}
844
855{
856 InitTry;
857
858 // Look if the power is on or off
859 UInt32 HIPowerStatus;
860 Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus));
861 CAL_Wait(0.1);
862
863 if (HIPowerStatus == 1) {
864 fprintf(stdout, "Power OFF the Viper650 robot\n");
865 fflush(stdout);
866
867 Try(PrimitivePOWEROFF_Viper650());
868 }
869
870 CatchPrint();
871 if (TryStt < 0) {
872 vpERROR_TRACE("Cannot power off the robot");
873 throw vpRobotException(vpRobotException::lowLevelError, "Cannot power off the robot.");
874 }
875}
876
889{
890 InitTry;
891 bool status = false;
892 // Look if the power is on or off
893 UInt32 HIPowerStatus;
894 Try(PrimitiveSTATUS_Viper650(nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, &HIPowerStatus));
895 CAL_Wait(0.1);
896
897 if (HIPowerStatus == 1) {
898 status = true;
899 }
900
901 CatchPrint();
902 if (TryStt < 0) {
903 vpERROR_TRACE("Cannot get the power status");
904 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get the power status.");
905 }
906 return status;
907}
908
919{
922
923 cVe.buildFrom(cMe);
924}
925
938
951{
952
953 double position[6];
954 double timestamp;
955
956 InitTry;
957 Try(PrimitiveACQ_POS_J_Viper650(position, &timestamp));
958 CatchPrint();
959
960 vpColVector q(6);
961 for (unsigned int i = 0; i < njoint; i++)
962 q[i] = vpMath::rad(position[i]);
963
964 try {
966 }
967 catch (...) {
968 vpERROR_TRACE("catch exception ");
969 throw;
970 }
971}
972
983
985{
986
987 double position[6];
988 double timestamp;
989
990 InitTry;
991 Try(PrimitiveACQ_POS_Viper650(position, &timestamp));
992 CatchPrint();
993
994 vpColVector q(6);
995 for (unsigned int i = 0; i < njoint; i++)
996 q[i] = position[i];
997
998 try {
1000 }
1001 catch (...) {
1002 vpERROR_TRACE("Error caught");
1003 throw;
1004 }
1005}
1006
1047void vpRobotViper650::setPositioningVelocity(double velocity) { m_positioningVelocity = velocity; }
1048
1054double vpRobotViper650::getPositioningVelocity(void) const { return m_positioningVelocity; }
1055
1137{
1138
1140 vpERROR_TRACE("Robot was not in position-based control\n"
1141 "Modification of the robot state");
1143 }
1144
1145 vpColVector destination(njoint);
1146 int error = 0;
1147 double timestamp;
1148
1149 InitTry;
1150 switch (frame) {
1151 case vpRobot::CAMERA_FRAME: {
1153 Try(PrimitiveACQ_POS_Viper650(q.data, &timestamp));
1154
1155 // Convert degrees into rad
1156 q.deg2rad();
1157
1158 // Get fMc from the inverse kinematics
1160 vpViper650::get_fMc(q, fMc);
1161
1162 // Set cMc from the input position
1164 vpRxyzVector rxyz;
1165 for (unsigned int i = 0; i < 3; i++) {
1166 txyz[i] = position[i];
1167 rxyz[i] = position[i + 3];
1168 }
1169
1170 // Compute cMc2
1171 vpRotationMatrix cRc2(rxyz);
1172 vpHomogeneousMatrix cMc2(txyz, cRc2);
1173
1174 // Compute the new position to reach: fMc*cMc2
1175 vpHomogeneousMatrix fMc2 = fMc * cMc2;
1176
1177 // Compute the corresponding joint position from the inverse kinematics
1178 unsigned int solution = this->getInverseKinematics(fMc2, q);
1179 if (solution) { // Position is reachable
1180 destination = q;
1181 // convert rad to deg requested for the low level controller
1182 destination.rad2deg();
1183 Try(PrimitiveMOVE_J_Viper650(destination.data, m_positioningVelocity));
1184 Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1185 }
1186 else {
1187 // Cartesian position is out of range
1188 error = -1;
1189 }
1190
1191 break;
1192 }
1194 destination = position;
1195 // convert rad to deg requested for the low level controller
1196 destination.rad2deg();
1197
1198 // std::cout << "Joint destination (deg): " << destination.t() <<
1199 // std::endl;
1200 Try(PrimitiveMOVE_J_Viper650(destination.data, m_positioningVelocity));
1201 Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1202 break;
1203 }
1205 // Convert angles from Rxyz representation to Rzyz representation
1206 vpRxyzVector rxyz(position[3], position[4], position[5]);
1207 vpRotationMatrix R(rxyz);
1208 vpRzyzVector rzyz(R);
1209
1210 for (unsigned int i = 0; i < 3; i++) {
1211 destination[i] = position[i];
1212 destination[i + 3] = vpMath::deg(rzyz[i]); // convert also angles in deg
1213 }
1214 int configuration = 0; // keep the actual configuration
1215
1216 // std::cout << "Base frame destination Rzyz (deg): " << destination.t()
1217 // << std::endl;
1218 Try(PrimitiveMOVE_C_Viper650(destination.data, configuration, m_positioningVelocity));
1219 Try(WaitState_Viper650(ETAT_ATTENTE_VIPER650, 1000));
1220
1221 break;
1222 }
1223 case vpRobot::MIXT_FRAME: {
1224 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1225 "Mixt frame not implemented.");
1226 }
1228 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1229 "Mixt frame not implemented.");
1230 }
1231 }
1232
1233 CatchPrint();
1234 if (TryStt == InvalidPosition || TryStt == -1023)
1235 std::cout << " : Position out of range.\n";
1236
1237 else if (TryStt == -3019) {
1238 if (frame == vpRobot::ARTICULAR_FRAME)
1239 std::cout << " : Joint position out of range.\n";
1240 else
1241 std::cout << " : Cartesian position leads to a joint position out of "
1242 "range.\n";
1243 }
1244 else if (TryStt < 0)
1245 std::cout << " : Unknown error (see Fabien).\n";
1246 else if (error == -1)
1247 std::cout << "Position out of range.\n";
1248
1249 if (TryStt < 0 || error < 0) {
1250 vpERROR_TRACE("Positioning error.");
1251 throw vpRobotException(vpRobotException::positionOutOfRangeError, "Position out of range.");
1252 }
1253
1254 return;
1255}
1256
1325void vpRobotViper650::setPosition(const vpRobot::vpControlFrameType frame, double pos1, double pos2, double pos3,
1326 double pos4, double pos5, double pos6)
1327{
1328 try {
1329 vpColVector position(6);
1330 position[0] = pos1;
1331 position[1] = pos2;
1332 position[2] = pos3;
1333 position[3] = pos4;
1334 position[4] = pos5;
1335 position[5] = pos6;
1336
1337 setPosition(frame, position);
1338 }
1339 catch (...) {
1340 vpERROR_TRACE("Error caught");
1341 throw;
1342 }
1343}
1344
1387void vpRobotViper650::setPosition(const std::string &filename)
1388{
1389 vpColVector q;
1390 bool ret;
1391
1392 ret = this->readPosFile(filename, q);
1393
1394 if (ret == false) {
1395 vpERROR_TRACE("Bad position in \"%s\"", filename.c_str());
1396 throw vpRobotException(vpRobotException::lowLevelError, "Bad position in filename.");
1397 }
1400}
1401
1473void vpRobotViper650::getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position, double &timestamp)
1474{
1475
1476 InitTry;
1477
1478 position.resize(6);
1479
1480 switch (frame) {
1481 case vpRobot::CAMERA_FRAME: {
1482 position = 0;
1483 return;
1484 }
1486 Try(PrimitiveACQ_POS_J_Viper650(position.data, &timestamp));
1487 // vpCTRACE << "Get joint position (deg)" << position.t() << std::endl;
1488 position.deg2rad();
1489
1490 return;
1491 }
1494 Try(PrimitiveACQ_POS_J_Viper650(q.data, &timestamp));
1495
1496 // Compute fMc
1498
1499 // From fMc extract the pose
1500 vpRotationMatrix fRc;
1501 fMc.extract(fRc);
1502 vpRxyzVector rxyz;
1503 rxyz.buildFrom(fRc);
1504
1505 for (unsigned int i = 0; i < 3; i++) {
1506 position[i] = fMc[i][3]; // translation x,y,z
1507 position[i + 3] = rxyz[i]; // Euler rotation x,y,z
1508 }
1509
1510 break;
1511 }
1512 case vpRobot::MIXT_FRAME: {
1513 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in mixt frame: "
1514 "not implemented");
1515 }
1517 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position in end-effector frame: "
1518 "not implemented");
1519 }
1520 }
1521
1522 CatchPrint();
1523 if (TryStt < 0) {
1524 vpERROR_TRACE("Cannot get position.");
1525 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get position.");
1526 }
1527
1528 return;
1529}
1530
1542{
1543 double timestamp;
1544 getPosition(frame, position, timestamp);
1545}
1546
1560void vpRobotViper650::getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position, double &timestamp)
1561{
1562 vpColVector posRxyz;
1563 // recupere position en Rxyz
1564 this->getPosition(frame, posRxyz, timestamp);
1565 vpRxyzVector RxyzVect;
1566 for (unsigned int j = 0; j < 3; j++)
1567 RxyzVect[j] = posRxyz[j + 3];
1568 // recupere le vecteur thetaU correspondant
1569 vpThetaUVector RtuVect(RxyzVect);
1570
1571 // remplit le vpPoseVector avec translation et rotation ThetaU
1572 for (unsigned int j = 0; j < 3; j++) {
1573 position[j] = posRxyz[j];
1574 position[j + 3] = RtuVect[j];
1575 }
1576}
1577
1589{
1590 double timestamp;
1591 getPosition(frame, position, timestamp);
1592}
1593
1599{
1600 double timestamp;
1601 PrimitiveACQ_TIME_Viper650(&timestamp);
1602 return timestamp;
1603}
1604
1687{
1689 vpERROR_TRACE("Cannot send a velocity to the robot "
1690 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1692 "Cannot send a velocity to the robot "
1693 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
1694 }
1695
1696 vpColVector vel_sat(6);
1697
1698 // Velocity saturation
1699 switch (frame) {
1700 // saturation in cartesian space
1704 case vpRobot::MIXT_FRAME: {
1705 vpColVector vel_max(6);
1706
1707 for (unsigned int i = 0; i < 3; i++)
1708 vel_max[i] = getMaxTranslationVelocity();
1709 for (unsigned int i = 3; i < 6; i++)
1710 vel_max[i] = getMaxRotationVelocity();
1711
1712 vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1713
1714 break;
1715 }
1716 // saturation in joint space
1718 vpColVector vel_max(6);
1719
1720 // if (getMaxRotationVelocity() == getMaxRotationVelocityJoint6()) {
1721 if (std::fabs(getMaxRotationVelocity() - getMaxRotationVelocityJoint6()) < std::numeric_limits<double>::epsilon()) {
1722 for (unsigned int i = 0; i < 6; i++)
1723 vel_max[i] = getMaxRotationVelocity();
1724 }
1725 else {
1726 for (unsigned int i = 0; i < 5; i++)
1727 vel_max[i] = getMaxRotationVelocity();
1728 vel_max[5] = getMaxRotationVelocityJoint6();
1729 }
1730
1731 vel_sat = vpRobot::saturateVelocities(vel, vel_max, true);
1732 }
1733 }
1734
1735 InitTry;
1736
1737 switch (frame) {
1738 case vpRobot::CAMERA_FRAME: {
1739 // Send velocities in m/s and rad/s
1740 // std::cout << "Vitesse cam appliquee: " << vel_sat.t();
1741 Try(PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPCAM_VIPER650));
1742 break;
1743 }
1745 // Transform in camera frame
1747 this->get_cMe(cMe);
1748 vpVelocityTwistMatrix cVe(cMe);
1749 vpColVector v_c = cVe * vel_sat;
1750 // Send velocities in m/s and rad/s
1751 Try(PrimitiveMOVESPEED_CART_Viper650(v_c.data, REPCAM_VIPER650));
1752 break;
1753 }
1755 // Convert all the velocities from rad/s into deg/s
1756 vel_sat.rad2deg();
1757 // std::cout << "Vitesse appliquee: " << vel_sat.t();
1758 // Try( PrimitiveMOVESPEED_CART(vel_sat.data, REPART_VIPER650) );
1759 Try(PrimitiveMOVESPEED_Viper650(vel_sat.data));
1760 break;
1761 }
1763 // Send velocities in m/s and rad/s
1764 // std::cout << "Vitesse ref appliquee: " << vel_sat.t();
1765 Try(PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPFIX_VIPER650));
1766 break;
1767 }
1768 case vpRobot::MIXT_FRAME: {
1769 // Try( PrimitiveMOVESPEED_CART_Viper650(vel_sat.data, REPMIX_VIPER650) );
1770 break;
1771 }
1772 default: {
1773 vpERROR_TRACE("Error in spec of vpRobot. "
1774 "Case not taken in account.");
1775 return;
1776 }
1777 }
1778
1779 Catch();
1780 if (TryStt < 0) {
1781 if (TryStt == VelStopOnJoint) {
1782 UInt32 axisInJoint[njoint];
1783 PrimitiveSTATUS_Viper650(nullptr, nullptr, nullptr, nullptr, nullptr, axisInJoint, nullptr);
1784 for (unsigned int i = 0; i < njoint; i++) {
1785 if (axisInJoint[i])
1786 std::cout << "\nWarning: Velocity control stopped: axis " << i + 1 << " on joint limit!" << std::endl;
1787 }
1788 }
1789 else {
1790 printf("\n%s(%d): Error %d", __FUNCTION__, TryLine, TryStt);
1791 if (TryString != nullptr) {
1792 // The statement is in TryString, but we need to check the validity
1793 printf(" Error sentence %s\n", TryString); // Print the TryString
1794 }
1795 else {
1796 printf("\n");
1797 }
1798 }
1799 }
1800
1801 return;
1802}
1803
1804/* ------------------------------------------------------------------------ */
1805/* --- GET ---------------------------------------------------------------- */
1806/* ------------------------------------------------------------------------ */
1807
1868void vpRobotViper650::getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity, double &timestamp)
1869{
1870 velocity.resize(6);
1871 velocity = 0;
1872
1873 vpColVector q_cur(6);
1874 vpHomogeneousMatrix fMe_cur, fMc_cur;
1875 vpHomogeneousMatrix eMe, cMc; // camera displacement
1876 double time_cur;
1877
1878 InitTry;
1879
1880 // Get the current joint position
1881 Try(PrimitiveACQ_POS_J_Viper650(q_cur.data, &timestamp));
1882 time_cur = timestamp;
1883 q_cur.deg2rad();
1884
1885 // Get the end-effector pose from the direct kinematics
1886 vpViper650::get_fMe(q_cur, fMe_cur);
1887 // Get the camera pose from the direct kinematics
1888 vpViper650::get_fMc(q_cur, fMc_cur);
1889
1890 if (!m_first_time_getvel) {
1891
1892 switch (frame) {
1894 // Compute the displacement of the end-effector since the previous call
1895 eMe = m_fMe_prev_getvel.inverse() * fMe_cur;
1896
1897 // Compute the velocity of the end-effector from this displacement
1898 velocity = vpExponentialMap::inverse(eMe, time_cur - m_time_prev_getvel);
1899
1900 break;
1901 }
1902
1903 case vpRobot::CAMERA_FRAME: {
1904 // Compute the displacement of the camera since the previous call
1905 cMc = m_fMc_prev_getvel.inverse() * fMc_cur;
1906
1907 // Compute the velocity of the camera from this displacement
1908 velocity = vpExponentialMap::inverse(cMc, time_cur - m_time_prev_getvel);
1909
1910 break;
1911 }
1912
1914 velocity = (q_cur - m_q_prev_getvel) / (time_cur - m_time_prev_getvel);
1915 break;
1916 }
1917
1919 // Compute the displacement of the camera since the previous call
1920 cMc = m_fMc_prev_getvel.inverse() * fMc_cur;
1921
1922 // Compute the velocity of the camera from this displacement
1923 vpColVector v;
1924 v = vpExponentialMap::inverse(cMc, time_cur - m_time_prev_getvel);
1925
1926 // Express this velocity in the reference frame
1927 vpVelocityTwistMatrix fVc(fMc_cur);
1928 velocity = fVc * v;
1929
1930 break;
1931 }
1932
1933 case vpRobot::MIXT_FRAME: {
1934 // Compute the displacement of the camera since the previous call
1935 cMc = m_fMc_prev_getvel.inverse() * fMc_cur;
1936
1937 // Compute the ThetaU representation for the rotation
1938 vpRotationMatrix cRc;
1939 cMc.extract(cRc);
1940 vpThetaUVector thetaU;
1941 thetaU.buildFrom(cRc);
1942
1943 for (unsigned int i = 0; i < 3; i++) {
1944 // Compute the translation displacement in the reference frame
1945 velocity[i] = m_fMc_prev_getvel[i][3] - fMc_cur[i][3];
1946 // Update the rotation displacement in the camera frame
1947 velocity[i + 3] = thetaU[i];
1948 }
1949
1950 // Compute the velocity
1951 velocity /= (time_cur - m_time_prev_getvel);
1952 break;
1953 }
1954 default: {
1956 "vpRobotViper650::getVelocity() not implemented in end-effector"));
1957 }
1958 }
1959 }
1960 else {
1961 m_first_time_getvel = false;
1962 }
1963
1964 // Memorize the end-effector pose for the next call
1965 m_fMe_prev_getvel = fMe_cur;
1966 // Memorize the camera pose for the next call
1967 m_fMc_prev_getvel = fMc_cur;
1968
1969 // Memorize the joint position for the next call
1970 m_q_prev_getvel = q_cur;
1971
1972 // Memorize the time associated to the joint position for the next call
1973 m_time_prev_getvel = time_cur;
1974
1975 CatchPrint();
1976 if (TryStt < 0) {
1977 vpERROR_TRACE("Cannot get velocity.");
1978 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get velocity.");
1979 }
1980}
1981
1991{
1992 double timestamp;
1993 getVelocity(frame, velocity, timestamp);
1994}
1995
2050{
2051 vpColVector velocity;
2052 getVelocity(frame, velocity, timestamp);
2053
2054 return velocity;
2055}
2056
2066{
2067 vpColVector velocity;
2068 double timestamp;
2069 getVelocity(frame, velocity, timestamp);
2070
2071 return velocity;
2072}
2073
2142
2143bool vpRobotViper650::readPosFile(const std::string &filename, vpColVector &q)
2144{
2145 std::ifstream fd(filename.c_str(), std::ios::in);
2146
2147 if (!fd.is_open()) {
2148 return false;
2149 }
2150
2151 std::string line;
2152 std::string key("R:");
2153 std::string id("#Viper650 - Position");
2154 bool pos_found = false;
2155 int lineNum = 0;
2156
2157 q.resize(njoint);
2158
2159 while (std::getline(fd, line)) {
2160 lineNum++;
2161 if (lineNum == 1) {
2162 if (!(line.compare(0, id.size(), id) == 0)) { // check if Viper650 position file
2163 std::cout << "Error: this position file " << filename << " is not for Viper650 robot" << std::endl;
2164 return false;
2165 }
2166 }
2167 if ((line.compare(0, 1, "#") == 0)) { // skip comment
2168 continue;
2169 }
2170 if ((line.compare(0, key.size(), key) == 0)) { // decode position
2171 // check if there are at least njoint values in the line
2172 std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
2173 if (chain.size() < njoint + 1) // try to split with tab separator
2174 chain = vpIoTools::splitChain(line, std::string("\t"));
2175 if (chain.size() < njoint + 1)
2176 continue;
2177
2178 std::istringstream ss(line);
2179 std::string key_;
2180 ss >> key_;
2181 for (unsigned int i = 0; i < njoint; i++)
2182 ss >> q[i];
2183 pos_found = true;
2184 break;
2185 }
2186 }
2187
2188 // converts rotations from degrees into radians
2189 q.deg2rad();
2190
2191 fd.close();
2192
2193 if (!pos_found) {
2194 std::cout << "Error: unable to find a position for Viper650 robot in " << filename << std::endl;
2195 return false;
2196 }
2197
2198 return true;
2199}
2200
2223
2224bool vpRobotViper650::savePosFile(const std::string &filename, const vpColVector &q)
2225{
2226
2227 FILE *fd;
2228 fd = fopen(filename.c_str(), "w");
2229 if (fd == nullptr)
2230 return false;
2231
2232 fprintf(fd, "\
2233#Viper650 - Position - Version 1.00\n\
2234#\n\
2235# R: A B C D E F\n\
2236# Joint position in degrees\n\
2237#\n\
2238#\n\n");
2239
2240 // Save positions in mm and deg
2241 fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n", vpMath::deg(q[0]), vpMath::deg(q[1]), vpMath::deg(q[2]),
2242 vpMath::deg(q[3]), vpMath::deg(q[4]), vpMath::deg(q[5]));
2243
2244 fclose(fd);
2245 return (true);
2246}
2247
2258void vpRobotViper650::move(const std::string &filename)
2259{
2260 vpColVector q;
2261
2262 try {
2263 this->readPosFile(filename, q);
2265 this->setPositioningVelocity(10);
2267 }
2268 catch (...) {
2269 throw;
2270 }
2271}
2272
2292{
2293 displacement.resize(6);
2294 displacement = 0;
2295
2296 double q[6];
2297 vpColVector q_cur(6);
2298 double timestamp;
2299
2300 InitTry;
2301
2302 // Get the current joint position
2303 Try(PrimitiveACQ_POS_Viper650(q, &timestamp));
2304 for (unsigned int i = 0; i < njoint; i++) {
2305 q_cur[i] = q[i];
2306 }
2307
2308 if (!m_first_time_getdis) {
2309 switch (frame) {
2310 case vpRobot::CAMERA_FRAME: {
2311 std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
2312 return;
2313 }
2314
2316 displacement = q_cur - m_q_prev_getdis;
2317 break;
2318 }
2319
2321 std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
2322 return;
2323 }
2324
2325 case vpRobot::MIXT_FRAME: {
2326 std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
2327 return;
2328 }
2330 std::cout << "getDisplacement() END_EFFECTOR_FRAME not implemented\n";
2331 return;
2332 }
2333 }
2334 }
2335 else {
2336 m_first_time_getdis = false;
2337 }
2338
2339 // Memorize the joint position for the next call
2340 m_q_prev_getdis = q_cur;
2341
2342 CatchPrint();
2343 if (TryStt < 0) {
2344 vpERROR_TRACE("Cannot get velocity.");
2345 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get velocity.");
2346 }
2347}
2348
2363{
2364 InitTry;
2365
2366 Try(PrimitiveTFS_BIAS_Viper650());
2367
2368 // Wait 500 ms to be sure the next measures take into account the bias
2369 vpTime::wait(500);
2370
2371 CatchPrint();
2372 if (TryStt < 0) {
2373 vpERROR_TRACE("Cannot bias the force/torque sensor.");
2374 throw vpRobotException(vpRobotException::lowLevelError, "Cannot bias the force/torque sensor.");
2375 }
2376}
2377
2421{
2422 InitTry;
2423
2424 H.resize(6);
2425
2426 Try(PrimitiveTFS_ACQ_Viper650(H.data));
2427
2428 CatchPrint();
2429 if (TryStt < 0) {
2430 vpERROR_TRACE("Cannot get the force/torque measures.");
2431 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get force/torque measures.");
2432 }
2433}
2434
2476{
2477 InitTry;
2478
2479 vpColVector H(6);
2480
2481 Try(PrimitiveTFS_ACQ_Viper650(H.data));
2482
2483 return H;
2484
2485 CatchPrint();
2486 if (TryStt < 0) {
2487 vpERROR_TRACE("Cannot get the force/torque measures.");
2488 throw vpRobotException(vpRobotException::lowLevelError, "Cannot get force/torque measures.");
2489 }
2490 return H; // Here to avoid a warning, but should never be called
2491}
2492
2499{
2500 InitTry;
2501 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(0));
2502 std::cout << "Enable joint limits on axis 6..." << std::endl;
2503 CatchPrint();
2504 if (TryStt < 0) {
2505 vpERROR_TRACE("Cannot enable joint limits on axis 6");
2506 throw vpRobotException(vpRobotException::lowLevelError, "Cannot enable joint limits on axis 6.");
2507 }
2508}
2509
2521{
2522 InitTry;
2523 Try(PrimitiveREMOVE_JOINT6_LIMITS_Viper650(1));
2524 std::cout << "Warning: Disable joint limits on axis 6..." << std::endl;
2525 CatchPrint();
2526 if (TryStt < 0) {
2527 vpERROR_TRACE("Cannot disable joint limits on axis 6");
2528 throw vpRobotException(vpRobotException::lowLevelError, "Cannot disable joint limits on axis 6.");
2529 }
2530}
2531
2539
2541{
2544
2545 return;
2546}
2547
2566
2568{
2569 m_maxRotationVelocity_joint6 = w6_max;
2570 return;
2571}
2572
2580double vpRobotViper650::getMaxRotationVelocityJoint6() const { return m_maxRotationVelocity_joint6; }
2581
2589{
2590 InitTry;
2591 Try(PrimitivePneumaticGripper_Viper650(1));
2592 std::cout << "Open the pneumatic gripper..." << std::endl;
2593 CatchPrint();
2594 if (TryStt < 0) {
2595 throw vpRobotException(vpRobotException::lowLevelError, "Cannot open the gripper.");
2596 }
2597}
2598
2607{
2608 InitTry;
2609 Try(PrimitivePneumaticGripper_Viper650(0));
2610 std::cout << "Close the pneumatic gripper..." << std::endl;
2611 CatchPrint();
2612 if (TryStt < 0) {
2613 throw vpRobotException(vpRobotException::lowLevelError, "Cannot close the gripper.");
2614 }
2615}
2616END_VISP_NAMESPACE
2617#elif !defined(VISP_BUILD_SHARED_LIBS)
2618// Work around to avoid warning: libvisp_robot.a(vpRobotViper650.cpp.o) has
2619// no symbols
2620void dummy_vpRobotViper650() { }
2621#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
@ 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.
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.
void move(const std::string &filename)
void set_eMc(const vpHomogeneousMatrix &eMc_)
void get_fJe(vpMatrix &fJe) VP_OVERRIDE
static bool savePosFile(const std::string &filename, const vpColVector &q)
static const double m_defaultPositioningVelocity
virtual ~vpRobotViper650(void)
void getDisplacement(vpRobot::vpControlFrameType frame, vpColVector &displacement)
void setPositioningVelocity(double velocity)
void enableJoint6Limits() const
void get_cVe(vpVelocityTwistMatrix &cVe) const
vpColVector getForceTorque() const
bool getPowerState() const
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
void setMaxRotationVelocityJoint6(double w6_max)
void disableJoint6Limits() const
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &position) VP_OVERRIDE
void biasForceTorqueSensor() const
void get_cMe(vpHomogeneousMatrix &cMe) const
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
@ AUTO
Automatic control mode (default).
@ ESTOP
Emergency stop activated.
double getMaxRotationVelocityJoint6() const
void setMaxRotationVelocity(double w_max)
double getTime() const
static bool readPosFile(const std::string &filename, vpColVector &q)
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE
double getPositioningVelocity(void) const
void closeGripper() const
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &velocity)
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)
vpCameraParameters::vpCameraParametersProjType projModel
Definition vpViper650.h:168
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition vpViper650.h:129
void init(void)
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition vpViper650.h:120
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)