36 #include <visp3/robot/vpSimulatorViper850.h>
38 #if defined(VISP_HAVE_MODULE_GUI) && defined(VISP_HAVE_THREADS)
43 #include <visp3/core/vpDebug.h>
44 #include <visp3/core/vpImagePoint.h>
45 #include <visp3/core/vpIoTools.h>
46 #include <visp3/core/vpMeterPixelConversion.h>
47 #include <visp3/core/vpPoint.h>
48 #include <visp3/core/vpTime.h>
50 #include "../wireframe-simulator/vpBound.h"
51 #include "../wireframe-simulator/vpRfstack.h"
52 #include "../wireframe-simulator/vpScene.h"
53 #include "../wireframe-simulator/vpVwstack.h"
56 const double vpSimulatorViper850::defaultPositioningVelocity = 25.0;
61 vpSimulatorViper850::vpSimulatorViper850()
62 : vpRobotWireFrameSimulator(),
vpViper850(), q_prev_getdis(), first_time_getdis(true),
63 positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir()
70 m_thread =
new std::thread(&launcher, std::ref(*
this));
81 vpSimulatorViper850::vpSimulatorViper850(
bool do_display)
82 : vpRobotWireFrameSimulator(do_display), q_prev_getdis(), first_time_getdis(true),
83 positioningVelocity(defaultPositioningVelocity), zeroPos(), reposPos(), toolCustom(false), arm_dir()
90 m_thread =
new std::thread(&launcher, std::ref(*
this));
98 vpSimulatorViper850::~vpSimulatorViper850()
100 m_mutex_robotStop.lock();
102 m_mutex_robotStop.unlock();
106 if (robotArms !=
nullptr) {
108 for (
int i = 0; i < 6; i++)
109 free_Bound_scene(&(robotArms[i]));
125 void vpSimulatorViper850::init()
129 std::vector<std::string> arm_dirs =
vpIoTools::splitChain(std::string(VISP_ROBOT_ARMS_DIR), std::string(
";"));
130 bool armDirExists =
false;
131 for (
size_t i = 0; i < arm_dirs.size(); i++)
133 arm_dir = arm_dirs[i];
140 std::cout <<
"The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl;
143 std::cout <<
"Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl;
153 artVel.resize(njoint);
155 zeroPos.resize(njoint);
157 zeroPos[1] = -M_PI / 2;
159 reposPos.resize(njoint);
161 reposPos[1] = -M_PI / 2;
163 reposPos[4] = M_PI / 2;
168 q_prev_getdis.resize(njoint);
170 first_time_getdis =
true;
172 positioningVelocity = defaultPositioningVelocity;
197 void vpSimulatorViper850::initDisplay()
200 robotArms =
new Bound_scene[6];
203 cameraParam.initPersProjWithoutDistortion(558.5309599, 556.055053, 320, 240);
204 setExternalCameraParameters(cameraParam);
206 getCameraParameters(tmp, 640, 480);
209 sceneInitialized =
true;
229 this->projModel = proj_model;
248 etc[0] = -0.04558630174;
249 etc[1] = -0.00134326752;
250 etc[2] = 0.001000828017;
258 std::cout <<
"This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
266 this->eMc.buildFrom(etc, eRc);
267 m_mutex_eMc.unlock();
283 void vpSimulatorViper850::getCameraParameters(
vpCameraParameters &cam,
const unsigned int &image_width,
284 const unsigned int &image_height)
290 switch (getToolType()) {
293 if (image_width == 640 && image_height == 480) {
299 vpTRACE(
"Cannot get default intrinsic camera parameters for this image "
306 if (image_width == 640 && image_height == 480) {
312 vpTRACE(
"Cannot get default intrinsic camera parameters for this image "
320 std::cout <<
"This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
369 void vpSimulatorViper850::updateArticularPosition()
371 double tcur_1 = tcur;
375 bool setVelocityCalled_ =
false;
381 m_mutex_setVelocityCalled.lock();
382 setVelocityCalled_ = setVelocityCalled;
383 m_mutex_setVelocityCalled.unlock();
385 if (setVelocityCalled_ || !constantSamplingTimeMode) {
386 m_mutex_setVelocityCalled.lock();
387 setVelocityCalled =
false;
388 m_mutex_setVelocityCalled.unlock();
389 computeArticularVelocity();
391 double ellapsedTime = (tcur - tprev) * 1e-3;
392 if (constantSamplingTimeMode) {
395 ellapsedTime = getSamplingTime();
402 double art = articularCoordinates[jointLimitArt - 1] + ellapsedTime * articularVelocities[jointLimitArt - 1];
403 if (art <= joint_min[jointLimitArt - 1] || art >= joint_max[jointLimitArt - 1]) {
405 std::cout <<
"Joint " << jointLimitArt - 1
407 <<
" < " <<
vpMath::deg(joint_max[jointLimitArt - 1]) << std::endl;
409 articularVelocities = 0.0;
415 articularCoordinates[0] = articularCoordinates[0] + ellapsedTime * articularVelocities[0];
416 articularCoordinates[1] = articularCoordinates[1] + ellapsedTime * articularVelocities[1];
417 articularCoordinates[2] = articularCoordinates[2] + ellapsedTime * articularVelocities[2];
418 articularCoordinates[3] = articularCoordinates[3] + ellapsedTime * articularVelocities[3];
419 articularCoordinates[4] = articularCoordinates[4] + ellapsedTime * articularVelocities[4];
420 articularCoordinates[5] = articularCoordinates[5] + ellapsedTime * articularVelocities[5];
422 int jl = isInJointLimit();
424 if (jl != 0 && jointLimit ==
false) {
426 ellapsedTime = (joint_min[(
unsigned int)(-jl - 1)] - articularCoordinates[(
unsigned int)(-jl - 1)]) /
427 (articularVelocities[(
unsigned int)(-jl - 1)]);
429 ellapsedTime = (joint_max[(
unsigned int)(jl - 1)] - articularCoordinates[(
unsigned int)(jl - 1)]) /
430 (articularVelocities[(
unsigned int)(jl - 1)]);
432 for (
unsigned int i = 0; i < 6; i++)
433 articularCoordinates[i] = articularCoordinates[i] + ellapsedTime * articularVelocities[i];
436 jointLimitArt = (
unsigned int)fabs((
double)jl);
439 set_artCoord(articularCoordinates);
440 set_artVel(articularVelocities);
444 if (displayAllowed) {
450 if (displayType == MODEL_3D && displayAllowed) {
451 while (get_displayBusy()) {
454 vpSimulatorViper850::getExternalImage(I);
455 set_displayBusy(
false);
458 if (displayType == MODEL_DH && displayAllowed) {
468 pt.track(getExternalCameraPosition());
470 pt.track(getExternalCameraPosition() * fMit[0]);
473 for (
int k = 1; k < 7; k++) {
474 pt.track(getExternalCameraPosition() * fMit[k - 1]);
477 pt.track(getExternalCameraPosition() * fMit[k]);
494 m_mutex_robotStop.lock();
496 m_mutex_robotStop.unlock();
512 void vpSimulatorViper850::compute_fMi()
531 double c23 = cos(q2 + q3);
532 double s23 = sin(q2 + q3);
549 fMit[0][0][3] = a1 * c1;
550 fMit[0][1][3] = a1 * s1;
553 fMit[1][0][0] = c1 * c2;
554 fMit[1][1][0] = s1 * c2;
556 fMit[1][0][1] = -c1 * s2;
557 fMit[1][1][1] = -s1 * s2;
562 fMit[1][0][3] = c1 * (a2 * c2 + a1);
563 fMit[1][1][3] = s1 * (a2 * c2 + a1);
564 fMit[1][2][3] = d1 - a2 * s2;
566 double quickcomp1 = a3 * c23 - a2 * c2 - a1;
568 fMit[2][0][0] = -c1 * c23;
569 fMit[2][1][0] = -s1 * c23;
574 fMit[2][0][2] = c1 * s23;
575 fMit[2][1][2] = s1 * s23;
577 fMit[2][0][3] = -c1 * quickcomp1;
578 fMit[2][1][3] = -s1 * quickcomp1;
579 fMit[2][2][3] = a3 * s23 - a2 * s2 + d1;
581 double quickcomp2 = c1 * (s23 * d4 - quickcomp1);
582 double quickcomp3 = s1 * (s23 * d4 - quickcomp1);
584 fMit[3][0][0] = -c1 * c23 * c4 + s1 * s4;
585 fMit[3][1][0] = -s1 * c23 * c4 - c1 * s4;
586 fMit[3][2][0] = s23 * c4;
587 fMit[3][0][1] = c1 * s23;
588 fMit[3][1][1] = s1 * s23;
590 fMit[3][0][2] = -c1 * c23 * s4 - s1 * c4;
591 fMit[3][1][2] = -s1 * c23 * s4 + c1 * c4;
592 fMit[3][2][2] = s23 * s4;
593 fMit[3][0][3] = quickcomp2;
594 fMit[3][1][3] = quickcomp3;
595 fMit[3][2][3] = c23 * d4 + a3 * s23 - a2 * s2 + d1;
597 fMit[4][0][0] = c1 * (s23 * s5 - c5 * c23 * c4) + s1 * c5 * s4;
598 fMit[4][1][0] = s1 * (s23 * s5 - c5 * c23 * c4) - c1 * c5 * s4;
599 fMit[4][2][0] = s23 * c4 * c5 + c23 * s5;
600 fMit[4][0][1] = c1 * c23 * s4 + s1 * c4;
601 fMit[4][1][1] = s1 * c23 * s4 - c1 * c4;
602 fMit[4][2][1] = -s23 * s4;
603 fMit[4][0][2] = c1 * (s23 * c5 + s5 * c23 * c4) - s1 * s5 * s4;
604 fMit[4][1][2] = s1 * (s23 * c5 + s5 * c23 * c4) + c1 * s5 * s4;
605 fMit[4][2][2] = -s23 * c4 * s5 + c23 * c5;
606 fMit[4][0][3] = quickcomp2;
607 fMit[4][1][3] = quickcomp3;
608 fMit[4][2][3] = c23 * d4 + a3 * s23 - a2 * s2 + d1;
610 fMit[5][0][0] = c1 * (c23 * (c4 * c5 * c6 - s4 * s6) - s23 * s5 * c6) - s1 * (s4 * c5 * c6 + c4 * s6);
611 fMit[5][1][0] = -s1 * (c23 * (-c4 * c5 * c6 + s4 * s6) + s23 * s5 * c6) + c1 * (s4 * c5 * c6 + c4 * s6);
612 fMit[5][2][0] = s23 * (s4 * s6 - c4 * c5 * c6) - c23 * s5 * c6;
613 fMit[5][0][1] = -c1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) + s1 * (s4 * c5 * s6 - c4 * c6);
614 fMit[5][1][1] = -s1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) - c1 * (s4 * c5 * s6 - c4 * c6);
615 fMit[5][2][1] = s23 * (c4 * c5 * s6 + s4 * c6) + c23 * s5 * s6;
616 fMit[5][0][2] = c1 * (c23 * c4 * s5 + s23 * c5) - s1 * s4 * s5;
617 fMit[5][1][2] = s1 * (c23 * c4 * s5 + s23 * c5) + c1 * s4 * s5;
618 fMit[5][2][2] = -s23 * c4 * s5 + c23 * c5;
619 fMit[5][0][3] = quickcomp2;
620 fMit[5][1][3] = quickcomp3;
621 fMit[5][2][3] = s23 * a3 + c23 * d4 - a2 * s2 + d1;
623 fMit[6][0][0] = c1 * (c23 * (c4 * c5 * c6 - s4 * s6) - s23 * s5 * c6) - s1 * (s4 * c5 * c6 + c4 * s6);
624 fMit[6][1][0] = -s1 * (c23 * (-c4 * c5 * c6 + s4 * s6) + s23 * s5 * c6) + c1 * (s4 * c5 * c6 + c4 * s6);
625 fMit[6][2][0] = s23 * (s4 * s6 - c4 * c5 * c6) - c23 * s5 * c6;
626 fMit[6][0][1] = -c1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) + s1 * (s4 * c5 * s6 - c4 * c6);
627 fMit[6][1][1] = -s1 * (c23 * (c4 * c5 * s6 + s4 * c6) - s23 * s5 * s6) - c1 * (s4 * c5 * s6 - c4 * c6);
628 fMit[6][2][1] = s23 * (c4 * c5 * s6 + s4 * c6) + c23 * s5 * s6;
629 fMit[6][0][2] = c1 * (c23 * c4 * s5 + s23 * c5) - s1 * s4 * s5;
630 fMit[6][1][2] = s1 * (c23 * c4 * s5 + s23 * c5) + c1 * s4 * s5;
631 fMit[6][2][2] = -s23 * c4 * s5 + c23 * c5;
632 fMit[6][0][3] = c1 * (c23 * (c4 * s5 * d6 - a3) + s23 * (c5 * d6 + d4) + a1 + a2 * c2) - s1 * s4 * s5 * d6;
633 fMit[6][1][3] = s1 * (c23 * (c4 * s5 * d6 - a3) + s23 * (c5 * d6 + d4) + a1 + a2 * c2) + c1 * s4 * s5 * d6;
634 fMit[6][2][3] = s23 * (a3 - c4 * s5 * d6) + c23 * (c5 * d6 + d4) - a2 * s2 + d1;
642 m_mutex_eMc.unlock();
645 for (
int i = 0; i < 8; i++) {
648 m_mutex_fMi.unlock();
668 std::cout <<
"Change the control mode from velocity to position control.\n";
679 std::cout <<
"Change the control mode from stop to velocity control.\n";
770 vpERROR_TRACE(
"Cannot send a velocity to the robot "
771 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
773 "Cannot send a velocity to the robot "
774 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
779 double scale_sat = 1;
780 double vel_trans_max = getMaxTranslationVelocity();
781 double vel_rot_max = getMaxRotationVelocity();
791 vpERROR_TRACE(
"The velocity vector must have a size of 6 !!!!");
795 for (
unsigned int i = 0; i < 3; ++i) {
796 vel_abs = fabs(vel[i]);
797 if (vel_abs > vel_trans_max && !jointLimit) {
798 vel_trans_max = vel_abs;
799 vpERROR_TRACE(
"Excess velocity %g m/s in TRANSLATION "
804 vel_abs = fabs(vel[i + 3]);
805 if (vel_abs > vel_rot_max && !jointLimit) {
806 vel_rot_max = vel_abs;
807 vpERROR_TRACE(
"Excess velocity %g rad/s in ROTATION "
813 double scale_trans_sat = 1;
814 double scale_rot_sat = 1;
815 if (vel_trans_max > getMaxTranslationVelocity())
816 scale_trans_sat = getMaxTranslationVelocity() / vel_trans_max;
818 if (vel_rot_max > getMaxRotationVelocity())
819 scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
821 if ((scale_trans_sat < 1) || (scale_rot_sat < 1)) {
822 if (scale_trans_sat < scale_rot_sat)
823 scale_sat = scale_trans_sat;
825 scale_sat = scale_rot_sat;
833 vpERROR_TRACE(
"The velocity vector must have a size of 6 !!!!");
836 for (
unsigned int i = 0; i < 6; ++i) {
837 vel_abs = fabs(vel[i]);
838 if (vel_abs > vel_rot_max && !jointLimit) {
839 vel_rot_max = vel_abs;
840 vpERROR_TRACE(
"Excess velocity %g rad/s in ROTATION "
845 double scale_rot_sat = 1;
846 if (vel_rot_max > getMaxRotationVelocity())
847 scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
848 if (scale_rot_sat < 1)
849 scale_sat = scale_rot_sat;
858 set_velocity(vel * scale_sat);
860 m_mutex_frame.lock();
861 setRobotFrame(frame);
862 m_mutex_frame.unlock();
864 m_mutex_setVelocityCalled.lock();
865 setVelocityCalled =
true;
866 m_mutex_setVelocityCalled.unlock();
872 void vpSimulatorViper850::computeArticularVelocity()
876 m_mutex_frame.lock();
877 frame = getRobotFrame();
878 m_mutex_frame.unlock();
880 double vel_rot_max = getMaxRotationVelocity();
892 if (singularityManagement)
893 singularityTest(articularCoordinates, eJe_);
894 articularVelocity = eJe_ * eVc * velocityframe;
895 set_artVel(articularVelocity);
902 if (singularityManagement)
903 singularityTest(articularCoordinates, fJe_);
904 articularVelocity = fJe_ * velocityframe;
905 set_artVel(articularVelocity);
909 articularVelocity = velocityframe;
910 set_artVel(articularVelocity);
922 for (
unsigned int i = 0; i < 6; ++i) {
923 double vel_abs = fabs(articularVelocity[i]);
924 if (vel_abs > vel_rot_max && !jointLimit) {
925 vel_rot_max = vel_abs;
926 vpERROR_TRACE(
"Excess velocity %g rad/s in ROTATION "
928 articularVelocity[i], i + 1);
931 double scale_rot_sat = 1;
932 double scale_sat = 1;
934 if (vel_rot_max > getMaxRotationVelocity())
935 scale_rot_sat = getMaxRotationVelocity() / vel_rot_max;
936 if (scale_rot_sat < 1)
937 scale_sat = scale_rot_sat;
939 set_artVel(articularVelocity * scale_sat);
1003 vpColVector articularCoordinates = get_artCoord();
1011 vel = cVe * eJe_ * articularVelocity;
1015 vel = articularVelocity;
1021 vel = fJe_ * articularVelocity;
1029 vpERROR_TRACE(
"Error in spec of vpRobot. "
1030 "Case not taken in account.");
1055 getVelocity(frame, vel);
1106 getVelocity(frame, vel);
1127 getVelocity(frame, vel);
1132 void vpSimulatorViper850::findHighestPositioningSpeed(
vpColVector &q)
1134 double vel_rot_max = getMaxRotationVelocity();
1135 double velmax = fabs(q[0]);
1136 for (
unsigned int i = 1; i < 6; i++) {
1137 if (velmax < fabs(q[i]))
1138 velmax = fabs(q[i]);
1141 double alpha = (getPositioningVelocity() * vel_rot_max) / (velmax * 100);
1226 vpERROR_TRACE(
"Robot was not in position-based control\n"
1227 "Modification of the robot state");
1231 vpColVector articularCoordinates = get_artCoord();
1242 for (
unsigned int i = 0; i < 3; i++) {
1256 articularCoordinates = get_artCoord();
1257 qdes = articularCoordinates;
1258 nbSol = getInverseKinematics(fMc2, qdes, verbose_);
1259 m_mutex_setVelocityCalled.lock();
1260 setVelocityCalled =
true;
1261 m_mutex_setVelocityCalled.unlock();
1263 error = qdes - articularCoordinates;
1267 if (errsqr < 1e-4) {
1271 set_velocity(error);
1276 vpERROR_TRACE(
"Positioning error.");
1279 }
while (errsqr > 1e-8 && nbSol > 0);
1286 articularCoordinates = get_artCoord();
1287 error = q - articularCoordinates;
1291 m_mutex_setVelocityCalled.lock();
1292 setVelocityCalled =
true;
1293 m_mutex_setVelocityCalled.unlock();
1294 if (errsqr < 1e-4) {
1298 set_velocity(error);
1301 }
while (errsqr > 1e-8);
1311 for (
unsigned int i = 0; i < 3; i++) {
1320 articularCoordinates = get_artCoord();
1321 qdes = articularCoordinates;
1322 nbSol = getInverseKinematics(fMc_, qdes, verbose_);
1324 error = qdes - articularCoordinates;
1325 errsqr = error.sumSquare();
1328 m_mutex_setVelocityCalled.lock();
1329 setVelocityCalled =
true;
1330 m_mutex_setVelocityCalled.unlock();
1331 if (errsqr < 1e-4) {
1335 set_velocity(error);
1340 vpERROR_TRACE(
"Positioning error. Position unreachable");
1341 }
while (errsqr > 1e-8 && nbSol > 0);
1346 "Mixt frame not implemented.");
1350 "End-effector frame not implemented.");
1422 double pos4,
double pos5,
double pos6)
1433 setPosition(frame, position);
1436 vpERROR_TRACE(
"Error caught");
1479 void vpSimulatorViper850::setPosition(
const char *filename)
1484 ret = this->readPosFile(filename, q);
1487 vpERROR_TRACE(
"Bad position in \"%s\"", filename);
1582 for (
unsigned int i = 0; i < 3; i++) {
1590 vpERROR_TRACE(
"Positioning error. Mixt frame not implemented");
1592 "Mixt frame not implemented.");
1595 vpERROR_TRACE(
"Positioning error. Mixt frame not implemented");
1597 "End-effector frame not implemented.");
1631 getPosition(frame, q);
1649 this->getPosition(frame, posRxyz);
1655 for (
unsigned int j = 0; j < 3; j++) {
1656 position[j] = posRxyz[j];
1657 position[j + 3] = RtuVect[j];
1676 getPosition(frame, position);
1690 vpTRACE(
"Joint limit vector has not a size of 6 !");
1694 joint_min[0] = limitMin[0];
1695 joint_min[1] = limitMin[1];
1696 joint_min[2] = limitMin[2];
1697 joint_min[3] = limitMin[3];
1698 joint_min[4] = limitMin[4];
1699 joint_min[5] = limitMin[5];
1701 joint_max[0] = limitMax[0];
1702 joint_max[1] = limitMax[1];
1703 joint_max[2] = limitMax[2];
1704 joint_max[3] = limitMax[3];
1705 joint_max[4] = limitMax[4];
1706 joint_max[5] = limitMax[5];
1720 double c2 = cos(q2);
1721 double c3 = cos(q3);
1722 double s3 = sin(q3);
1723 double c23 = cos(q2 + q3);
1724 double s23 = sin(q2 + q3);
1725 double s5 = sin(q5);
1727 bool cond1 = fabs(s5) < 1e-1;
1728 bool cond2 = fabs(a3 * s3 + c3 * d4) < 1e-1;
1729 bool cond3 = fabs(a2 * c2 - a3 * c23 + s23 * d4 + a1) < 1e-1;
1783 int vpSimulatorViper850::isInJointLimit()
1789 vpColVector articularCoordinates = get_artCoord();
1791 for (
unsigned int i = 0; i < 6; i++) {
1792 if (articularCoordinates[i] <= joint_min[i]) {
1793 difft = joint_min[i] - articularCoordinates[i];
1796 artNumb = -(int)i - 1;
1801 for (
unsigned int i = 0; i < 6; i++) {
1802 if (articularCoordinates[i] >= joint_max[i]) {
1803 difft = articularCoordinates[i] - joint_max[i];
1806 artNumb = (int)(i + 1);
1812 std::cout <<
"\nWarning: Velocity control stopped: axis " << fabs((
float)artNumb) <<
" on joint limit!"
1841 q_cur = get_artCoord();
1843 if (!first_time_getdis) {
1846 std::cout <<
"getDisplacement() CAMERA_FRAME not implemented\n";
1851 displacement = q_cur - q_prev_getdis;
1856 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
1861 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
1865 std::cout <<
"getDisplacement() END_EFFECTOR_FRAME not implemented\n";
1871 first_time_getdis =
false;
1875 q_prev_getdis = q_cur;
1943 bool vpSimulatorViper850::readPosFile(
const std::string &filename,
vpColVector &q)
1945 std::ifstream fd(filename.c_str(), std::ios::in);
1947 if (!fd.is_open()) {
1952 std::string key(
"R:");
1953 std::string id(
"#Viper850 - Position");
1954 bool pos_found =
false;
1959 while (std::getline(fd, line)) {
1962 if (!(line.compare(0,
id.size(),
id) == 0)) {
1963 std::cout <<
"Error: this position file " << filename <<
" is not for Viper850 robot" << std::endl;
1967 if ((line.compare(0, 1,
"#") == 0)) {
1970 if ((line.compare(0, key.size(), key) == 0)) {
1973 if (chain.size() < njoint + 1)
1975 if (chain.size() < njoint + 1)
1978 std::istringstream ss(line);
1981 for (
unsigned int i = 0; i < njoint; i++)
1994 std::cout <<
"Error: unable to find a position for Viper850 robot in " << filename << std::endl;
2022 bool vpSimulatorViper850::savePosFile(
const std::string &filename,
const vpColVector &q)
2026 fd = fopen(filename.c_str(),
"w");
2031 #Viper - Position - Version 1.0\n\
2034 # Joint position in degrees\n\
2053 void vpSimulatorViper850::move(
const char *filename)
2058 this->readPosFile(filename, q);
2102 void vpSimulatorViper850::get_eJe(
vpMatrix &eJe_)
2108 vpERROR_TRACE(
"catch exception ");
2123 void vpSimulatorViper850::get_fJe(
vpMatrix &fJe_)
2126 vpColVector articularCoordinates = get_artCoord();
2130 vpERROR_TRACE(
"Error caught");
2138 void vpSimulatorViper850::stopMotion()
2163 void vpSimulatorViper850::initArms()
2167 std::string scene_dir_;
2168 std::vector<std::string> scene_dirs =
vpIoTools::splitChain(std::string(VISP_SCENES_DIR), std::string(
";"));
2169 bool sceneDirExists =
false;
2170 for (
size_t i = 0; i < scene_dirs.size(); i++)
2172 scene_dir_ = scene_dirs[i];
2173 sceneDirExists =
true;
2176 if (!sceneDirExists) {
2179 std::cout <<
"The simulator uses data from VISP_SCENES_DIR=" << scene_dir_ << std::endl;
2182 std::cout <<
"Cannot get VISP_SCENES_DIR environment variable" << std::endl;
2186 unsigned int name_length = 30;
2187 if (scene_dir_.size() > FILENAME_MAX)
2190 unsigned int full_length = (
unsigned int)scene_dir_.size() + name_length;
2191 if (full_length > FILENAME_MAX)
2194 char *name_cam =
new char[full_length];
2196 strcpy(name_cam, scene_dir_.c_str());
2197 strcat(name_cam,
"/camera.bnd");
2198 set_scene(name_cam, &camera, cameraFactor);
2200 if (arm_dir.size() > FILENAME_MAX)
2202 full_length = (
unsigned int)arm_dir.size() + name_length;
2203 if (full_length > FILENAME_MAX)
2206 char *name_arm =
new char[full_length];
2207 strcpy(name_arm, arm_dir.c_str());
2208 strcat(name_arm,
"/viper850_arm1.bnd");
2209 set_scene(name_arm, robotArms, 1.0);
2210 strcpy(name_arm, arm_dir.c_str());
2211 strcat(name_arm,
"/viper850_arm2.bnd");
2212 set_scene(name_arm, robotArms + 1, 1.0);
2213 strcpy(name_arm, arm_dir.c_str());
2214 strcat(name_arm,
"/viper850_arm3.bnd");
2215 set_scene(name_arm, robotArms + 2, 1.0);
2216 strcpy(name_arm, arm_dir.c_str());
2217 strcat(name_arm,
"/viper850_arm4.bnd");
2218 set_scene(name_arm, robotArms + 3, 1.0);
2219 strcpy(name_arm, arm_dir.c_str());
2220 strcat(name_arm,
"/viper850_arm5.bnd");
2221 set_scene(name_arm, robotArms + 4, 1.0);
2222 strcpy(name_arm, arm_dir.c_str());
2223 strcat(name_arm,
"/viper850_arm6.bnd");
2224 set_scene(name_arm, robotArms + 5, 1.0);
2232 add_rfstack(IS_BACK);
2234 add_vwstack(
"start",
"depth", 0.0, 100.0);
2235 add_vwstack(
"start",
"window", -0.1, 0.1, -0.1, 0.1);
2236 add_vwstack(
"start",
"type", PERSPECTIVE);
2240 displayCamera =
true;
2248 m_mutex_scene.lock();
2249 bool changed =
false;
2253 if (std::fabs(displacement[2][3]) > std::numeric_limits<double>::epsilon())
2254 camMf2 = camMf2 * displacement;
2256 f2Mf = camMf2.
inverse() * camMf;
2258 camMf = camMf2 * displacement * f2Mf;
2264 if ((std::fabs(px_ext - 1.) >
vpMath::maximum(px_ext, 1.) * std::numeric_limits<double>::epsilon()) &&
2265 (std::fabs(py_ext - 1) >
vpMath::maximum(py_ext, 1.) * std::numeric_limits<double>::epsilon())) {
2266 u = (double)I_.
getWidth() / (2 * px_ext);
2267 v = (double)I_.
getHeight() / (2 * py_ext);
2274 float w44o[4][4], w44cext[4][4], x, y, z;
2276 vp2jlc_matrix(camMf.inverse(), w44cext);
2278 add_vwstack(
"start",
"cop", w44cext[3][0], w44cext[3][1], w44cext[3][2]);
2279 x = w44cext[2][0] + w44cext[3][0];
2280 y = w44cext[2][1] + w44cext[3][1];
2281 z = w44cext[2][2] + w44cext[3][2];
2282 add_vwstack(
"start",
"vrp", x, y, z);
2283 add_vwstack(
"start",
"vpn", w44cext[2][0], w44cext[2][1], w44cext[2][2]);
2284 add_vwstack(
"start",
"vup", w44cext[1][0], w44cext[1][1], w44cext[1][2]);
2285 add_vwstack(
"start",
"window", -u, u, -v, v);
2291 display_scene(w44o, robotArms[0], I_, curColor);
2293 vp2jlc_matrix(fMit[0], w44o);
2294 display_scene(w44o, robotArms[1], I_, curColor);
2296 vp2jlc_matrix(fMit[1], w44o);
2297 display_scene(w44o, robotArms[2], I_, curColor);
2299 vp2jlc_matrix(fMit[2], w44o);
2300 display_scene(w44o, robotArms[3], I_, curColor);
2302 vp2jlc_matrix(fMit[3], w44o);
2303 display_scene(w44o, robotArms[4], I_, curColor);
2305 vp2jlc_matrix(fMit[6], w44o);
2306 display_scene(w44o, robotArms[5], I_, curColor);
2308 if (displayCamera) {
2312 cMe = fMit[6] * cMe;
2313 vp2jlc_matrix(cMe, w44o);
2314 display_scene(w44o, camera, I_, camColor);
2317 if (displayObject) {
2318 vp2jlc_matrix(fMo, w44o);
2319 display_scene(w44o, scene, I_, curColor);
2321 m_mutex_scene.unlock();
2340 bool vpSimulatorViper850::initialiseCameraRelativeToObject(
const vpHomogeneousMatrix &cMo_)
2350 vpColVector articularCoordinates = get_artCoord();
2351 unsigned int nbSol = getInverseKinematics(fMc_, articularCoordinates, verbose_);
2355 vpERROR_TRACE(
"Positioning error. Position unreachable");
2359 std::cout <<
"Used joint coordinates (rad): " << articularCoordinates.
t() << std::endl;
2361 set_artCoord(articularCoordinates);
2381 void vpSimulatorViper850::initialiseObjectRelativeToCamera(
const vpHomogeneousMatrix &cMo_)
2385 m_mutex_scene.lock();
2390 fMo = fMit[7] * cMo_;
2391 m_mutex_scene.unlock();
2394 #elif !defined(VISP_BUILD_SHARED_LIBS)
2397 void dummy_vpSimulatorViper850() { };
unsigned int getRows() const
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
vpCameraParametersProjType
Implementation of column vector and the associated operations.
void resize(unsigned int i, bool flagNullify=true)
static const vpColor none
static const vpColor green
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.
@ dimensionError
Bad dimension.
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
void resize(unsigned int nrows, unsigned int ncols, bool flagNullify=true)
void extract(vpRotationMatrix &R) const
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
unsigned int getWidth() const
unsigned int getHeight() const
void init(unsigned int h, unsigned int w, Type value)
static double rad(double deg)
static Type maximum(const Type &a, const Type &b)
static Type minimum(const Type &a, const Type &b)
static double deg(double rad)
Implementation of a matrix and operations on matrices.
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 ...
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.
@ STATE_POSITION_CONTROL
Initialize the position controller.
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
@ STATE_ACCELERATION_CONTROL
Initialize the acceleration controller.
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Implementation of a rotation matrix and operations on such kind of matrices.
Implementation of a rotation vector as Euler angle minimal representation.
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)
Modelization of the ADEPT Viper 850 robot.
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME
static const vpToolType defaultTool
Default tool attached to the robot end effector.
vpToolType
List of possible tools that can be attached to the robot end-effector.
@ TOOL_SCHUNK_GRIPPER_CAMERA
@ TOOL_PTGREY_FLEA2_CAMERA
@ TOOL_MARLIN_F033C_CAMERA
static const char *const CONST_MARLIN_F033C_CAMERA_NAME
void get_cMe(vpHomogeneousMatrix &cMe) const
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT double getMinTimeForUsleepCall()
VISP_EXPORT double measureTimeSecond()
VISP_EXPORT double measureTimeMs()