Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vpSimulatorAfma6.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 Afma6.
32 */
33
34#include <visp3/core/vpConfig.h>
35#if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS)
36#include <cmath> // std::fabs
37#include <limits> // numeric_limits
38#include <string>
39#include <visp3/core/vpDebug.h>
40#include <visp3/core/vpImagePoint.h>
41#include <visp3/core/vpIoTools.h>
42#include <visp3/core/vpMeterPixelConversion.h>
43#include <visp3/core/vpPoint.h>
44#include <visp3/core/vpTime.h>
45#include <visp3/robot/vpRobotException.h>
46#include <visp3/robot/vpSimulatorAfma6.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(), vpAfma6(), 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 for (int i = 0; i < 6; i++)
106 free_Bound_scene(&(robotArms[i]));
107 }
108
109 delete[] robotArms;
110 delete[] fMi;
111 delete m_thread;
112}
113
123{
124 // set arm_dir from #define VISP_ROBOT_ARMS_DIR if it exists
125 // VISP_ROBOT_ARMS_DIR may contain multiple locations separated by ";"
126 std::vector<std::string> arm_dirs = vpIoTools::splitChain(std::string(VISP_ROBOT_ARMS_DIR), std::string(";"));
127 bool armDirExists = false;
128 for (size_t i = 0; i < arm_dirs.size(); i++)
129 if (vpIoTools::checkDirectory(arm_dirs[i]) == true) { // directory exists
130 arm_dir = arm_dirs[i];
131 armDirExists = true;
132 break;
133 }
134 if (!armDirExists) {
135 try {
136 arm_dir = vpIoTools::getenv("VISP_ROBOT_ARMS_DIR");
137 std::cout << "The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl;
138 }
139 catch (...) {
140 std::cout << "Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl;
141 }
142 }
143
145 toolCustom = false;
146
147 size_fMi = 8;
148 fMi = new vpHomogeneousMatrix[8];
149 artCoord.resize(njoint);
150 artVel.resize(njoint);
151
152 zeroPos.resize(njoint);
153 zeroPos = 0;
154 reposPos.resize(njoint);
155 reposPos = 0;
156 reposPos[1] = -M_PI / 2;
157 reposPos[2] = M_PI;
158 reposPos[4] = M_PI / 2;
159
160 artCoord = zeroPos;
161 artVel = 0;
162
163 q_prev_getdis.resize(njoint);
164 q_prev_getdis = 0;
165 first_time_getdis = true;
166
167 positioningVelocity = defaultPositioningVelocity;
168
171
172 // Software joint limits in radians
173 //_joint_min.resize(njoint);
174 _joint_min[0] = -0.7501;
175 _joint_min[1] = -0.6501;
176 _joint_min[2] = -0.5001;
177 _joint_min[3] = -2.7301;
178 _joint_min[4] = -0.3001;
179 _joint_min[5] = -1.5901;
180 //_joint_max.resize(njoint);
181 _joint_max[0] = 0.6001;
182 _joint_max[1] = 0.6701;
183 _joint_max[2] = 0.4601;
184 _joint_max[3] = 2.7301;
185 _joint_max[4] = 2.4801;
186 _joint_max[5] = 1.5901;
187}
188
193{
194 robotArms = nullptr;
195 robotArms = new Bound_scene[6];
196 initArms();
198 vpHomogeneousMatrix(-0.1, 0, 4, vpMath::rad(90), 0, 0));
199 cameraParam.initPersProjWithoutDistortion(558.5309599, 556.055053, 320, 240);
202 getCameraParameters(tmp, 640, 480);
203 px_int = tmp.get_px();
204 py_int = tmp.get_py();
205 sceneInitialized = true;
206}
207
224{
225 this->projModel = proj_model;
226 unsigned int name_length = 30; // the size of this kind of string "/afma6_tool_vacuum.bnd"
227 if (arm_dir.size() > FILENAME_MAX)
228 throw vpException(vpException::dimensionError, "Cannot initialize Afma6 simulator");
229 unsigned int full_length = static_cast<unsigned int>(arm_dir.size()) + name_length;
230 if (full_length > FILENAME_MAX)
231 throw vpException(vpException::dimensionError, "Cannot initialize Afma6 simulator");
232
233 // Use here default values of the robot constant parameters.
234 switch (tool) {
235 case vpAfma6::TOOL_CCMOP: {
236 _erc[0] = vpMath::rad(164.35); // rx
237 _erc[1] = vpMath::rad(89.64); // ry
238 _erc[2] = vpMath::rad(-73.05); // rz
239 _etc[0] = 0.0117; // tx
240 _etc[1] = 0.0033; // ty
241 _etc[2] = 0.2272; // tz
242
243 setCameraParameters(vpCameraParameters(1109.5735473989, 1112.1520168160, 320, 240));
244
245 if (robotArms != nullptr) {
246 while (get_displayBusy())
247 vpTime::wait(2);
248 free_Bound_scene(&(robotArms[5]));
249 char *name_arm = new char[full_length];
250 strcpy(name_arm, arm_dir.c_str());
251 strcat(name_arm, "/afma6_tool_ccmop.bnd");
252 set_scene(name_arm, robotArms + 5, 1.0);
253 set_displayBusy(false);
254 delete[] name_arm;
255 }
256 break;
257 }
259 _erc[0] = vpMath::rad(88.33); // rx
260 _erc[1] = vpMath::rad(72.07); // ry
261 _erc[2] = vpMath::rad(2.53); // rz
262 _etc[0] = 0.0783; // tx
263 _etc[1] = 0.1234; // ty
264 _etc[2] = 0.1638; // tz
265
266 setCameraParameters(vpCameraParameters(852.6583228197, 854.8084224761, 320, 240));
267
268 if (robotArms != nullptr) {
269 while (get_displayBusy())
270 vpTime::wait(2);
271 free_Bound_scene(&(robotArms[5]));
272 char *name_arm = new char[full_length];
273 strcpy(name_arm, arm_dir.c_str());
274 strcat(name_arm, "/afma6_tool_gripper.bnd");
275 set_scene(name_arm, robotArms + 5, 1.0);
276 set_displayBusy(false);
277 delete[] name_arm;
278 }
279 break;
280 }
282 _erc[0] = vpMath::rad(90.40); // rx
283 _erc[1] = vpMath::rad(75.11); // ry
284 _erc[2] = vpMath::rad(0.18); // rz
285 _etc[0] = 0.0038; // tx
286 _etc[1] = 0.1281; // ty
287 _etc[2] = 0.1658; // tz
288
289 setCameraParameters(vpCameraParameters(853.4876600807, 856.0339170706, 320, 240));
290
291 if (robotArms != nullptr) {
292 while (get_displayBusy())
293 vpTime::wait(2);
294 free_Bound_scene(&(robotArms[5]));
295
296 char *name_arm = new char[full_length];
297
298 strcpy(name_arm, arm_dir.c_str());
299 strcat(name_arm, "/afma6_tool_vacuum.bnd");
300 set_scene(name_arm, robotArms + 5, 1.0);
301 set_displayBusy(false);
302 delete[] name_arm;
303 }
304 break;
305 }
307 std::cout << "The custom tool is not handled in vpSimulatorAfma6.cpp" << std::endl;
308 break;
309 }
311 std::cout << "The Intel D435 camera is not handled in vpSimulatorAfma6.cpp" << std::endl;
312 break;
313 }
315 std::cout << "The generic camera is not handled in vpSimulatorAfma6.cpp" << std::endl;
316 break;
317 }
318 }
319
321
322 m_mutex_eMc.lock();
323 this->_eMc.buildFrom(_etc, eRc);
324 m_mutex_eMc.unlock();
325
326 setToolType(tool);
327 return;
328}
329
339
340void vpSimulatorAfma6::getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width,
341 const unsigned int &image_height)
342{
343 if (toolCustom) {
344 cam.initPersProjWithoutDistortion(px_int, py_int, image_width / 2, image_height / 2);
345 }
346 // Set default parameters
347 switch (getToolType()) {
348 case vpAfma6::TOOL_CCMOP: {
349 // Set default intrinsic camera parameters for 640x480 images
350 if (image_width == 640 && image_height == 480) {
351 std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_CCMOP_CAMERA_NAME << "\""
352 << std::endl;
353 cam.initPersProjWithoutDistortion(1109.5735473989, 1112.1520168160, 320, 240);
354 }
355 else {
356 vpTRACE("Cannot get default intrinsic camera parameters for this image "
357 "resolution");
358 }
359 break;
360 }
362 // Set default intrinsic camera parameters for 640x480 images
363 if (image_width == 640 && image_height == 480) {
364 std::cout << "Get default camera parameters for camera \"" << vpAfma6::CONST_GRIPPER_CAMERA_NAME << "\""
365 << std::endl;
366 cam.initPersProjWithoutDistortion(852.6583228197, 854.8084224761, 320, 240);
367 }
368 else {
369 vpTRACE("Cannot get default intrinsic camera parameters for this image "
370 "resolution");
371 }
372 break;
373 }
375 std::cout << "The generic tool is not handled in vpSimulatorAfma6.cpp" << std::endl;
376 break;
377 }
379 std::cout << "The Intel D435 camera is not handled in vpSimulatorAfma6.cpp" << std::endl;
380 break;
381 }
383 std::cout << "The generic camera is not handled in vpSimulatorAfma6.cpp" << std::endl;
384 break;
385 }
387 std::cout << "The vacuum tool is not handled in vpSimulatorAfma6.cpp" << std::endl;
388 break;
389 }
390 default:
391 vpERROR_TRACE("This error should not occur!");
392 break;
393 }
394 return;
395}
396
409
422
429{
430 px_int = cam.get_px();
431 py_int = cam.get_py();
432 toolCustom = true;
433}
434
440{
441 double tcur_1 = tcur; // temporary variable used to store the last time
442 // since the last command
443 bool stop = false;
444 bool setVelocityCalled_ = false;
445 while (!stop) {
446 // Get current time
447 tprev = tcur_1;
449
451 setVelocityCalled_ = setVelocityCalled;
453
454 if (setVelocityCalled_ || !constantSamplingTimeMode) {
456 setVelocityCalled = false;
458
460
461 double ellapsedTime = (tcur - tprev) * 1e-3;
462 if (constantSamplingTimeMode) { // if we want a constant velocity, we
463 // force the ellapsed time to the given
464 // samplingTime
465 ellapsedTime = getSamplingTime(); // in second
466 }
467
468 vpColVector articularCoordinates = get_artCoord();
469 vpColVector articularVelocities = get_artVel();
470
471 if (jointLimit) {
472 double art = articularCoordinates[jointLimitArt - 1] + ellapsedTime * articularVelocities[jointLimitArt - 1];
473 if (art <= _joint_min[jointLimitArt - 1] || art >= _joint_max[jointLimitArt - 1]) {
474 if (verbose_) {
475 std::cout << "Joint " << jointLimitArt - 1
476 << " reaches a limit: " << vpMath::deg(_joint_min[jointLimitArt - 1]) << " < " << vpMath::deg(art)
477 << " < " << vpMath::deg(_joint_max[jointLimitArt - 1]) << std::endl;
478 }
479
480 articularVelocities = 0.0;
481 }
482 else
483 jointLimit = false;
484 }
485
486 articularCoordinates[0] = articularCoordinates[0] + ellapsedTime * articularVelocities[0];
487 articularCoordinates[1] = articularCoordinates[1] + ellapsedTime * articularVelocities[1];
488 articularCoordinates[2] = articularCoordinates[2] + ellapsedTime * articularVelocities[2];
489 articularCoordinates[3] = articularCoordinates[3] + ellapsedTime * articularVelocities[3];
490 articularCoordinates[4] = articularCoordinates[4] + ellapsedTime * articularVelocities[4];
491 articularCoordinates[5] = articularCoordinates[5] + ellapsedTime * articularVelocities[5];
492
493 int jl = isInJointLimit();
494
495 if (jl != 0 && jointLimit == false) {
496 if (jl < 0)
497 ellapsedTime = (_joint_min[static_cast<unsigned int>(-jl - 1)] - articularCoordinates[static_cast<unsigned int>(-jl - 1)]) /
498 (articularVelocities[static_cast<unsigned int>(-jl - 1)]);
499 else
500 ellapsedTime = (_joint_max[static_cast<unsigned int>(jl - 1)] - articularCoordinates[static_cast<unsigned int>(jl - 1)]) /
501 (articularVelocities[static_cast<unsigned int>(jl - 1)]);
502
503 for (unsigned int i = 0; i < 6; i++)
504 articularCoordinates[i] = articularCoordinates[i] + ellapsedTime * articularVelocities[i];
505
506 jointLimit = true;
507 jointLimitArt = static_cast<unsigned int>(fabs(static_cast<double>(jl)));
508 }
509
510 set_artCoord(articularCoordinates);
511 set_artVel(articularVelocities);
512
513 compute_fMi();
514
515 if (displayAllowed) {
519 }
520
522 while (get_displayBusy()) {
523 vpTime::wait(2);
524 }
526 set_displayBusy(false);
527 }
528
530 vpHomogeneousMatrix fMit[8];
531 get_fMi(fMit);
532
533 // vpDisplay::displayFrame(I,getExternalCameraPosition
534 // ()*fMi[6],cameraParam,0.2,vpColor::none);
535
536 vpImagePoint iP, iP_1;
537 vpPoint pt(0, 0, 0);
538
541 pt.track(getExternalCameraPosition() * fMit[0]);
544 for (unsigned int k = 1; k < 7; k++) {
545 pt.track(getExternalCameraPosition() * fMit[k - 1]);
547
548 pt.track(getExternalCameraPosition() * fMit[k]);
550
552 }
554 thickness_);
555 }
556
558
560 tcur_1 = tcur;
561 }
562 else {
564 }
565
566 m_mutex_robotStop.lock();
567 stop = robotStop;
568 m_mutex_robotStop.unlock();
569 }
570}
571
586{
587 // vpColVector q = get_artCoord();
588 vpColVector q(6); //; = get_artCoord();
589 q = get_artCoord();
590
591 vpHomogeneousMatrix fMit[8];
592
593 double q1 = q[0];
594 double q2 = q[1];
595 double q3 = q[2];
596 double q4 = q[3];
597 double q5 = q[4];
598 double q6 = q[5];
599
600 double c4 = cos(q4);
601 double s4 = sin(q4);
602 double c5 = cos(q5);
603 double s5 = sin(q5);
604 double c6 = cos(q6);
605 double s6 = sin(q6);
606
607 fMit[0][0][0] = 1;
608 fMit[0][1][0] = 0;
609 fMit[0][2][0] = 0;
610 fMit[0][0][1] = 0;
611 fMit[0][1][1] = 1;
612 fMit[0][2][1] = 0;
613 fMit[0][0][2] = 0;
614 fMit[0][1][2] = 0;
615 fMit[0][2][2] = 1;
616 fMit[0][0][3] = q1;
617 fMit[0][1][3] = 0;
618 fMit[0][2][3] = 0;
619
620 fMit[1][0][0] = 1;
621 fMit[1][1][0] = 0;
622 fMit[1][2][0] = 0;
623 fMit[1][0][1] = 0;
624 fMit[1][1][1] = 1;
625 fMit[1][2][1] = 0;
626 fMit[1][0][2] = 0;
627 fMit[1][1][2] = 0;
628 fMit[1][2][2] = 1;
629 fMit[1][0][3] = q1;
630 fMit[1][1][3] = q2;
631 fMit[1][2][3] = 0;
632
633 fMit[2][0][0] = 1;
634 fMit[2][1][0] = 0;
635 fMit[2][2][0] = 0;
636 fMit[2][0][1] = 0;
637 fMit[2][1][1] = 1;
638 fMit[2][2][1] = 0;
639 fMit[2][0][2] = 0;
640 fMit[2][1][2] = 0;
641 fMit[2][2][2] = 1;
642 fMit[2][0][3] = q1;
643 fMit[2][1][3] = q2;
644 fMit[2][2][3] = q3;
645
646 fMit[3][0][0] = s4;
647 fMit[3][1][0] = -c4;
648 fMit[3][2][0] = 0;
649 fMit[3][0][1] = c4;
650 fMit[3][1][1] = s4;
651 fMit[3][2][1] = 0;
652 fMit[3][0][2] = 0;
653 fMit[3][1][2] = 0;
654 fMit[3][2][2] = 1;
655 fMit[3][0][3] = q1;
656 fMit[3][1][3] = q2;
657 fMit[3][2][3] = q3;
658
659 fMit[4][0][0] = s4 * s5;
660 fMit[4][1][0] = -c4 * s5;
661 fMit[4][2][0] = c5;
662 fMit[4][0][1] = s4 * c5;
663 fMit[4][1][1] = -c4 * c5;
664 fMit[4][2][1] = -s5;
665 fMit[4][0][2] = c4;
666 fMit[4][1][2] = s4;
667 fMit[4][2][2] = 0;
668 fMit[4][0][3] = c4 * this->_long_56 + q1;
669 fMit[4][1][3] = s4 * this->_long_56 + q2;
670 fMit[4][2][3] = q3;
671
672 fMit[5][0][0] = s4 * s5 * c6 + c4 * s6;
673 fMit[5][1][0] = -c4 * s5 * c6 + s4 * s6;
674 fMit[5][2][0] = c5 * c6;
675 fMit[5][0][1] = -s4 * s5 * s6 + c4 * c6;
676 fMit[5][1][1] = c4 * s5 * s6 + s4 * c6;
677 fMit[5][2][1] = -c5 * s6;
678 fMit[5][0][2] = -s4 * c5;
679 fMit[5][1][2] = c4 * c5;
680 fMit[5][2][2] = s5;
681 fMit[5][0][3] = c4 * this->_long_56 + q1;
682 fMit[5][1][3] = s4 * this->_long_56 + q2;
683 fMit[5][2][3] = q3;
684
685 fMit[6][0][0] = fMit[5][0][0];
686 fMit[6][1][0] = fMit[5][1][0];
687 fMit[6][2][0] = fMit[5][2][0];
688 fMit[6][0][1] = fMit[5][0][1];
689 fMit[6][1][1] = fMit[5][1][1];
690 fMit[6][2][1] = fMit[5][2][1];
691 fMit[6][0][2] = fMit[5][0][2];
692 fMit[6][1][2] = fMit[5][1][2];
693 fMit[6][2][2] = fMit[5][2][2];
694 fMit[6][0][3] = fMit[5][0][3];
695 fMit[6][1][3] = fMit[5][1][3];
696 fMit[6][2][3] = fMit[5][2][3];
697
698 // vpHomogeneousMatrix cMe;
699 // get_cMe(cMe);
700 // cMe = cMe.inverse();
701 // fMit[7] = fMit[6] * cMe;
702 m_mutex_eMc.lock();
703 vpAfma6::get_fMc(q, fMit[7]);
704 m_mutex_eMc.unlock();
705
706 m_mutex_fMi.lock();
707 for (int i = 0; i < 8; i++) {
708 fMi[i] = fMit[i];
709 }
710 m_mutex_fMi.unlock();
711}
712
719{
720 switch (newState) {
721 case vpRobot::STATE_STOP: {
722 // Start primitive STOP only if the current state is Velocity
724 stopMotion();
725 }
726 break;
727 }
730 std::cout << "Change the control mode from velocity to position control.\n";
731 stopMotion();
732 }
733 else {
734 // std::cout << "Change the control mode from stop to position
735 // control.\n";
736 }
737 break;
738 }
741 std::cout << "Change the control mode from stop to velocity control.\n";
742 }
743 break;
744 }
746 default:
747 break;
748 }
749
750 return vpRobot::setRobotState(newState);
751}
752
830{
832 vpERROR_TRACE("Cannot send a velocity to the robot "
833 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
835 "Cannot send a velocity to the robot "
836 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
837 }
838
839 vpColVector vel_sat(6);
840
841 double scale_sat = 1;
842 double vel_trans_max = getMaxTranslationVelocity();
843 double vel_rot_max = getMaxRotationVelocity();
844
845 double vel_abs; // Absolute value
846
847 // Velocity saturation
848 switch (frame) {
849 // saturation in cartesian space
852 if (vel.getRows() != 6) {
853 vpERROR_TRACE("The velocity vector must have a size of 6 !!!!");
854 throw;
855 }
856
857 for (unsigned int i = 0; i < 3; ++i) {
858 vel_abs = fabs(vel[i]);
859 if (vel_abs > vel_trans_max && !jointLimit) {
860 vel_trans_max = vel_abs;
861 vpERROR_TRACE("Excess velocity %g m/s in TRANSLATION "
862 "(axis nr. %d).",
863 vel[i], i + 1);
864 }
865
866 vel_abs = fabs(vel[i + 3]);
867 if (vel_abs > vel_rot_max && !jointLimit) {
868 vel_rot_max = vel_abs;
869 vpERROR_TRACE("Excess velocity %g rad/s in ROTATION "
870 "(axis nr. %d).",
871 vel[i + 3], i + 4);
872 }
873 }
874
875 double scale_trans_sat = 1;
876 double scale_rot_sat = 1;
877 if (vel_trans_max > getMaxTranslationVelocity())
878 scale_trans_sat = getMaxTranslationVelocity() / vel_trans_max;
879
880 if (vel_rot_max > getMaxRotationVelocity())
881 scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
882
883 if ((scale_trans_sat < 1) || (scale_rot_sat < 1)) {
884 if (scale_trans_sat < scale_rot_sat)
885 scale_sat = scale_trans_sat;
886 else
887 scale_sat = scale_rot_sat;
888 }
889 break;
890 }
891
892 // saturation in joint space
894 if (vel.getRows() != 6) {
895 vpERROR_TRACE("The velocity vector must have a size of 6 !!!!");
896 throw;
897 }
898 for (unsigned int i = 0; i < 6; ++i) {
899 vel_abs = fabs(vel[i]);
900 if (vel_abs > vel_rot_max && !jointLimit) {
901 vel_rot_max = vel_abs;
902 vpERROR_TRACE("Excess velocity %g rad/s in ROTATION "
903 "(axis nr. %d).",
904 vel[i], i + 1);
905 }
906 }
907 double scale_rot_sat = 1;
908 if (vel_rot_max > getMaxRotationVelocity())
909 scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
910 if (scale_rot_sat < 1)
911 scale_sat = scale_rot_sat;
912 break;
913 }
914 case vpRobot::MIXT_FRAME: {
915 throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in MIXT_FRAME frame:"
916 "functionality not implemented");
917 }
919 throw vpRobotException(vpRobotException::wrongStateError, "Cannot set a velocity in END_EFFECTOR_FRAME frame:"
920 "functionality not implemented");
921 }
922 }
923
924 set_velocity(vel * scale_sat);
925
926 m_mutex_frame.lock();
927 setRobotFrame(frame);
928 m_mutex_frame.unlock();
929
931 setVelocityCalled = true;
933}
934
939{
941
942 m_mutex_frame.lock();
943 frame = getRobotFrame();
944 m_mutex_frame.unlock();
945
946 double vel_rot_max = getMaxRotationVelocity();
947
948 vpColVector articularCoordinates = get_artCoord();
949 vpColVector velocityframe = get_velocity();
950 vpColVector articularVelocity;
951
952 switch (frame) {
954 vpMatrix eJe_;
956 vpAfma6::get_eJe(articularCoordinates, eJe_);
957 eJe_ = eJe_.pseudoInverse();
959 singularityTest(articularCoordinates, eJe_);
960 articularVelocity = eJe_ * eVc * velocityframe;
961 set_artVel(articularVelocity);
962 break;
963 }
965 vpMatrix fJe_;
966 vpAfma6::get_fJe(articularCoordinates, fJe_);
967 fJe_ = fJe_.pseudoInverse();
969 singularityTest(articularCoordinates, fJe_);
970 articularVelocity = fJe_ * velocityframe;
971 set_artVel(articularVelocity);
972 break;
973 }
975 articularVelocity = velocityframe;
976 set_artVel(articularVelocity);
977 break;
978 }
980 case vpRobot::MIXT_FRAME: {
981 break;
982 }
983 }
984
985 switch (frame) {
988 for (unsigned int i = 0; i < 6; ++i) {
989 double vel_abs = fabs(articularVelocity[i]);
990 if (vel_abs > vel_rot_max && !jointLimit) {
991 vel_rot_max = vel_abs;
992 vpERROR_TRACE("Excess velocity %g rad/s in ROTATION "
993 "(axis nr. %d).",
994 articularVelocity[i], i + 1);
995 }
996 }
997 double scale_rot_sat = 1;
998 double scale_sat = 1;
999 if (vel_rot_max > getMaxRotationVelocity())
1000 scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
1001 if (scale_rot_sat < 1)
1002 scale_sat = scale_rot_sat;
1003
1004 set_artVel(articularVelocity * scale_sat);
1005 break;
1006 }
1009 case vpRobot::MIXT_FRAME: {
1010 break;
1011 }
1012 }
1013}
1014
1065{
1066 vel.resize(6);
1067
1068 vpColVector articularCoordinates = get_artCoord();
1069 vpColVector articularVelocity = get_artVel();
1070
1071 switch (frame) {
1072 case vpRobot::CAMERA_FRAME: {
1073 vpMatrix eJe_;
1075 vpAfma6::get_eJe(articularCoordinates, eJe_);
1076 vel = cVe * eJe_ * articularVelocity;
1077 break;
1078 }
1080 vel = articularVelocity;
1081 break;
1082 }
1084 vpMatrix fJe_;
1085 vpAfma6::get_fJe(articularCoordinates, fJe_);
1086 vel = fJe_ * articularVelocity;
1087 break;
1088 }
1090 case vpRobot::MIXT_FRAME: {
1091 break;
1092 }
1093 default: {
1094 vpERROR_TRACE("Error in spec of vpRobot. "
1095 "Case not taken in account.");
1096 return;
1097 }
1098 }
1099}
1100
1118{
1119 timestamp = vpTime::measureTimeSecond();
1120 getVelocity(frame, vel);
1121}
1122
1169{
1170 vpColVector vel(6);
1171 getVelocity(frame, vel);
1172
1173 return vel;
1174}
1175
1189{
1190 timestamp = vpTime::measureTimeSecond();
1191 vpColVector vel(6);
1192 getVelocity(frame, vel);
1193
1194 return vel;
1195}
1196
1198{
1199 double vel_rot_max = getMaxRotationVelocity();
1200 double velmax = fabs(q[0]);
1201 for (unsigned int i = 1; i < 6; i++) {
1202 if (velmax < fabs(q[i]))
1203 velmax = fabs(q[i]);
1204 }
1205
1206 double alpha = (getPositioningVelocity() * vel_rot_max) / (velmax * 100);
1207 q = q * alpha;
1208}
1209
1289{
1291 vpERROR_TRACE("Robot was not in position-based control\n"
1292 "Modification of the robot state");
1293 // setRobotState(vpRobot::STATE_POSITION_CONTROL) ;
1294 }
1295
1296 vpColVector articularCoordinates = get_artCoord();
1297
1298 vpColVector error(6);
1299 double errsqr = 0;
1300 switch (frame) {
1301 case vpRobot::CAMERA_FRAME: {
1302 int nbSol;
1303 vpColVector qdes(6);
1304
1306 vpRxyzVector rxyz;
1307 for (unsigned int i = 0; i < 3; i++) {
1308 txyz[i] = q[i];
1309 rxyz[i] = q[i + 3];
1310 }
1311
1312 vpRotationMatrix cRc2(rxyz);
1313 vpHomogeneousMatrix cMc2(txyz, cRc2);
1314
1316 vpAfma6::get_fMc(articularCoordinates, fMc_);
1317
1318 vpHomogeneousMatrix fMc2 = fMc_ * cMc2;
1319
1320 do {
1321 articularCoordinates = get_artCoord();
1322 qdes = articularCoordinates;
1323 nbSol = getInverseKinematics(fMc2, qdes, true, verbose_);
1324
1326 setVelocityCalled = true;
1328
1329 if (nbSol > 0) {
1330 error = qdes - articularCoordinates;
1331 errsqr = error.sumSquare();
1332 // findHighestPositioningSpeed(error);
1333 set_artVel(error);
1334 if (errsqr < 1e-4) {
1335 set_artCoord(qdes);
1336 error = 0;
1337 set_artVel(error);
1338 set_velocity(error);
1339 break;
1340 }
1341 }
1342 else {
1343 vpERROR_TRACE("Positioning error.");
1344 throw vpRobotException(vpRobotException::positionOutOfRangeError, "Position out of range.");
1345 }
1346 } while (errsqr > 1e-8 && nbSol > 0);
1347
1348 break;
1349 }
1350
1352 do {
1353 articularCoordinates = get_artCoord();
1354 error = q - articularCoordinates;
1355 errsqr = error.sumSquare();
1356 // findHighestPositioningSpeed(error);
1357 set_artVel(error);
1359 setVelocityCalled = true;
1361 if (errsqr < 1e-4) {
1362 set_artCoord(q);
1363 error = 0;
1364 set_artVel(error);
1365 set_velocity(error);
1366 break;
1367 }
1368 } while (errsqr > 1e-8);
1369 break;
1370 }
1371
1373 int nbSol;
1374 vpColVector qdes(6);
1375
1377 vpRxyzVector rxyz;
1378 for (unsigned int i = 0; i < 3; i++) {
1379 txyz[i] = q[i];
1380 rxyz[i] = q[i + 3];
1381 }
1382
1383 vpRotationMatrix fRc(rxyz);
1384 vpHomogeneousMatrix fMc_(txyz, fRc);
1385
1386 do {
1387 articularCoordinates = get_artCoord();
1388 qdes = articularCoordinates;
1389 nbSol = getInverseKinematics(fMc_, qdes, true, verbose_);
1391 setVelocityCalled = true;
1393 if (nbSol > 0) {
1394 error = qdes - articularCoordinates;
1395 errsqr = error.sumSquare();
1396 // findHighestPositioningSpeed(error);
1397 set_artVel(error);
1398 if (errsqr < 1e-4) {
1399 set_artCoord(qdes);
1400 error = 0;
1401 set_artVel(error);
1402 set_velocity(error);
1403 break;
1404 }
1405 }
1406 else
1407 vpERROR_TRACE("Positioning error. Position unreachable");
1408 } while (errsqr > 1e-8 && nbSol > 0);
1409 break;
1410 }
1411 case vpRobot::MIXT_FRAME: {
1412 vpERROR_TRACE("Positioning error. Mixt frame not implemented");
1413 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1414 "MIXT_FRAME not implemented.");
1415 }
1417 vpERROR_TRACE("Positioning error. Mixt frame not implemented");
1418 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1419 "END_EFFECTOR_FRAME not implemented.");
1420 }
1421 }
1422}
1423
1489void vpSimulatorAfma6::setPosition(const vpRobot::vpControlFrameType frame, double pos1, double pos2, double pos3,
1490 double pos4, double pos5, double pos6)
1491{
1492 try {
1493 vpColVector position(6);
1494 position[0] = pos1;
1495 position[1] = pos2;
1496 position[2] = pos3;
1497 position[3] = pos4;
1498 position[4] = pos5;
1499 position[5] = pos6;
1500
1501 setPosition(frame, position);
1502 }
1503 catch (...) {
1504 vpERROR_TRACE("Error caught");
1505 throw;
1506 }
1507}
1508
1547void vpSimulatorAfma6::setPosition(const char *filename)
1548{
1549 vpColVector q;
1550 bool ret;
1551
1552 ret = this->readPosFile(filename, q);
1553
1554 if (ret == false) {
1555 vpERROR_TRACE("Bad position in \"%s\"", filename);
1556 throw vpRobotException(vpRobotException::lowLevelError, "Bad position in filename.");
1557 }
1560}
1561
1625{
1626 q.resize(6);
1627
1628 switch (frame) {
1629 case vpRobot::CAMERA_FRAME: {
1630 q = 0;
1631 break;
1632 }
1633
1635 q = get_artCoord();
1636 break;
1637 }
1638
1642
1643 vpRotationMatrix fRc;
1644 fMc_.extract(fRc);
1645 vpRxyzVector rxyz(fRc);
1646
1648 fMc_.extract(txyz);
1649
1650 for (unsigned int i = 0; i < 3; i++) {
1651 q[i] = txyz[i];
1652 q[i + 3] = rxyz[i];
1653 }
1654 break;
1655 }
1656
1657 case vpRobot::MIXT_FRAME: {
1658 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1659 "Mixt frame not implemented.");
1660 }
1662 throw vpRobotException(vpRobotException::lowLevelError, "Positioning error: "
1663 "End-effector frame not implemented.");
1664 }
1665 }
1666}
1667
1695{
1696 timestamp = vpTime::measureTimeSecond();
1697 getPosition(frame, q);
1698}
1699
1712{
1713 vpColVector posRxyz;
1714 // recupere position en Rxyz
1715 this->getPosition(frame, posRxyz);
1716
1717 // recupere le vecteur thetaU correspondant
1718 vpThetaUVector RtuVect(vpRxyzVector(posRxyz[3], posRxyz[4], posRxyz[5]));
1719
1720 // remplit le vpPoseVector avec translation et rotation ThetaU
1721 for (unsigned int j = 0; j < 3; j++) {
1722 position[j] = posRxyz[j];
1723 position[j + 3] = RtuVect[j];
1724 }
1725}
1726
1738void vpSimulatorAfma6::getPosition(const vpRobot::vpControlFrameType frame, vpPoseVector &position, double &timestamp)
1739{
1740 timestamp = vpTime::measureTimeSecond();
1741 getPosition(frame, position);
1742}
1743
1754void vpSimulatorAfma6::setJointLimit(const vpColVector &limitMin, const vpColVector &limitMax)
1755{
1756 if (limitMin.getRows() != 6 || limitMax.getRows() != 6) {
1757 vpTRACE("Joint limit vector has not a size of 6 !");
1758 return;
1759 }
1760
1761 _joint_min[0] = limitMin[0];
1762 _joint_min[1] = limitMin[1];
1763 _joint_min[2] = limitMin[2];
1764 _joint_min[3] = limitMin[3];
1765 _joint_min[4] = limitMin[4];
1766 _joint_min[5] = limitMin[5];
1767
1768 _joint_max[0] = limitMax[0];
1769 _joint_max[1] = limitMax[1];
1770 _joint_max[2] = limitMax[2];
1771 _joint_max[3] = limitMax[3];
1772 _joint_max[4] = limitMax[4];
1773 _joint_max[5] = limitMax[5];
1774}
1775
1782{
1783 double q5 = q[4];
1784
1785 bool cond = fabs(q5 - M_PI / 2) < 1e-1;
1786
1787 if (cond) {
1788 J[0][3] = 0;
1789 J[0][4] = 0;
1790 J[1][3] = 0;
1791 J[1][4] = 0;
1792 J[3][3] = 0;
1793 J[3][4] = 0;
1794 J[5][3] = 0;
1795 J[5][4] = 0;
1796 return true;
1797 }
1798
1799 return false;
1800}
1801
1806{
1807 int artNumb = 0;
1808 double diff = 0;
1809 double difft = 0;
1810
1811 vpColVector articularCoordinates = get_artCoord();
1812
1813 for (unsigned int i = 0; i < 6; i++) {
1814 if (articularCoordinates[i] <= _joint_min[i]) {
1815 difft = _joint_min[i] - articularCoordinates[i];
1816 if (difft > diff) {
1817 diff = difft;
1818 artNumb = -static_cast<int>(i) - 1;
1819 }
1820 }
1821 }
1822
1823 for (unsigned int i = 0; i < 6; i++) {
1824 if (articularCoordinates[i] >= _joint_max[i]) {
1825 difft = articularCoordinates[i] - _joint_max[i];
1826 if (difft > diff) {
1827 diff = difft;
1828 artNumb = static_cast<int>(i + 1);
1829 }
1830 }
1831 }
1832
1833 if (artNumb != 0)
1834 std::cout << "\nWarning: Velocity control stopped: axis " << fabs(static_cast<float>(artNumb)) << " on joint limit!"
1835 << std::endl;
1836
1837 return artNumb;
1838}
1839
1858{
1859 displacement.resize(6);
1860 displacement = 0;
1861 vpColVector q_cur(6);
1862
1863 q_cur = get_artCoord();
1864
1865 if (!first_time_getdis) {
1866 switch (frame) {
1867 case vpRobot::CAMERA_FRAME: {
1868 std::cout << "getDisplacement() CAMERA_FRAME not implemented\n";
1869 return;
1870 }
1872 displacement = q_cur - q_prev_getdis;
1873 break;
1874 }
1876 std::cout << "getDisplacement() REFERENCE_FRAME not implemented\n";
1877 return;
1878 }
1879 case vpRobot::MIXT_FRAME: {
1880 std::cout << "getDisplacement() MIXT_FRAME not implemented\n";
1881 return;
1882 }
1884 std::cout << "getDisplacement() END_EFFECTOR_FRAME not implemented\n";
1885 return;
1886 }
1887 }
1888 }
1889 else {
1890 first_time_getdis = false;
1891 }
1892
1893 // Memorize the joint position for the next call
1894 q_prev_getdis = q_cur;
1895}
1896
1944bool vpSimulatorAfma6::readPosFile(const std::string &filename, vpColVector &q)
1945{
1946 std::ifstream fd(filename.c_str(), std::ios::in);
1947
1948 if (!fd.is_open()) {
1949 return false;
1950 }
1951
1952 std::string line;
1953 std::string key("R:");
1954 std::string id("#AFMA6 - Position");
1955 bool pos_found = false;
1956 int lineNum = 0;
1957
1958 q.resize(njoint);
1959
1960 while (std::getline(fd, line)) {
1961 lineNum++;
1962 if (lineNum == 1) {
1963 if (!(line.compare(0, id.size(), id) == 0)) { // check if Afma6 position file
1964 std::cout << "Error: this position file " << filename << " is not for Afma6 robot" << std::endl;
1965 return false;
1966 }
1967 }
1968 if ((line.compare(0, 1, "#") == 0)) { // skip comment
1969 continue;
1970 }
1971 if ((line.compare(0, key.size(), key) == 0)) { // decode position
1972 // check if there are at least njoint values in the line
1973 std::vector<std::string> chain = vpIoTools::splitChain(line, std::string(" "));
1974 if (chain.size() < njoint + 1) // try to split with tab separator
1975 chain = vpIoTools::splitChain(line, std::string("\t"));
1976 if (chain.size() < njoint + 1)
1977 continue;
1978
1979 std::istringstream ss(line);
1980 std::string key_;
1981 ss >> key_;
1982 for (unsigned int i = 0; i < njoint; i++)
1983 ss >> q[i];
1984 pos_found = true;
1985 break;
1986 }
1987 }
1988
1989 // converts rotations from degrees into radians
1990 q[3] = vpMath::rad(q[3]);
1991 q[4] = vpMath::rad(q[4]);
1992 q[5] = vpMath::rad(q[5]);
1993
1994 fd.close();
1995
1996 if (!pos_found) {
1997 std::cout << "Error: unable to find a position for Afma6 robot in " << filename << std::endl;
1998 return false;
1999 }
2000
2001 return true;
2002}
2003
2026bool vpSimulatorAfma6::savePosFile(const std::string &filename, const vpColVector &q)
2027{
2028 FILE *fd;
2029 fd = fopen(filename.c_str(), "w");
2030 if (fd == nullptr)
2031 return false;
2032
2033 fprintf(fd, "\
2034#AFMA6 - Position - Version 2.01\n\
2035#\n\
2036# R: X Y Z A B C\n\
2037# Joint position: X, Y, Z: translations in meters\n\
2038# A, B, C: rotations in degrees\n\
2039#\n\
2040#\n\n");
2041
2042 // Save positions in mm and deg
2043 fprintf(fd, "R: %lf %lf %lf %lf %lf %lf\n", q[0], q[1], q[2], vpMath::deg(q[3]), vpMath::deg(q[4]),
2044 vpMath::deg(q[5]));
2045
2046 fclose(fd);
2047 return (true);
2048}
2049
2057void vpSimulatorAfma6::move(const char *filename)
2058{
2059 vpColVector q;
2060
2061 try {
2062 this->readPosFile(filename, q);
2065 }
2066 catch (...) {
2067 throw;
2068 }
2069}
2070
2081
2090{
2092 vpAfma6::get_cMe(cMe);
2093
2094 cVe.buildFrom(cMe);
2095}
2096
2107{
2108 try {
2110 }
2111 catch (...) {
2112 vpERROR_TRACE("catch exception ");
2113 throw;
2114 }
2115}
2116
2128{
2129 try {
2130 vpColVector articularCoordinates = get_artCoord();
2131 vpAfma6::get_fJe(articularCoordinates, fJe_);
2132 }
2133 catch (...) {
2134 vpERROR_TRACE("Error caught");
2135 throw;
2136 }
2137}
2138
2143{
2145 return;
2146
2147 vpColVector stop(6);
2148 stop = 0;
2149 set_artVel(stop);
2150 set_velocity(stop);
2152}
2153
2163{
2164 // set scene_dir from #define VISP_SCENE_DIR if it exists
2165 // VISP_SCENES_DIR may contain multiple locations separated by ";"
2166 std::string scene_dir_;
2167 std::vector<std::string> scene_dirs = vpIoTools::splitChain(std::string(VISP_SCENES_DIR), std::string(";"));
2168 bool sceneDirExists = false;
2169 for (size_t i = 0; i < scene_dirs.size(); i++)
2170 if (vpIoTools::checkDirectory(scene_dirs[i]) == true) { // directory exists
2171 scene_dir_ = scene_dirs[i];
2172 sceneDirExists = true;
2173 break;
2174 }
2175 if (!sceneDirExists) {
2176 try {
2177 scene_dir_ = vpIoTools::getenv("VISP_SCENES_DIR");
2178 std::cout << "The simulator uses data from VISP_SCENES_DIR=" << scene_dir_ << std::endl;
2179 }
2180 catch (...) {
2181 std::cout << "Cannot get VISP_SCENES_DIR environment variable" << std::endl;
2182 }
2183 }
2184
2185 unsigned int name_length = 30; // the size of this kind of string "/afma6_arm2.bnd"
2186 if (scene_dir_.size() > FILENAME_MAX)
2187 throw vpException(vpException::dimensionError, "Cannot initialize Afma6 simulator");
2188 unsigned int full_length = static_cast<unsigned int>(scene_dir_.size()) + name_length;
2189 if (full_length > FILENAME_MAX)
2190 throw vpException(vpException::dimensionError, "Cannot initialize Afma6 simulator");
2191
2192 char *name_cam = new char[full_length];
2193
2194 strcpy(name_cam, scene_dir_.c_str());
2195 strcat(name_cam, "/camera.bnd");
2196 set_scene(name_cam, &camera, cameraFactor);
2197
2198 if (arm_dir.size() > FILENAME_MAX)
2199 throw vpException(vpException::dimensionError, "Cannot initialize Afma6 simulator");
2200 full_length = static_cast<unsigned int>(arm_dir.size()) + name_length;
2201 if (full_length > FILENAME_MAX)
2202 throw vpException(vpException::dimensionError, "Cannot initialize Afma6 simulator");
2203
2204 char *name_arm = new char[full_length];
2205 strcpy(name_arm, arm_dir.c_str());
2206 strcat(name_arm, "/afma6_gate.bnd");
2207 std::cout << "name arm: " << name_arm << std::endl;
2208 set_scene(name_arm, robotArms, 1.0);
2209 strcpy(name_arm, arm_dir.c_str());
2210 strcat(name_arm, "/afma6_arm1.bnd");
2211 set_scene(name_arm, robotArms + 1, 1.0);
2212 strcpy(name_arm, arm_dir.c_str());
2213 strcat(name_arm, "/afma6_arm2.bnd");
2214 set_scene(name_arm, robotArms + 2, 1.0);
2215 strcpy(name_arm, arm_dir.c_str());
2216 strcat(name_arm, "/afma6_arm3.bnd");
2217 set_scene(name_arm, robotArms + 3, 1.0);
2218 strcpy(name_arm, arm_dir.c_str());
2219 strcat(name_arm, "/afma6_arm4.bnd");
2220 set_scene(name_arm, robotArms + 4, 1.0);
2221
2223 tool = getToolType();
2224 strcpy(name_arm, arm_dir.c_str());
2225 switch (tool) {
2226 case vpAfma6::TOOL_CCMOP: {
2227 strcat(name_arm, "/afma6_tool_ccmop.bnd");
2228 break;
2229 }
2230 case vpAfma6::TOOL_GRIPPER: {
2231 strcat(name_arm, "/afma6_tool_gripper.bnd");
2232 break;
2233 }
2234 case vpAfma6::TOOL_VACUUM: {
2235 strcat(name_arm, "/afma6_tool_vacuum.bnd");
2236 break;
2237 }
2238 case vpAfma6::TOOL_CUSTOM: {
2239 std::cout << "The custom tool is not handled in vpSimulatorAfma6.cpp" << std::endl;
2240 break;
2241 }
2243 std::cout << "The Intel D435 camera is not handled in vpSimulatorAfma6.cpp" << std::endl;
2244 break;
2245 }
2247 std::cout << "The generic camera is not handled in vpSimulatorAfma6.cpp" << std::endl;
2248 break;
2249 }
2250 }
2251 set_scene(name_arm, robotArms + 5, 1.0);
2252
2253 add_rfstack(IS_BACK);
2254
2255 add_vwstack("start", "depth", 0.0, 100.0);
2256 add_vwstack("start", "window", -0.1, 0.1, -0.1, 0.1);
2257 add_vwstack("start", "type", PERSPECTIVE);
2258 //
2259 // sceneInitialized = true;
2260 // displayObject = true;
2261 displayCamera = true;
2262
2263 delete[] name_cam;
2264 delete[] name_arm;
2265}
2266
2268{
2269 m_mutex_scene.lock();
2270 bool changed = false;
2271 vpHomogeneousMatrix displacement = navigation(I_, changed);
2272
2273 // if (displacement[2][3] != 0)
2274 if (std::fabs(displacement[2][3]) > std::numeric_limits<double>::epsilon())
2275 camMf2 = camMf2 * displacement;
2276
2277 f2Mf = camMf2.inverse() * camMf;
2278
2279 camMf = camMf2 * displacement * f2Mf;
2280
2281 double u;
2282 double v;
2283 // if(px_ext != 1 && py_ext != 1)
2284 // we assume px_ext and py_ext > 0
2285 if ((std::fabs(px_ext - 1.) > vpMath::maximum(px_ext, 1.) * std::numeric_limits<double>::epsilon()) &&
2286 (std::fabs(py_ext - 1) > vpMath::maximum(py_ext, 1.) * std::numeric_limits<double>::epsilon())) {
2287 u = static_cast<double>(I_.getWidth()) / (2 * px_ext);
2288 v = static_cast<double>(I_.getHeight()) / (2 * py_ext);
2289 }
2290 else {
2291 u = static_cast<double>(I_.getWidth()) / (vpMath::minimum(I_.getWidth(), I_.getHeight()));
2292 v = static_cast<double>(I_.getHeight()) / (vpMath::minimum(I_.getWidth(), I_.getHeight()));
2293 }
2294
2295 float w44o[4][4], w44cext[4][4], x, y, z;
2296
2297 vp2jlc_matrix(camMf.inverse(), w44cext);
2298
2299 add_vwstack("start", "cop", w44cext[3][0], w44cext[3][1], w44cext[3][2]);
2300 x = w44cext[2][0] + w44cext[3][0];
2301 y = w44cext[2][1] + w44cext[3][1];
2302 z = w44cext[2][2] + w44cext[3][2];
2303 add_vwstack("start", "vrp", x, y, z);
2304 add_vwstack("start", "vpn", w44cext[2][0], w44cext[2][1], w44cext[2][2]);
2305 add_vwstack("start", "vup", w44cext[1][0], w44cext[1][1], w44cext[1][2]);
2306 add_vwstack("start", "window", -u, u, -v, v);
2307
2308 vpHomogeneousMatrix fMit[8];
2309 get_fMi(fMit);
2310
2311 vp2jlc_matrix(vpHomogeneousMatrix(0, 0, 0, 0, 0, 0), w44o);
2312 display_scene(w44o, robotArms[0], I_, curColor);
2313
2314 vp2jlc_matrix(fMit[0], w44o);
2315 display_scene(w44o, robotArms[1], I_, curColor);
2316
2317 vp2jlc_matrix(fMit[2], w44o);
2318 display_scene(w44o, robotArms[2], I_, curColor);
2319
2320 vp2jlc_matrix(fMit[3], w44o);
2321 display_scene(w44o, robotArms[3], I_, curColor);
2322
2323 vp2jlc_matrix(fMit[4], w44o);
2324 display_scene(w44o, robotArms[4], I_, curColor);
2325
2326 vp2jlc_matrix(fMit[5], w44o);
2327 display_scene(w44o, robotArms[5], I_, curColor);
2328
2329 if (displayCamera) {
2331 get_cMe(cMe);
2332 cMe = cMe.inverse();
2333 cMe = fMit[6] * cMe;
2334 vp2jlc_matrix(cMe, w44o);
2335 display_scene(w44o, camera, I_, camColor);
2336 }
2337
2338 if (displayObject) {
2339 vp2jlc_matrix(fMo, w44o);
2340 display_scene(w44o, scene, I_, curColor);
2341 }
2342 m_mutex_scene.unlock();
2343}
2344
2363{
2364 vpColVector stop(6);
2365 bool status = true;
2366 stop = 0;
2367 m_mutex_scene.lock();
2368 set_artVel(stop);
2369 set_velocity(stop);
2371 fMc_ = fMo * cMo_.inverse();
2372
2373 vpColVector articularCoordinates = get_artCoord();
2374 int nbSol = getInverseKinematics(fMc_, articularCoordinates, true, verbose_);
2375
2376 if (nbSol == 0) {
2377 status = false;
2378 vpERROR_TRACE("Positioning error. Position unreachable");
2379 }
2380
2381 if (verbose_)
2382 std::cout << "Used joint coordinates (rad): " << articularCoordinates.t() << std::endl;
2383
2384 set_artCoord(articularCoordinates);
2385
2386 compute_fMi();
2387 m_mutex_scene.unlock();
2388
2389 return status;
2390}
2391
2406{
2407 vpColVector stop(6);
2408 stop = 0;
2409 m_mutex_scene.lock();
2410 set_artVel(stop);
2411 set_velocity(stop);
2412 vpHomogeneousMatrix fMit[8];
2413 get_fMi(fMit);
2414 fMo = fMit[7] * cMo_;
2415 m_mutex_scene.unlock();
2416}
2417
2429bool vpSimulatorAfma6::setPosition(const vpHomogeneousMatrix &cdMo_, vpImage<unsigned char> *Iint, const double &errMax)
2430{
2431 // get rid of max velocity
2432 double vMax = getMaxTranslationVelocity();
2433 double wMax = getMaxRotationVelocity();
2434 setMaxTranslationVelocity(10. * vMax);
2435 setMaxRotationVelocity(10. * wMax);
2436
2437 vpColVector v(3), w(3), vel(6);
2440 vpRotationMatrix cdRc;
2441 vpThetaUVector cdTUc;
2442 vpColVector err(6);
2443 err = 1.;
2444 const double lambda = 5.;
2445
2447
2448 unsigned int i, iter = 0;
2449 while ((iter++ < 300) && (err.frobeniusNorm() > errMax)) {
2450 double t = vpTime::measureTimeMs();
2451
2452 // update image
2453 if (Iint != nullptr) {
2454 vpDisplay::display(*Iint);
2455 getInternalView(*Iint);
2456 vpDisplay::flush(*Iint);
2457 }
2458
2459 // update pose error
2460 cdMc = cdMo_ * get_cMo().inverse();
2461 cdMc.extract(cdRc);
2462 cdMc.extract(cdTc);
2463 cdTUc.buildFrom(cdRc);
2464
2465 // compute v,w and velocity
2466 v = -lambda * cdRc.t() * cdTc;
2467 w = -lambda * cdTUc;
2468 for (i = 0; i < 3; ++i) {
2469 vel[i] = v[i];
2470 vel[i + 3] = w[i];
2471 err[i] = cdTc[i];
2472 err[i + 3] = cdTUc[i];
2473 }
2474
2475 // update feat
2477
2478 // wait for it
2479 vpTime::wait(t, 10);
2480 }
2481 vel = 0.;
2482 set_velocity(vel);
2483 set_artVel(vel);
2486
2487 // std::cout << "setPosition: final error " << err.t() << std::endl;
2488 return (err.frobeniusNorm() <= errMax);
2489}
2490END_VISP_NAMESPACE
2491#elif !defined(VISP_BUILD_SHARED_LIBS)
2492// Work around to avoid warning: libvisp_robot.a(vpSimulatorAfma6.cpp.o) has
2493// no symbols
2494void dummy_vpSimulatorAfma6() { }
2495#endif
static const char *const CONST_CCMOP_CAMERA_NAME
Definition vpAfma6.h:99
double _joint_min[6]
Definition vpAfma6.h:202
static const unsigned int njoint
Number of joint.
Definition vpAfma6.h:196
vpRxyzVector _erc
Definition vpAfma6.h:205
int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &nearest=true, const bool &verbose=false) const
Definition vpAfma6.cpp:596
void get_cMe(vpHomogeneousMatrix &cMe) const
Definition vpAfma6.cpp:890
void setToolType(vpAfma6::vpAfma6ToolType tool)
Set the current tool type.
Definition vpAfma6.h:192
vpAfma6ToolType getToolType() const
Get the current tool type.
Definition vpAfma6.h:167
static const char *const CONST_GRIPPER_CAMERA_NAME
Definition vpAfma6.h:104
vpHomogeneousMatrix _eMc
Definition vpAfma6.h:207
double _long_56
Definition vpAfma6.h:200
vpTranslationVector _etc
Definition vpAfma6.h:204
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition vpAfma6.cpp:777
vpCameraParameters::vpCameraParametersProjType projModel
Definition vpAfma6.h:213
double _joint_max[6]
Definition vpAfma6.h:201
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
Definition vpAfma6.cpp:934
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
Definition vpAfma6.cpp:1004
vpAfma6ToolType
List of possible tools that can be attached to the robot end-effector.
Definition vpAfma6.h:124
@ TOOL_CCMOP
Definition vpAfma6.h:125
@ TOOL_GENERIC_CAMERA
Definition vpAfma6.h:128
@ TOOL_CUSTOM
Definition vpAfma6.h:130
@ TOOL_VACUUM
Definition vpAfma6.h:127
@ TOOL_INTEL_D435_CAMERA
Definition vpAfma6.h:129
@ TOOL_GRIPPER
Definition vpAfma6.h:126
unsigned int getRows() const
Definition vpArray2D.h:433
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
vpRowVector t() const
double frobeniusNorm() 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)
void getInternalView(vpImage< vpRGBa > &I)
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
void setMaxRotationVelocity(double maxVr)
Definition vpRobot.cpp:259
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
Definition vpRobot.cpp:206
void setMaxTranslationVelocity(double maxVt)
Definition vpRobot.cpp:238
bool verbose_
Definition vpRobot.h:115
Implementation of a rotation matrix and operations on such kind of matrices.
vpRotationMatrix t() const
Implementation of a rotation vector as Euler angle minimal representation.
void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &displacement) VP_OVERRIDE
void get_fJe(vpMatrix &fJe) VP_OVERRIDE
static bool savePosFile(const std::string &filename, const vpColVector &q)
void setCameraParameters(const vpCameraParameters &cam)
void get_cVe(vpVelocityTwistMatrix &cVe)
void initialiseObjectRelativeToCamera(const vpHomogeneousMatrix &cMo)
static bool readPosFile(const std::string &filename, vpColVector &q)
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height)
void get_fMi(vpHomogeneousMatrix *fMit) VP_OVERRIDE
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity) VP_OVERRIDE
void computeArticularVelocity() VP_OVERRIDE
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q) VP_OVERRIDE
int isInJointLimit() VP_OVERRIDE
bool initialiseCameraRelativeToObject(const vpHomogeneousMatrix &cMo)
void initArms() VP_OVERRIDE
void findHighestPositioningSpeed(vpColVector &q)
void move(const char *filename)
bool singularityTest(const vpColVector &q, vpMatrix &J)
vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState) VP_OVERRIDE
virtual ~vpSimulatorAfma6() VP_OVERRIDE
void setJointLimit(const vpColVector &limitMin, const vpColVector &limitMax)
void updateArticularPosition() VP_OVERRIDE
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &q)
void get_eJe(vpMatrix &eJe) VP_OVERRIDE
void getExternalImage(vpImage< vpRGBa > &I)
double getPositioningVelocity(void)
void get_cMe(vpHomogeneousMatrix &cMe)
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q) VP_OVERRIDE
void init() VP_OVERRIDE
static const double defaultPositioningVelocity
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)
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()