Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpSimulatorViper850.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 * Class which provides a simulator for the robot Viper850.
32 */
33
34#include <visp3/robot/vpSimulatorViper850.h>
35
36#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS)
37
38#include <cmath> // std::fabs
39#include <limits> // numeric_limits
40#include <string>
41#include <visp3/core/vpDebug.h>
42#include <visp3/core/vpImagePoint.h>
43#include <visp3/core/vpIoTools.h>
44#include <visp3/core/vpMeterPixelConversion.h>
45#include <visp3/core/vpPoint.h>
46#include <visp3/core/vpTime.h>
47
48#include "../wireframe-simulator/vpBound.h"
49#include "../wireframe-simulator/vpRfstack.h"
50#include "../wireframe-simulator/vpScene.h"
51#include "../wireframe-simulator/vpVwstack.h"
52
55
60 : vpRobotWireFrameSimulator(), vpViper850(), q_prev_getdis(), first_time_getdis(true),
61 positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir()
62{
63 init();
65
67
68 m_thread = new std::thread(&launcher, std::ref(*this));
69
71}
72
80 : vpRobotWireFrameSimulator(do_display), q_prev_getdis(), first_time_getdis(true),
81 positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir()
82{
83 init();
85
87
88 m_thread = new std::thread(&launcher, std::ref(*this));
89
91}
92
97{
98 m_mutex_robotStop.lock();
99 robotStop = true;
100 m_mutex_robotStop.unlock();
101
102 m_thread->join();
103
104 if (robotArms != nullptr) {
105 // free_Bound_scene (&(camera));
106 for (int i = 0; i < 6; i++)
107 free_Bound_scene(&(robotArms[i]));
108 }
109
110 delete[] robotArms;
111 delete[] fMi;
112 delete m_thread;
113}
114
124{
125 // set arm_dir from #define VISP_ROBOT_ARMS_DIR if it exists
126 // VISP_ROBOT_ARMS_DIR may contain multiple locations separated by ";"
127 std::vector<std::string> arm_dirs = vpIoTools::splitChain(std::string(VISP_ROBOT_ARMS_DIR), std::string(";"));
128 bool armDirExists = false;
129 for (size_t i = 0; i < arm_dirs.size(); i++)
130 if (vpIoTools::checkDirectory(arm_dirs[i]) == true) { // directory exists
131 arm_dir = arm_dirs[i];
132 armDirExists = true;
133 break;
134 }
135 if (!armDirExists) {
136 try {
137 arm_dir = vpIoTools::getenv("VISP_ROBOT_ARMS_DIR");
138 std::cout << "The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl;
139 }
140 catch (...) {
141 std::cout << "Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl;
142 }
143 }
144
146 toolCustom = false;
147
148 size_fMi = 8;
149 fMi = new vpHomogeneousMatrix[8];
150 artCoord.resize(njoint);
151 artVel.resize(njoint);
152
153 zeroPos.resize(njoint);
154 zeroPos = 0;
155 zeroPos[1] = -M_PI / 2;
156 zeroPos[2] = M_PI;
157 reposPos.resize(njoint);
158 reposPos = 0;
159 reposPos[1] = -M_PI / 2;
160 reposPos[2] = M_PI;
161 reposPos[4] = M_PI / 2;
162
163 artCoord = reposPos;
164 artVel = 0;
165
166 q_prev_getdis.resize(njoint);
167 q_prev_getdis = 0;
168 first_time_getdis = true;
169
170 positioningVelocity = defaultPositioningVelocity;
171
174
175 // Software joint limits in radians
176 // joint_min.resize(njoint);
177 joint_min[0] = vpMath::rad(-50);
178 joint_min[1] = vpMath::rad(-135);
179 joint_min[2] = vpMath::rad(-40);
180 joint_min[3] = vpMath::rad(-190);
181 joint_min[4] = vpMath::rad(-110);
182 joint_min[5] = vpMath::rad(-184);
183 // joint_max.resize(njoint);
184 joint_max[0] = vpMath::rad(50);
185 joint_max[1] = vpMath::rad(-40);
186 joint_max[2] = vpMath::rad(215);
187 joint_max[3] = vpMath::rad(190);
188 joint_max[4] = vpMath::rad(110);
189 joint_max[5] = vpMath::rad(184);
190}
191
196{
197 robotArms = nullptr;
198 robotArms = new Bound_scene[6];
199 initArms();
201 cameraParam.initPersProjWithoutDistortion(558.5309599, 556.055053, 320, 240);
204 getCameraParameters(tmp, 640, 480);
205 px_int = tmp.get_px();
206 py_int = tmp.get_py();
207 sceneInitialized = true;
208}
209
226{
227 this->projModel = proj_model;
228
229 // Use here default values of the robot constant parameters.
230 switch (tool) {
232 erc[0] = vpMath::rad(0.07); // rx
233 erc[1] = vpMath::rad(2.76); // ry
234 erc[2] = vpMath::rad(-91.50); // rz
235 etc[0] = -0.0453; // tx
236 etc[1] = 0.0005; // ty
237 etc[2] = 0.0728; // tz
238
239 setCameraParameters(vpCameraParameters(1232.0, 1233.0, 320, 240));
240 break;
241 }
243 erc[0] = vpMath::rad(0.1527764261); // rx
244 erc[1] = vpMath::rad(1.285092455); // ry
245 erc[2] = vpMath::rad(-90.75777848); // rz
246 etc[0] = -0.04558630174; // tx
247 etc[1] = -0.00134326752; // ty
248 etc[2] = 0.001000828017; // tz
249
250 setCameraParameters(vpCameraParameters(868.0, 869.0, 320, 240));
251 break;
252 }
256 std::cout << "This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
257 break;
258 }
259 }
260
262
263 m_mutex_eMc.lock();
264 this->eMc.buildFrom(etc, eRc);
265 m_mutex_eMc.unlock();
266
267 setToolType(tool);
268 return;
269}
270
280
281void vpSimulatorViper850::getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width,
282 const unsigned int &image_height)
283{
284 if (toolCustom) {
285 cam.initPersProjWithoutDistortion(px_int, py_int, image_width / 2, image_height / 2);
286 }
287 // Set default parameters
288 switch (getToolType()) {
290 // Set default intrinsic camera parameters for 640x480 images
291 if (image_width == 640 && image_height == 480) {
292 std::cout << "Get default camera parameters for camera \"" << vpViper850::CONST_MARLIN_F033C_CAMERA_NAME << "\""
293 << std::endl;
294 cam.initPersProjWithoutDistortion(1232.0, 1233.0, 320, 240);
295 }
296 else {
297 vpTRACE("Cannot get default intrinsic camera parameters for this image "
298 "resolution");
299 }
300 break;
301 }
303 // Set default intrinsic camera parameters for 640x480 images
304 if (image_width == 640 && image_height == 480) {
305 std::cout << "Get default camera parameters for camera \"" << vpViper850::CONST_PTGREY_FLEA2_CAMERA_NAME << "\""
306 << std::endl;
307 cam.initPersProjWithoutDistortion(868.0, 869.0, 320, 240);
308 }
309 else {
310 vpTRACE("Cannot get default intrinsic camera parameters for this image "
311 "resolution");
312 }
313 break;
314 }
318 std::cout << "This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
319 break;
320 }
321 }
322 return;
323}
324
337
350
357{
358 px_int = cam.get_px();
359 py_int = cam.get_py();
360 toolCustom = true;
361}
362
368{
369 double tcur_1 = tcur; // temporary variable used to store the last time
370 // since the last command
371
372 bool stop = false;
373 bool setVelocityCalled_ = false;
374 while (!stop) {
375 // Get current time
376 tprev = tcur_1;
378
380 setVelocityCalled_ = setVelocityCalled;
382
383 if (setVelocityCalled_ || !constantSamplingTimeMode) {
385 setVelocityCalled = false;
388
389 double ellapsedTime = (tcur - tprev) * 1e-3;
390 if (constantSamplingTimeMode) { // if we want a constant velocity, we
391 // force the ellapsed time to the given
392 // samplingTime
393 ellapsedTime = getSamplingTime(); // in second
394 }
395
396 vpColVector articularCoordinates = get_artCoord();
397 vpColVector articularVelocities = get_artVel();
398
399 if (jointLimit) {
400 double art = articularCoordinates[jointLimitArt - 1] + ellapsedTime * articularVelocities[jointLimitArt - 1];
401 if (art <= joint_min[jointLimitArt - 1] || art >= joint_max[jointLimitArt - 1]) {
402 if (verbose_) {
403 std::cout << "Joint " << jointLimitArt - 1
404 << " reaches a limit: " << vpMath::deg(joint_min[jointLimitArt - 1]) << " < " << vpMath::deg(art)
405 << " < " << vpMath::deg(joint_max[jointLimitArt - 1]) << std::endl;
406 }
407 articularVelocities = 0.0;
408 }
409 else
410 jointLimit = false;
411 }
412
413 articularCoordinates[0] = articularCoordinates[0] + ellapsedTime * articularVelocities[0];
414 articularCoordinates[1] = articularCoordinates[1] + ellapsedTime * articularVelocities[1];
415 articularCoordinates[2] = articularCoordinates[2] + ellapsedTime * articularVelocities[2];
416 articularCoordinates[3] = articularCoordinates[3] + ellapsedTime * articularVelocities[3];
417 articularCoordinates[4] = articularCoordinates[4] + ellapsedTime * articularVelocities[4];
418 articularCoordinates[5] = articularCoordinates[5] + ellapsedTime * articularVelocities[5];
419
420 int jl = isInJointLimit();
421
422 if (jl != 0 && jointLimit == false) {
423 if (jl < 0)
424 ellapsedTime = (joint_min[static_cast<unsigned int>(-jl - 1)] - articularCoordinates[static_cast<unsigned int>(-jl - 1)]) /
425 (articularVelocities[static_cast<unsigned int>(-jl - 1)]);
426 else
427 ellapsedTime = (joint_max[static_cast<unsigned int>(jl - 1)] - articularCoordinates[static_cast<unsigned int>(jl - 1)]) /
428 (articularVelocities[static_cast<unsigned int>(jl - 1)]);
429
430 for (unsigned int i = 0; i < 6; i++)
431 articularCoordinates[i] = articularCoordinates[i] + ellapsedTime * articularVelocities[i];
432
433 jointLimit = true;
434 jointLimitArt = static_cast<unsigned int>(fabs(static_cast<double>(jl)));
435 }
436
437 set_artCoord(articularCoordinates);
438 set_artVel(articularVelocities);
439
440 compute_fMi();
441
442 if (displayAllowed) {
446 }
447
449 while (get_displayBusy()) {
450 vpTime::wait(2);
451 }
453 set_displayBusy(false);
454 }
455
457 vpHomogeneousMatrix fMit[8];
458 get_fMi(fMit);
459
460 // vpDisplay::displayFrame(I,getExternalCameraPosition
461 // ()*fMi[6],cameraParam,0.2,vpColor::none);
462
463 vpImagePoint iP, iP_1;
464 vpPoint pt(0, 0, 0);
465
468 pt.track(getExternalCameraPosition() * fMit[0]);
471 for (int k = 1; k < 7; k++) {
472 pt.track(getExternalCameraPosition() * fMit[k - 1]);
474
475 pt.track(getExternalCameraPosition() * fMit[k]);
477
479 }
481 thickness_);
482 }
483
485
487 tcur_1 = tcur;
488 }
489 else {
491 }
492 m_mutex_robotStop.lock();
493 stop = robotStop;
494 m_mutex_robotStop.unlock();
495 }
496}
497
511{
512 // vpColVector q = get_artCoord();
513 vpColVector q(6); //; = get_artCoord();
514 q = get_artCoord();
515
516 vpHomogeneousMatrix fMit[8];
517
518 double q1 = q[0];
519 double q2 = q[1];
520 double q3 = q[2];
521 double q4 = q[3];
522 double q5 = q[4];
523 double q6 = q[5];
524
525 double c1 = cos(q1);
526 double s1 = sin(q1);
527 double c2 = cos(q2);
528 double s2 = sin(q2);
529 double c23 = cos(q2 + q3);
530 double s23 = sin(q2 + q3);
531 double c4 = cos(q4);
532 double s4 = sin(q4);
533 double c5 = cos(q5);
534 double s5 = sin(q5);
535 double c6 = cos(q6);
536 double s6 = sin(q6);
537
538 fMit[0][0][0] = c1;
539 fMit[0][1][0] = s1;
540 fMit[0][2][0] = 0;
541 fMit[0][0][1] = 0;
542 fMit[0][1][1] = 0;
543 fMit[0][2][1] = -1;
544 fMit[0][0][2] = -s1;
545 fMit[0][1][2] = c1;
546 fMit[0][2][2] = 0;
547 fMit[0][0][3] = a1 * c1;
548 fMit[0][1][3] = a1 * s1;
549 fMit[0][2][3] = d1;
550
551 fMit[1][0][0] = c1 * c2;
552 fMit[1][1][0] = s1 * c2;
553 fMit[1][2][0] = -s2;
554 fMit[1][0][1] = -c1 * s2;
555 fMit[1][1][1] = -s1 * s2;
556 fMit[1][2][1] = -c2;
557 fMit[1][0][2] = -s1;
558 fMit[1][1][2] = c1;
559 fMit[1][2][2] = 0;
560 fMit[1][0][3] = c1 * (a2 * c2 + a1);
561 fMit[1][1][3] = s1 * (a2 * c2 + a1);
562 fMit[1][2][3] = d1 - a2 * s2;
563
564 double quickcomp1 = a3 * c23 - a2 * c2 - a1;
565
566 fMit[2][0][0] = -c1 * c23;
567 fMit[2][1][0] = -s1 * c23;
568 fMit[2][2][0] = s23;
569 fMit[2][0][1] = s1;
570 fMit[2][1][1] = -c1;
571 fMit[2][2][1] = 0;
572 fMit[2][0][2] = c1 * s23;
573 fMit[2][1][2] = s1 * s23;
574 fMit[2][2][2] = c23;
575 fMit[2][0][3] = -c1 * quickcomp1;
576 fMit[2][1][3] = -s1 * quickcomp1;
577 fMit[2][2][3] = a3 * s23 - a2 * s2 + d1;
578
579 double quickcomp2 = c1 * (s23 * d4 - quickcomp1);
580 double quickcomp3 = s1 * (s23 * d4 - quickcomp1);
581
582 fMit[3][0][0] = -c1 * c23 * c4 + s1 * s4;
583 fMit[3][1][0] = -s1 * c23 * c4 - c1 * s4;
584 fMit[3][2][0] = s23 * c4;
585 fMit[3][0][1] = c1 * s23;
586 fMit[3][1][1] = s1 * s23;
587 fMit[3][2][1] = c23;
588 fMit[3][0][2] = -c1 * c23 * s4 - s1 * c4;
589 fMit[3][1][2] = -s1 * c23 * s4 + c1 * c4;
590 fMit[3][2][2] = s23 * s4;
591 fMit[3][0][3] = quickcomp2;
592 fMit[3][1][3] = quickcomp3;
593 fMit[3][2][3] = c23 * d4 + a3 * s23 - a2 * s2 + d1;
594
595 fMit[4][0][0] = c1 * (s23 * s5 - c5 * c23 * c4) + s1 * c5 * s4;
596 fMit[4][1][0] = s1 * (s23 * s5 - c5 * c23 * c4) - c1 * c5 * s4;
597 fMit[4][2][0] = s23 * c4 * c5 + c23 * s5;
598 fMit[4][0][1] = c1 * c23 * s4 + s1 * c4;
599 fMit[4][1][1] = s1 * c23 * s4 - c1 * c4;
600 fMit[4][2][1] = -s23 * s4;
601 fMit[4][0][2] = c1 * (s23 * c5 + s5 * c23 * c4) - s1 * s5 * s4;
602 fMit[4][1][2] = s1 * (s23 * c5 + s5 * c23 * c4) + c1 * s5 * s4;
603 fMit[4][2][2] = -s23 * c4 * s5 + c23 * c5;
604 fMit[4][0][3] = quickcomp2;
605 fMit[4][1][3] = quickcomp3;
606 fMit[4][2][3] = c23 * d4 + a3 * s23 - a2 * s2 + d1;
607
608 fMit[5][0][0] = c1 * (c23 * (c4 * c5 * c6 - s4 * s6) - s23 * s5 * c6) - s1 * (s4 * c5 * c6 + c4 * s6);
609 fMit[5][1][0] = -s1 * (c23 * (-c4 * c5 * c6 + s4 * s6) + s23 * s5 * c6) + c1 * (s4 * c5 * c6 + c4 * s6);
610 fMit[5][2][0] = s23 * (s4 * s6 - c4 * c5 * c6) - c23 * s5 * c6;
611 fMit[5][0][1] = -c1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) + s1 * (s4 * c5 * s6 - c4 * c6);
612 fMit[5][1][1] = -s1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) - c1 * (s4 * c5 * s6 - c4 * c6);
613 fMit[5][2][1] = s23 * (c4 * c5 * s6 + s4 * c6) + c23 * s5 * s6;
614 fMit[5][0][2] = c1 * (c23 * c4 * s5 + s23 * c5) - s1 * s4 * s5;
615 fMit[5][1][2] = s1 * (c23 * c4 * s5 + s23 * c5) + c1 * s4 * s5;
616 fMit[5][2][2] = -s23 * c4 * s5 + c23 * c5;
617 fMit[5][0][3] = quickcomp2;
618 fMit[5][1][3] = quickcomp3;
619 fMit[5][2][3] = s23 * a3 + c23 * d4 - a2 * s2 + d1;
620
621 fMit[6][0][0] = c1 * (c23 * (c4 * c5 * c6 - s4 * s6) - s23 * s5 * c6) - s1 * (s4 * c5 * c6 + c4 * s6);
622 fMit[6][1][0] = -s1 * (c23 * (-c4 * c5 * c6 + s4 * s6) + s23 * s5 * c6) + c1 * (s4 * c5 * c6 + c4 * s6);
623 fMit[6][2][0] = s23 * (s4 * s6 - c4 * c5 * c6) - c23 * s5 * c6;
624 fMit[6][0][1] = -c1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) + s1 * (s4 * c5 * s6 - c4 * c6);
625 fMit[6][1][1] = -s1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) - c1 * (s4 * c5 * s6 - c4 * c6);
626 fMit[6][2][1] = s23 * (c4 * c5 * s6 + s4 * c6) + c23 * s5 * s6;
627 fMit[6][0][2] = c1 * (c23 * c4 * s5 + s23 * c5) - s1 * s4 * s5;
628 fMit[6][1][2] = s1 * (c23 * c4 * s5 + s23 * c5) + c1 * s4 * s5;
629 fMit[6][2][2] = -s23 * c4 * s5 + c23 * c5;
630 fMit[6][0][3] = c1 * (c23 * (c4 * s5 * d6 - a3) + s23 * (c5 * d6 + d4) + a1 + a2 * c2) - s1 * s4 * s5 * d6;
631 fMit[6][1][3] = s1 * (c23 * (c4 * s5 * d6 - a3) + s23 * (c5 * d6 + d4) + a1 + a2 * c2) + c1 * s4 * s5 * d6;
632 fMit[6][2][3] = s23 * (a3 - c4 * s5 * d6) + c23 * (c5 * d6 + d4) - a2 * s2 + d1;
633
634 // vpHomogeneousMatrix cMe;
635 // get_cMe(cMe);
636 // cMe = cMe.inverse();
637 // fMit[7] = fMit[6] * cMe;
638 m_mutex_eMc.lock();
639 vpViper::get_fMc(q, fMit[7]);
640 m_mutex_eMc.unlock();
641
642 m_mutex_fMi.lock();
643 for (int i = 0; i < 8; i++) {
644 fMi[i] = fMit[i];
645 }
646 m_mutex_fMi.unlock();
647}
648
655{
656 switch (newState) {
657 case vpRobot::STATE_STOP: {
658 // Start primitive STOP only if the current state is Velocity
660 stopMotion();
661 }
662 break;
663 }
666 std::cout << "Change the control mode from velocity to position control.\n";
667 stopMotion();
668 }
669 else {
670 // std::cout << "Change the control mode from stop to position
671 // control.\n";
672 }
673 break;
674 }
677 std::cout << "Change the control mode from stop to velocity control.\n";
678 }
679 break;
680 }
682 default:
683 break;
684 }
685
686 return vpRobot::setRobotState(newState);
687}
688
766{
768 vpERROR_TRACE("Cannot send a velocity to the robot "
769 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
771 "Cannot send a velocity to the robot "
772 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
773 }
774
775 vpColVector vel_sat(6);
776
777 double scale_sat = 1;
778 double vel_trans_max = getMaxTranslationVelocity();
779 double vel_rot_max = getMaxRotationVelocity();
780
781 double vel_abs; // Absolute value
782
783 // Velocity saturation
784 switch (frame) {
785 // saturation in cartesian space
788 if (vel.getRows() != 6) {
789 vpERROR_TRACE("The velocity vector must have a size of 6 !!!!");
790 throw;
791 }
792
793 for (unsigned int i = 0; i < 3; ++i) {
794 vel_abs = fabs(vel[i]);
795 if (vel_abs > vel_trans_max && !jointLimit) {
796 vel_trans_max = vel_abs;
797 vpERROR_TRACE("Excess velocity %g m/s in TRANSLATION "
798 "(axis nr. %d).",
799 vel[i], i + 1);
800 }
801
802 vel_abs = fabs(vel[i + 3]);
803 if (vel_abs > vel_rot_max && !jointLimit) {
804 vel_rot_max = vel_abs;
805 vpERROR_TRACE("Excess velocity %g rad/s in ROTATION "
806 "(axis nr. %d).",
807 vel[i + 3], i + 4);
808 }
809 }
810
811 double scale_trans_sat = 1;
812 double scale_rot_sat = 1;
813 if (vel_trans_max > getMaxTranslationVelocity())
814 scale_trans_sat = getMaxTranslationVelocity() / vel_trans_max;
815
816 if (vel_rot_max > getMaxRotationVelocity())
817 scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
818
819 if ((scale_trans_sat < 1) || (scale_rot_sat < 1)) {
820 if (scale_trans_sat < scale_rot_sat)
821 scale_sat = scale_trans_sat;
822 else
823 scale_sat = scale_rot_sat;
824 }
825 break;
826 }
827
828 // saturation in joint space
830 if (vel.getRows() != 6) {
831 vpERROR_TRACE("The velocity vector must have a size of 6 !!!!");
832 throw;
833 }
834 for (unsigned int i = 0; i < 6; ++i) {
835 vel_abs = fabs(vel[i]);
836 if (vel_abs > vel_rot_max && !jointLimit) {
837 vel_rot_max = vel_abs;
838 vpERROR_TRACE("Excess velocity %g rad/s in ROTATION "
839 "(axis nr. %d).",
840 vel[i], i + 1);
841 }
842 }
843 double scale_rot_sat = 1;
844 if (vel_rot_max > getMaxRotationVelocity())
845 scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
846 if (scale_rot_sat < 1)
847 scale_sat = scale_rot_sat;
848 break;
849 }
851 case vpRobot::MIXT_FRAME: {
852 break;
853 }
854 }
855
856 set_velocity(vel * scale_sat);
857
858 m_mutex_frame.lock();
859 setRobotFrame(frame);
860 m_mutex_frame.unlock();
861
863 setVelocityCalled = true;
865}
866
871{
873
874 m_mutex_frame.lock();
875 frame = getRobotFrame();
876 m_mutex_frame.unlock();
877
878 double vel_rot_max = getMaxRotationVelocity();
879
880 vpColVector articularCoordinates = get_artCoord();
881 vpColVector velocityframe = get_velocity();
882 vpColVector articularVelocity;
883
884 switch (frame) {
886 vpMatrix eJe_;
888 vpViper850::get_eJe(articularCoordinates, eJe_);
889 eJe_ = eJe_.pseudoInverse();
891 singularityTest(articularCoordinates, eJe_);
892 articularVelocity = eJe_ * eVc * velocityframe;
893 set_artVel(articularVelocity);
894 break;
895 }
897 vpMatrix fJe_;
898 vpViper850::get_fJe(articularCoordinates, fJe_);
899 fJe_ = fJe_.pseudoInverse();
901 singularityTest(articularCoordinates, fJe_);
902 articularVelocity = fJe_ * velocityframe;
903 set_artVel(articularVelocity);
904 break;
905 }
907 articularVelocity = velocityframe;
908 set_artVel(articularVelocity);
909 break;
910 }
912 case vpRobot::MIXT_FRAME: {
913 break;
914 }
915 }
916
917 switch (frame) {
920 for (unsigned int i = 0; i < 6; ++i) {
921 double vel_abs = fabs(articularVelocity[i]);
922 if (vel_abs > vel_rot_max && !jointLimit) {
923 vel_rot_max = vel_abs;
924 vpERROR_TRACE("Excess velocity %g rad/s in ROTATION "
925 "(axis nr. %d).",
926 articularVelocity[i], i + 1);
927 }
928 }
929 double scale_rot_sat = 1;
930 double scale_sat = 1;
931
932 if (vel_rot_max > getMaxRotationVelocity())
933 scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
934 if (scale_rot_sat < 1)
935 scale_sat = scale_rot_sat;
936
937 set_artVel(articularVelocity * scale_sat);
938 break;
939 }
942 case vpRobot::MIXT_FRAME: {
943 break;
944 }
945 }
946}
947
998{
999 vel.resize(6);
1000
1001 vpColVector articularCoordinates = get_artCoord();
1002 vpColVector articularVelocity = get_artVel();
1003
1004 switch (frame) {
1005 case vpRobot::CAMERA_FRAME: {
1006 vpMatrix eJe_;
1008 vpViper850::get_eJe(articularCoordinates, eJe_);
1009 vel = cVe * eJe_ * articularVelocity;
1010 break;
1011 }
1013 vel = articularVelocity;
1014 break;
1015 }
1017 vpMatrix fJe_;
1018 vpViper850::get_fJe(articularCoordinates, fJe_);
1019 vel = fJe_ * articularVelocity;
1020 break;
1021 }
1023 case vpRobot::MIXT_FRAME: {
1024 break;
1025 }
1026 default: {
1027 vpERROR_TRACE("Error in spec of vpRobot. "
1028 "Case not taken in account.");
1029 return;
1030 }
1031 }
1032}
1033
1051{
1052 timestamp = vpTime::measureTimeSecond();
1053 getVelocity(frame, vel);
1054}
1055
1102{
1103 vpColVector vel(6);
1104 getVelocity(frame, vel);
1105
1106 return vel;
1107}
1108
1122{
1123 timestamp = vpTime::measureTimeSecond();
1124 vpColVector vel(6);
1125 getVelocity(frame, vel);
1126
1127 return vel;
1128}
1129
1131{
1132 double vel_rot_max = getMaxRotationVelocity();
1133 double velmax = fabs(q[0]);
1134 for (unsigned int i = 1; i < 6; i++) {
1135 if (velmax < fabs(q[i]))
1136 velmax = fabs(q[i]);
1137 }
1138
1139 double alpha = (getPositioningVelocity() * vel_rot_max) / (velmax * 100);
1140 q = q * alpha;
1141}
1142
1222{
1224 vpERROR_TRACE("Robot was not in position-based control\n"
1225 "Modification of the robot state");
1226 // setRobotState(vpRobot::STATE_POSITION_CONTROL) ;
1227 }
1228
1229 vpColVector articularCoordinates = get_artCoord();
1230
1231 vpColVector error(6);
1232 double errsqr = 0;
1233 switch (frame) {
1234 case vpRobot::CAMERA_FRAME: {
1235 unsigned int nbSol;
1236 vpColVector qdes(6);
1237
1239 vpRxyzVector rxyz;
1240 for (unsigned int i = 0; i < 3; i++) {
1241 txyz[i] = q[i];
1242 rxyz[i] = q[i + 3];
1243 }
1244
1245 vpRotationMatrix cRc2(rxyz);
1246 vpHomogeneousMatrix cMc2(txyz, cRc2);
1247
1249 vpViper850::get_fMc(articularCoordinates, fMc_);
1250
1251 vpHomogeneousMatrix fMc2 = fMc_ * cMc2;
1252
1253 do {
1254 articularCoordinates = get_artCoord();
1255 qdes = articularCoordinates;
1256 nbSol = getInverseKinematics(fMc2, qdes, verbose_);
1258 setVelocityCalled = true;
1260 if (nbSol > 0) {
1261 error = qdes - articularCoordinates;
1262 errsqr = error.sumSquare();
1263 // findHighestPositioningSpeed(error);
1264 set_artVel(error);
1265 if (errsqr < 1e-4) {
1266 set_artCoord(qdes);
1267 error = 0;
1268 set_artVel(error);
1269 set_velocity(error);
1270 break;
1271 }
1272 }
1273 else {
1274 vpERROR_TRACE("Positioning error.");
1275 throw vpRobotException(vpRobotException::positionOutOfRangeError, "Position out of range.");
1276 }
1277 } while (errsqr > 1e-8 && nbSol > 0);
1278
1279 break;
1280 }
1281
1283 do {
1284 articularCoordinates = get_artCoord();
1285 error = q - articularCoordinates;
1286 errsqr = error.sumSquare();
1287 // findHighestPositioningSpeed(error);
1288 set_artVel(error);
1290 setVelocityCalled = true;
1292 if (errsqr < 1e-4) {
1293 set_artCoord(q);
1294 error = 0;
1295 set_artVel(error);
1296 set_velocity(error);
1297 break;
1298 }
1299 } while (errsqr > 1e-8);
1300 break;
1301 }
1302
1304 unsigned int nbSol;
1305 vpColVector qdes(6);
1306
1308 vpRxyzVector rxyz;
1309 for (unsigned int i = 0; i < 3; i++) {
1310 txyz[i] = q[i];
1311 rxyz[i] = q[i + 3];
1312 }
1313
1314 vpRotationMatrix fRc(rxyz);
1315 vpHomogeneousMatrix fMc_(txyz, fRc);
1316
1317 do {
1318 articularCoordinates = get_artCoord();
1319 qdes = articularCoordinates;
1320 nbSol = getInverseKinematics(fMc_, qdes, verbose_);
1321 if (nbSol > 0) {
1322 error = qdes - articularCoordinates;
1323 errsqr = error.sumSquare();
1324 // findHighestPositioningSpeed(error);
1325 set_artVel(error);
1327 setVelocityCalled = true;
1329 if (errsqr < 1e-4) {
1330 set_artCoord(qdes);
1331 error = 0;
1332 set_artVel(error);
1333 set_velocity(error);
1334 break;
1335 }
1336 }
1337 else
1338 vpERROR_TRACE("Positioning error. Position unreachable");
1339 } while (errsqr > 1e-8 && nbSol > 0);
1340 break;
1341 }
1342 case vpRobot::MIXT_FRAME: {
1343 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1344 "Mixt frame not implemented.");
1345 }
1347 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1348 "End-effector frame not implemented.");
1349 }
1350 }
1351}
1352
1418void vpSimulatorViper850::setPosition(const vpRobot::vpControlFrameType frame, double pos1, double pos2, double pos3,
1419 double pos4, double pos5, double pos6)
1420{
1421 try {
1422 vpColVector position(6);
1423 position[0] = pos1;
1424 position[1] = pos2;
1425 position[2] = pos3;
1426 position[3] = pos4;
1427 position[4] = pos5;
1428 position[5] = pos6;
1429
1430 setPosition(frame, position);
1431 }
1432 catch (...) {
1433 vpERROR_TRACE("Error caught");
1434 throw;
1435 }
1436}
1437
1476void vpSimulatorViper850::setPosition(const char *filename)
1477{
1478 vpColVector q;
1479 bool ret;
1480
1481 ret = this->readPosFile(filename, q);
1482
1483 if (ret == false) {
1484 vpERROR_TRACE("Bad position in \"%s\"", filename);
1485 throw vpRobotException(vpRobotException::lowLevelError, "Bad position in filename.");
1486 }
1489}
1490
1554{
1555 q.resize(6);
1556
1557 switch (frame) {
1558 case vpRobot::CAMERA_FRAME: {
1559 q = 0;
1560 break;
1561 }
1562
1564 q = get_artCoord();
1565 break;
1566 }
1567
1571
1572 vpRotationMatrix fRc;
1573 fMc_.extract(fRc);
1574 vpRxyzVector rxyz(fRc);
1575
1577 fMc_.extract(txyz);
1578
1579 for (unsigned int i = 0; i < 3; i++) {
1580 q[i] = txyz[i];
1581 q[i + 3] = rxyz[i];
1582 }
1583 break;
1584 }
1585
1586 case vpRobot::MIXT_FRAME: {
1587 vpERROR_TRACE("Positioning error. Mixt frame not implemented");
1588 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1589 "Mixt frame not implemented.");
1590 }
1592 vpERROR_TRACE("Positioning error. Mixt frame not implemented");
1593 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1594 "End-effector frame not implemented.");
1595 }
1596 }
1597}
1598
1626{
1627 timestamp = vpTime::measureTimeSecond();
1628 getPosition(frame, q);
1629}
1630
1643{
1644 vpColVector posRxyz;
1645 // recupere position en Rxyz
1646 this->getPosition(frame, posRxyz);
1647
1648 // recupere le vecteur thetaU correspondant
1649 vpThetaUVector RtuVect(vpRxyzVector(posRxyz[3], posRxyz[4], posRxyz[5]));
1650
1651 // remplit le vpPoseVector avec translation et rotation ThetaU
1652 for (unsigned int j = 0; j < 3; j++) {
1653 position[j] = posRxyz[j];
1654 position[j + 3] = RtuVect[j];
1655 }
1656}
1657
1670 double &timestamp)
1671{
1672 timestamp = vpTime::measureTimeSecond();
1673 getPosition(frame, position);
1674}
1675
1684void vpSimulatorViper850::setJointLimit(const vpColVector &limitMin, const vpColVector &limitMax)
1685{
1686 if (limitMin.getRows() != 6 || limitMax.getRows() != 6) {
1687 vpTRACE("Joint limit vector has not a size of 6 !");
1688 return;
1689 }
1690
1691 joint_min[0] = limitMin[0];
1692 joint_min[1] = limitMin[1];
1693 joint_min[2] = limitMin[2];
1694 joint_min[3] = limitMin[3];
1695 joint_min[4] = limitMin[4];
1696 joint_min[5] = limitMin[5];
1697
1698 joint_max[0] = limitMax[0];
1699 joint_max[1] = limitMax[1];
1700 joint_max[2] = limitMax[2];
1701 joint_max[3] = limitMax[3];
1702 joint_max[4] = limitMax[4];
1703 joint_max[5] = limitMax[5];
1704}
1705
1712{
1713 double q2 = q[1];
1714 double q3 = q[2];
1715 double q5 = q[4];
1716
1717 double c2 = cos(q2);
1718 double c3 = cos(q3);
1719 double s3 = sin(q3);
1720 double c23 = cos(q2 + q3);
1721 double s23 = sin(q2 + q3);
1722 double s5 = sin(q5);
1723
1724 bool cond1 = fabs(s5) < 1e-1;
1725 bool cond2 = fabs(a3 * s3 + c3 * d4) < 1e-1;
1726 bool cond3 = fabs(a2 * c2 - a3 * c23 + s23 * d4 + a1) < 1e-1;
1727
1728 if (cond1) {
1729 J[3][0] = 0;
1730 J[5][0] = 0;
1731 J[3][1] = 0;
1732 J[5][1] = 0;
1733 J[3][2] = 0;
1734 J[5][2] = 0;
1735 J[3][3] = 0;
1736 J[5][3] = 0;
1737 J[3][4] = 0;
1738 J[5][4] = 0;
1739 J[3][5] = 0;
1740 J[5][5] = 0;
1741 return true;
1742 }
1743
1744 if (cond2) {
1745 J[1][0] = 0;
1746 J[2][0] = 0;
1747 J[3][0] = 0;
1748 J[4][0] = 0;
1749 J[5][0] = 0;
1750 J[1][1] = 0;
1751 J[2][1] = 0;
1752 J[3][1] = 0;
1753 J[4][1] = 0;
1754 J[5][1] = 0;
1755 J[1][2] = 0;
1756 J[2][2] = 0;
1757 J[3][2] = 0;
1758 J[4][2] = 0;
1759 J[5][2] = 0;
1760 return true;
1761 }
1762
1763 if (cond3) {
1764 J[0][0] = 0;
1765 J[3][0] = 0;
1766 J[4][0] = 0;
1767 J[5][0] = 0;
1768 J[0][1] = 0;
1769 J[3][1] = 0;
1770 J[4][1] = 0;
1771 J[5][1] = 0;
1772 }
1773
1774 return false;
1775}
1776
1781{
1782 int artNumb = 0;
1783 double diff = 0;
1784 double difft = 0;
1785
1786 vpColVector articularCoordinates = get_artCoord();
1787
1788 for (unsigned int i = 0; i < 6; i++) {
1789 if (articularCoordinates[i] <= joint_min[i]) {
1790 difft = joint_min[i] - articularCoordinates[i];
1791 if (difft > diff) {
1792 diff = difft;
1793 artNumb = -static_cast<int>(i) - 1;
1794 }
1795 }
1796 }
1797
1798 for (unsigned int i = 0; i < 6; i++) {
1799 if (articularCoordinates[i] >= joint_max[i]) {
1800 difft = articularCoordinates[i] - joint_max[i];
1801 if (difft > diff) {
1802 diff = difft;
1803 artNumb = static_cast<int>(i + 1);
1804 }
1805 }
1806 }
1807
1808 if (artNumb != 0)
1809 std::cout << "\nWarning: Velocity control stopped: axis " << fabs(static_cast<float>(artNumb)) << " on joint limit!"
1810 << std::endl;
1811
1812 return artNumb;
1813}
1814
1833{
1834 displacement.resize(6);
1835 displacement = 0;
1836 vpColVector q_cur(6);
1837
1838 q_cur = get_artCoord();
1839
1840 if (!first_time_getdis) {
1841 switch (frame) {
1842 case vpRobot::CAMERA_FRAME: {
1843 std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
1844 return;
1845 }
1846
1848 displacement = q_cur - q_prev_getdis;
1849 break;
1850 }
1851
1853 std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
1854 return;
1855 }
1856
1857 case vpRobot::MIXT_FRAME: {
1858 std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
1859 return;
1860 }
1862 std::cout << "getDisplacement() END_EFFECTOR_FRAME not implemented\n";
1863 return;
1864 }
1865 }
1866 }
1867 else {
1868 first_time_getdis = false;
1869 }
1870
1871 // Memorize the joint position for the next call
1872 q_prev_getdis = q_cur;
1873}
1874
1940bool vpSimulatorViper850::readPosFile(const std::string &filename, vpColVector &q)
1941{
1942 std::ifstream fd(filename.c_str(), std::ios::in);
1943
1944 if (!fd.is_open()) {
1945 return false;
1946 }
1947
1948 std::string line;
1949 std::string key("R:");
1950 std::string id("#Viper850 - Position");
1951 bool pos_found = false;
1952 int lineNum = 0;
1953
1954 q.resize(njoint);
1955
1956 while (std::getline(fd, line)) {
1957 lineNum++;
1958 if (lineNum == 1) {
1959 if (!(line.compare(0, id.size(), id) == 0)) { // check if Viper850 position file
1960 std::cout << "Error: this position file " << filename << " is not for Viper850 robot" << std::endl;
1961 return false;
1962 }
1963 }
1964 if ((line.compare(0, 1, "#") == 0)) { // skip comment
1965 continue;
1966 }
1967 if ((line.compare(0, key.size(), key) == 0)) { // decode position
1968 // check if there are at least njoint values in the line
1969 std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
1970 if (chain.size() < njoint + 1) // try to split with tab separator
1971 chain = vpIoTools::splitChain(line, std::string("\t"));
1972 if (chain.size() < njoint + 1)
1973 continue;
1974
1975 std::istringstream ss(line);
1976 std::string key_;
1977 ss >> key_;
1978 for (unsigned int i = 0; i < njoint; i++)
1979 ss >> q[i];
1980 pos_found = true;
1981 break;
1982 }
1983 }
1984
1985 // converts rotations from degrees into radians
1986 q.deg2rad();
1987
1988 fd.close();
1989
1990 if (!pos_found) {
1991 std::cout << "Error: unable to find a position for Viper850 robot in " << filename << std::endl;
1992 return false;
1993 }
1994
1995 return true;
1996}
1997
2019bool vpSimulatorViper850::savePosFile(const std::string &filename, const vpColVector &q)
2020{
2021
2022 FILE *fd;
2023 fd = fopen(filename.c_str(), "w");
2024 if (fd == nullptr)
2025 return false;
2026
2027 fprintf(fd, "\
2028#Viper - Position - Version 1.0\n\
2029#\n\
2030# R: A B C D E F\n\
2031# Joint position in degrees\n\
2032#\n\
2033#\n\n");
2034
2035 // Save positions in mm and deg
2036 fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n", vpMath::deg(q[0]), vpMath::deg(q[1]), vpMath::deg(q[2]),
2037 vpMath::deg(q[3]), vpMath::deg(q[4]), vpMath::deg(q[5]));
2038
2039 fclose(fd);
2040 return (true);
2041}
2042
2050void vpSimulatorViper850::move(const char *filename)
2051{
2052 vpColVector q;
2053
2054 try {
2055 this->readPosFile(filename, q);
2058 }
2059 catch (...) {
2060 throw;
2061 }
2062}
2063
2074
2083{
2086
2087 cVe.buildFrom(cMe);
2088}
2089
2100{
2101 try {
2103 }
2104 catch (...) {
2105 vpERROR_TRACE("catch exception ");
2106 throw;
2107 }
2108}
2109
2121{
2122 try {
2123 vpColVector articularCoordinates = get_artCoord();
2124 vpViper850::get_fJe(articularCoordinates, fJe_);
2125 }
2126 catch (...) {
2127 vpERROR_TRACE("Error caught");
2128 throw;
2129 }
2130}
2131
2136{
2138 return;
2139
2140 vpColVector stop(6);
2141 stop = 0;
2142 set_artVel(stop);
2143 set_velocity(stop);
2145}
2146
2156{
2157 // set scene_dir from #define VISP_SCENE_DIR if it exists
2158 // VISP_SCENES_DIR may contain multiple locations separated by ";"
2159 std::string scene_dir_;
2160 std::vector<std::string> scene_dirs = vpIoTools::splitChain(std::string(VISP_SCENES_DIR), std::string(";"));
2161 bool sceneDirExists = false;
2162 for (size_t i = 0; i < scene_dirs.size(); i++)
2163 if (vpIoTools::checkDirectory(scene_dirs[i]) == true) { // directory exists
2164 scene_dir_ = scene_dirs[i];
2165 sceneDirExists = true;
2166 break;
2167 }
2168 if (!sceneDirExists) {
2169 try {
2170 scene_dir_ = vpIoTools::getenv("VISP_SCENES_DIR");
2171 std::cout << "The simulator uses data from VISP_SCENES_DIR=" << scene_dir_ << std::endl;
2172 }
2173 catch (...) {
2174 std::cout << "Cannot get VISP_SCENES_DIR environment variable" << std::endl;
2175 }
2176 }
2177
2178 unsigned int name_length = 30; // the size of this kind of string "/viper850_arm2.bnd"
2179 if (scene_dir_.size() > FILENAME_MAX)
2180 throw vpException(vpException::dimensionError, "Cannot initialize Viper850 simulator");
2181
2182 unsigned int full_length = static_cast<unsigned int>(scene_dir_.size()) + name_length;
2183 if (full_length > FILENAME_MAX)
2184 throw vpException(vpException::dimensionError, "Cannot initialize Viper850 simulator");
2185
2186 char *name_cam = new char[full_length];
2187
2188 strcpy(name_cam, scene_dir_.c_str());
2189 strcat(name_cam, "/camera.bnd");
2190 set_scene(name_cam, &camera, cameraFactor);
2191
2192 if (arm_dir.size() > FILENAME_MAX)
2193 throw vpException(vpException::dimensionError, "Cannot initialize Viper850 simulator");
2194 full_length = static_cast<unsigned int>(arm_dir.size()) + name_length;
2195 if (full_length > FILENAME_MAX)
2196 throw vpException(vpException::dimensionError, "Cannot initialize Viper850 simulator");
2197
2198 char *name_arm = new char[full_length];
2199 strcpy(name_arm, arm_dir.c_str());
2200 strcat(name_arm, "/viper850_arm1.bnd");
2201 set_scene(name_arm, robotArms, 1.0);
2202 strcpy(name_arm, arm_dir.c_str());
2203 strcat(name_arm, "/viper850_arm2.bnd");
2204 set_scene(name_arm, robotArms + 1, 1.0);
2205 strcpy(name_arm, arm_dir.c_str());
2206 strcat(name_arm, "/viper850_arm3.bnd");
2207 set_scene(name_arm, robotArms + 2, 1.0);
2208 strcpy(name_arm, arm_dir.c_str());
2209 strcat(name_arm, "/viper850_arm4.bnd");
2210 set_scene(name_arm, robotArms + 3, 1.0);
2211 strcpy(name_arm, arm_dir.c_str());
2212 strcat(name_arm, "/viper850_arm5.bnd");
2213 set_scene(name_arm, robotArms + 4, 1.0);
2214 strcpy(name_arm, arm_dir.c_str());
2215 strcat(name_arm, "/viper850_arm6.bnd");
2216 set_scene(name_arm, robotArms + 5, 1.0);
2217
2218 // set_scene("./arm2.bnd", robotArms+1, 1.0);
2219 // set_scene("./arm3.bnd", robotArms+2, 1.0);
2220 // set_scene("./arm4.bnd", robotArms+3, 1.0);
2221 // set_scene("./arm5.bnd", robotArms+4, 1.0);
2222 // set_scene("./arm6.bnd", robotArms+5, 1.0);
2223
2224 add_rfstack(IS_BACK);
2225
2226 add_vwstack("start", "depth", 0.0, 100.0);
2227 add_vwstack("start", "window", -0.1, 0.1, -0.1, 0.1);
2228 add_vwstack("start", "type", PERSPECTIVE);
2229 //
2230 // sceneInitialized = true;
2231 // displayObject = true;
2232 displayCamera = true;
2233
2234 delete[] name_cam;
2235 delete[] name_arm;
2236}
2237
2239{
2240 m_mutex_scene.lock();
2241 bool changed = false;
2242 vpHomogeneousMatrix displacement = navigation(I_, changed);
2243
2244 // if (displacement[2][3] != 0)
2245 if (std::fabs(displacement[2][3]) > std::numeric_limits<double>::epsilon())
2246 camMf2 = camMf2 * displacement;
2247
2248 f2Mf = camMf2.inverse() * camMf;
2249
2250 camMf = camMf2 * displacement * f2Mf;
2251
2252 double u;
2253 double v;
2254 // if(px_ext != 1 && py_ext != 1)
2255 // we assume px_ext and py_ext > 0
2256 if ((std::fabs(px_ext - 1.) > vpMath::maximum(px_ext, 1.) * std::numeric_limits<double>::epsilon()) &&
2257 (std::fabs(py_ext - 1) > vpMath::maximum(py_ext, 1.) * std::numeric_limits<double>::epsilon())) {
2258 u = static_cast<double>(I_.getWidth()) / (2 * px_ext);
2259 v = static_cast<double>(I_.getHeight()) / (2 * py_ext);
2260 }
2261 else {
2262 u = static_cast<double>(I_.getWidth()) / (vpMath::minimum(I_.getWidth(), I_.getHeight()));
2263 v = static_cast<double>(I_.getHeight()) / (vpMath::minimum(I_.getWidth(), I_.getHeight()));
2264 }
2265
2266 float w44o[4][4], w44cext[4][4], x, y, z;
2267
2268 vp2jlc_matrix(camMf.inverse(), w44cext);
2269
2270 add_vwstack("start", "cop", w44cext[3][0], w44cext[3][1], w44cext[3][2]);
2271 x = w44cext[2][0] + w44cext[3][0];
2272 y = w44cext[2][1] + w44cext[3][1];
2273 z = w44cext[2][2] + w44cext[3][2];
2274 add_vwstack("start", "vrp", x, y, z);
2275 add_vwstack("start", "vpn", w44cext[2][0], w44cext[2][1], w44cext[2][2]);
2276 add_vwstack("start", "vup", w44cext[1][0], w44cext[1][1], w44cext[1][2]);
2277 add_vwstack("start", "window", -u, u, -v, v);
2278
2279 vpHomogeneousMatrix fMit[8];
2280 get_fMi(fMit);
2281
2282 vp2jlc_matrix(vpHomogeneousMatrix(0, 0, 0, 0, 0, 0), w44o);
2283 display_scene(w44o, robotArms[0], I_, curColor);
2284
2285 vp2jlc_matrix(fMit[0], w44o);
2286 display_scene(w44o, robotArms[1], I_, curColor);
2287
2288 vp2jlc_matrix(fMit[1], w44o);
2289 display_scene(w44o, robotArms[2], I_, curColor);
2290
2291 vp2jlc_matrix(fMit[2], w44o);
2292 display_scene(w44o, robotArms[3], I_, curColor);
2293
2294 vp2jlc_matrix(fMit[3], w44o);
2295 display_scene(w44o, robotArms[4], I_, curColor);
2296
2297 vp2jlc_matrix(fMit[6], w44o);
2298 display_scene(w44o, robotArms[5], I_, curColor);
2299
2300 if (displayCamera) {
2302 get_cMe(cMe);
2303 cMe = cMe.inverse();
2304 cMe = fMit[6] * cMe;
2305 vp2jlc_matrix(cMe, w44o);
2306 display_scene(w44o, camera, I_, camColor);
2307 }
2308
2309 if (displayObject) {
2310 vp2jlc_matrix(fMo, w44o);
2311 display_scene(w44o, scene, I_, curColor);
2312 }
2313 m_mutex_scene.unlock();
2314}
2315
2333{
2334 vpColVector stop(6);
2335 bool status = true;
2336 stop = 0;
2337 set_artVel(stop);
2338 set_velocity(stop);
2340 fMc_ = fMo * cMo_.inverse();
2341
2342 vpColVector articularCoordinates = get_artCoord();
2343 unsigned int nbSol = getInverseKinematics(fMc_, articularCoordinates, verbose_);
2344
2345 if (nbSol == 0) {
2346 status = false;
2347 vpERROR_TRACE("Positioning error. Position unreachable");
2348 }
2349
2350 if (verbose_)
2351 std::cout << "Used joint coordinates (rad): " << articularCoordinates.t() << std::endl;
2352
2353 set_artCoord(articularCoordinates);
2354
2355 compute_fMi();
2356
2357 return status;
2358}
2359
2374{
2375 vpColVector stop(6);
2376 stop = 0;
2377 m_mutex_scene.lock();
2378 set_artVel(stop);
2379 set_velocity(stop);
2380 vpHomogeneousMatrix fMit[8];
2381 get_fMi(fMit);
2382 fMo = fMit[7] * cMo_;
2383 m_mutex_scene.unlock();
2384}
2385END_VISP_NAMESPACE
2386#elif !defined(VISP_BUILD_SHARED_LIBS)
2387// Work around to avoid warning: libvisp_robot.a(vpSimulatorViper850.cpp.o)
2388// has no symbols
2389void dummy_vpSimulatorViper850() { }
2390#endif
unsigned int getRows() const
Definition vpArray2D.h:433
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
vpColVector & deg2rad()
vpRowVector t() const
void resize(unsigned int i, bool flagNullify=true)
static const vpColor none
Definition vpColor.h:210
static const vpColor green
Definition vpColor.h:201
static void display(const vpImage< unsigned char > &I)
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
static void displayFrame(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color=vpColor::none, unsigned int thickness=1, const vpImagePoint &offset=vpImagePoint(0, 0), const std::string &frameName="", const vpColor &textColor=vpColor::black, const vpImagePoint &textOffset=vpImagePoint(15, 15))
static void flush(const vpImage< unsigned char > &I)
static void displayCamera(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color, unsigned int thickness)
error that can be emitted by ViSP classes.
Definition vpException.h:60
@ dimensionError
Bad dimension.
Definition vpException.h:71
void track(const vpHomogeneousMatrix &cMo)
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
void extract(vpRotationMatrix &R) const
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition of the vpImage class member functions.
Definition vpImage.h:131
unsigned int getWidth() const
Definition vpImage.h:242
unsigned int getHeight() const
Definition vpImage.h:181
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
static bool checkDirectory(const std::string &dirname)
static std::string getenv(const std::string &env)
static double rad(double deg)
Definition vpMath.h:129
static Type maximum(const Type &a, const Type &b)
Definition vpMath.h:257
static Type minimum(const Type &a, const Type &b)
Definition vpMath.h:265
static double deg(double rad)
Definition vpMath.h:119
Implementation of a matrix and operations on matrices.
Definition vpMatrix.h:175
vpMatrix pseudoInverse(double svThreshold=1e-6) const
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition vpPoint.h:79
double get_y() const
Get the point y coordinate in the image plane.
Definition vpPoint.cpp:429
double get_x() const
Get the point x coordinate in the image plane.
Definition vpPoint.cpp:427
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.
@ positionOutOfRangeError
Position is out of range.
@ lowLevelError
Error thrown by the low level sdk.
double getSamplingTime() const
void set_velocity(const vpColVector &vel)
static void launcher(vpRobotWireFrameSimulator &simulator)
void set_displayBusy(const bool &status)
vpHomogeneousMatrix getExternalCameraPosition() const
void set_artCoord(const vpColVector &coord)
void setExternalCameraPosition(const vpHomogeneousMatrix &camMf_)
void set_artVel(const vpColVector &vel)
virtual vpRobotStateType getRobotState(void) const
Definition vpRobot.h:152
vpControlFrameType
Definition vpRobot.h:74
@ REFERENCE_FRAME
Definition vpRobot.h:75
@ ARTICULAR_FRAME
Definition vpRobot.h:77
@ MIXT_FRAME
Definition vpRobot.h:85
@ CAMERA_FRAME
Definition vpRobot.h:81
@ END_EFFECTOR_FRAME
Definition vpRobot.h:80
vpControlFrameType getRobotFrame(void) const
Definition vpRobot.h:180
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_ACCELERATION_CONTROL
Initialize the acceleration controller.
Definition vpRobot.h:66
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition vpRobot.h:63
double getMaxRotationVelocity(void) const
Definition vpRobot.cpp:272
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition vpRobot.cpp:200
double getMaxTranslationVelocity(void) const
Definition vpRobot.cpp:250
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition vpRobot.cpp:206
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.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE
void computeArticularVelocity() VP_OVERRIDE
static bool savePosFile(const std::string &filename, const vpColVector &q)
void setCameraParameters(const vpCameraParameters &cam)
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height)
void getExternalImage(vpImage< vpRGBa > &I)
void get_cMe(vpHomogeneousMatrix &cMe)
void updateArticularPosition() VP_OVERRIDE
void get_cVe(vpVelocityTwistMatrix &cVe)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) VP_OVERRIDE
static const double defaultPositioningVelocity
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q) VP_OVERRIDE
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &q)
void findHighestPositioningSpeed(vpColVector &q)
bool singularityTest(const vpColVector &q, vpMatrix &J)
vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState) VP_OVERRIDE
void setJointLimit(const vpColVector &limitMin, const vpColVector &limitMax)
void initArms() VP_OVERRIDE
void get_fJe(vpMatrix &fJe) VP_OVERRIDE
void initialiseObjectRelativeToCamera(const vpHomogeneousMatrix &cMo)
void get_fMi(vpHomogeneousMatrix *fMit) VP_OVERRIDE
int isInJointLimit() VP_OVERRIDE
virtual ~vpSimulatorViper850() VP_OVERRIDE
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
static bool readPosFile(const std::string &filename, vpColVector &q)
void move(const char *filename)
double getPositioningVelocity(void)
bool initialiseCameraRelativeToObject(const vpHomogeneousMatrix &cMo)
void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &displacement) VP_OVERRIDE
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.
vpVelocityTwistMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME
Definition vpViper850.h:114
void setToolType(vpViper850::vpToolType tool)
Set the current tool type.
Definition vpViper850.h:161
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition vpViper850.h:129
vpCameraParameters::vpCameraParametersProjType projModel
Definition vpViper850.h:168
vpToolType getToolType() const
Get the current tool type.
Definition vpViper850.h:152
vpToolType
List of possible tools that can be attached to the robot end-effector.
Definition vpViper850.h:120
@ TOOL_SCHUNK_GRIPPER_CAMERA
Definition vpViper850.h:123
@ TOOL_PTGREY_FLEA2_CAMERA
Definition vpViper850.h:122
@ TOOL_MARLIN_F033C_CAMERA
Definition vpViper850.h:121
@ TOOL_GENERIC_CAMERA
Definition vpViper850.h:124
static const char *const CONST_MARLIN_F033C_CAMERA_NAME
Definition vpViper850.h:113
vpTranslationVector etc
Definition vpViper.h:158
double d6
for joint 6
Definition vpViper.h:166
double a3
for joint 3
Definition vpViper.h:164
static const unsigned int njoint
Number of joint.
Definition vpViper.h:153
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition vpViper.cpp:942
double d4
for joint 4
Definition vpViper.h:165
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
vpHomogeneousMatrix eMc
End effector to camera transformation.
Definition vpViper.h:156
double a1
Definition vpViper.h:162
vpRxyzVector erc
Definition vpViper.h:159
vpColVector joint_min
Definition vpViper.h:172
double a2
for joint 2
Definition vpViper.h:163
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition vpViper.cpp:990
double d1
for joint 1
Definition vpViper.h:162
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition vpViper.cpp:626
vpHomogeneousMatrix camMf2
vpHomogeneousMatrix f2Mf
void display_scene(Matrix mat, Bound_scene &sc, const vpImage< vpRGBa > &I, const vpColor &color)
vpHomogeneousMatrix fMo
vpHomogeneousMatrix camMf
void setExternalCameraParameters(const vpCameraParameters &cam)
vpHomogeneousMatrix navigation(const vpImage< vpRGBa > &I, bool &changed)
#define vpTRACE
Definition vpDebug.h:450
#define vpERROR_TRACE
Definition vpDebug.h:423
VISP_EXPORT double measureTimeMs()
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT double getMinTimeForUsleepCall()
VISP_EXPORT double measureTimeSecond()