44 #include <visp/vpSimulatorViper850.h>
45 #include <visp/vpTime.h>
46 #include <visp/vpImagePoint.h>
47 #include <visp/vpPoint.h>
48 #include <visp/vpMeterPixelConversion.h>
49 #include <visp/vpIoTools.h>
53 #if defined(_WIN32) || defined(VISP_HAVE_PTHREAD)
62 q_prev_getdis(), first_time_getdis(true), positioningVelocity(defaultPositioningVelocity),
63 zeroPos(), reposPos(), toolCustom(false), arm_dir()
78 DWORD dwThreadIdArray;
79 hThread = CreateThread(
86 #elif defined (VISP_HAVE_PTHREAD)
93 pthread_attr_init(&
attr);
94 pthread_attr_setdetachstate(&
attr, PTHREAD_CREATE_JOINABLE);
110 q_prev_getdis(), first_time_getdis(true), positioningVelocity(defaultPositioningVelocity),
111 zeroPos(), reposPos(), toolCustom(false), arm_dir()
119 mutex_fMi = CreateMutex(NULL,FALSE,NULL);
126 DWORD dwThreadIdArray;
127 hThread = CreateThread(
134 #elif defined(VISP_HAVE_PTHREAD)
141 pthread_attr_init(&
attr);
142 pthread_attr_setdetachstate(&
attr, PTHREAD_CREATE_JOINABLE);
158 WaitForSingleObject(hThread,INFINITE);
159 CloseHandle(hThread);
165 #elif defined(VISP_HAVE_PTHREAD)
166 pthread_attr_destroy(&
attr);
167 pthread_join(
thread, NULL);
178 for(
int i = 0; i < 6; i++)
199 arm_dir = VISP_ROBOT_ARMS_DIR;
203 std::cout <<
"The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl;
206 std::cout <<
"Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl;
220 zeroPos[1] = -M_PI/2; zeroPos[2] = M_PI;
223 reposPos[1] = -M_PI/2; reposPos[2] = M_PI; reposPos[4] = M_PI/2;
230 first_time_getdis =
true;
312 etc[0] = -0.04558630174;
313 etc[1] = -0.00134326752;
314 etc[2] = 0.001000828017;
321 std::cout <<
"This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
345 const unsigned int &image_width,
346 const unsigned int &image_height)
356 if (image_width == 640 && image_height == 480)
358 std::cout <<
"Get default camera parameters for camera \""
363 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
369 if (image_width == 640 && image_height == 480) {
370 std::cout <<
"Get default camera parameters for camera \""
375 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
381 std::cout <<
"This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
439 double tcur_1 =
tcur;
452 double ellapsedTime = (
tcur -
tprev) * 1e-3;
469 articularVelocities = 0.0;
475 articularCoordinates[0] = articularCoordinates[0] + ellapsedTime*articularVelocities[0];
476 articularCoordinates[1] = articularCoordinates[1] + ellapsedTime*articularVelocities[1];
477 articularCoordinates[2] = articularCoordinates[2] + ellapsedTime*articularVelocities[2];
478 articularCoordinates[3] = articularCoordinates[3] + ellapsedTime*articularVelocities[3];
479 articularCoordinates[4] = articularCoordinates[4] + ellapsedTime*articularVelocities[4];
480 articularCoordinates[5] = articularCoordinates[5] + ellapsedTime*articularVelocities[5];
487 ellapsedTime = (
joint_min[(
unsigned int)(-jl-1)] - articularCoordinates[(
unsigned int)(-jl-1)])/(articularVelocities[(
unsigned int)(-jl-1)]);
489 ellapsedTime = (
joint_max[(
unsigned int)(jl-1)] - articularCoordinates[(
unsigned int)(jl-1)])/(articularVelocities[(
unsigned int)(jl-1)]);
491 for (
unsigned int i = 0; i < 6; i++)
492 articularCoordinates[i] = articularCoordinates[i] + ellapsedTime*articularVelocities[i];
534 for (
int k = 1; k < 7; k++)
587 double c23 = cos(q2+q3);
588 double s23 = sin(q2+q3);
605 fMit[0][0][3] =
a1*c1;
606 fMit[0][1][3] =
a1*s1;
609 fMit[1][0][0] = c1*c2;
610 fMit[1][1][0] = s1*c2;
612 fMit[1][0][1] = -c1*s2;
613 fMit[1][1][1] = -s1*s2;
618 fMit[1][0][3] = c1*(
a2*c2+
a1);
619 fMit[1][1][3] = s1*(
a2*c2+
a1);
620 fMit[1][2][3] =
d1-
a2*s2;
622 double quickcomp1 =
a3*c23-
a2*c2-
a1;
624 fMit[2][0][0] = -c1*c23;
625 fMit[2][1][0] = -s1*c23;
630 fMit[2][0][2] = c1*s23;
631 fMit[2][1][2] = s1*s23;
633 fMit[2][0][3] = -c1*quickcomp1;
634 fMit[2][1][3] = -s1*quickcomp1;
635 fMit[2][2][3] =
a3*s23-
a2*s2+
d1;
637 double quickcomp2 = c1*(s23*
d4 - quickcomp1);
638 double quickcomp3 = s1*(s23*
d4 - quickcomp1);
640 fMit[3][0][0] = -c1*c23*c4+s1*s4;
641 fMit[3][1][0] = -s1*c23*c4-c1*s4;
642 fMit[3][2][0] = s23*c4;
643 fMit[3][0][1] = c1*s23;
644 fMit[3][1][1] = s1*s23;
646 fMit[3][0][2] = -c1*c23*s4-s1*c4;
647 fMit[3][1][2] = -s1*c23*s4+c1*c4;
648 fMit[3][2][2] = s23*s4;
649 fMit[3][0][3] = quickcomp2;
650 fMit[3][1][3] = quickcomp3;
651 fMit[3][2][3] = c23*
d4+
a3*s23-
a2*s2+
d1;
653 fMit[4][0][0] = c1*(s23*s5-c5*c23*c4)+s1*c5*s4;
654 fMit[4][1][0] = s1*(s23*s5-c5*c23*c4)-c1*c5*s4;
655 fMit[4][2][0] = s23*c4*c5+c23*s5;
656 fMit[4][0][1] = c1*c23*s4+s1*c4;
657 fMit[4][1][1] = s1*c23*s4-c1*c4;
658 fMit[4][2][1] = -s23*s4;
659 fMit[4][0][2] = c1*(s23*c5+s5*c23*c4)-s1*s5*s4;
660 fMit[4][1][2] = s1*(s23*c5+s5*c23*c4)+c1*s5*s4;
661 fMit[4][2][2] = -s23*c4*s5+c23*c5;
662 fMit[4][0][3] = quickcomp2;
663 fMit[4][1][3] = quickcomp3;
664 fMit[4][2][3] = c23*
d4+
a3*s23-
a2*s2+
d1;
666 fMit[5][0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
667 fMit[5][1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
668 fMit[5][2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
669 fMit[5][0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
670 fMit[5][1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
671 fMit[5][2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
672 fMit[5][0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
673 fMit[5][1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
674 fMit[5][2][2] = -s23*c4*s5+c23*c5;
675 fMit[5][0][3] = quickcomp2;
676 fMit[5][1][3] = quickcomp3;
677 fMit[5][2][3] = s23*
a3+c23*
d4-
a2*s2+
d1;
679 fMit[6][0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
680 fMit[6][1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
681 fMit[6][2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
682 fMit[6][0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
683 fMit[6][1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
684 fMit[6][2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
685 fMit[6][0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
686 fMit[6][1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
687 fMit[6][2][2] = -s23*c4*s5+c23*c5;
688 fMit[6][0][3] = c1*(c23*(c4*s5*
d6-
a3)+s23*(c5*
d6+
d4)+a1+
a2*c2)-s1*s4*s5*
d6;
689 fMit[6][1][3] = s1*(c23*(c4*s5*
d6-
a3)+s23*(c5*
d6+
d4)+a1+
a2*c2)+c1*s4*s5*
d6;
690 fMit[6][2][3] = s23*(
a3-c4*s5*
d6)+c23*(c5*
d6+
d4)-
a2*s2+
d1;
700 for (
int i = 0; i < 8; i++)
703 #elif defined(VISP_HAVE_PTHREAD)
705 for (
int i = 0; i < 8; i++)
730 std::cout <<
"Change the control mode from velocity to position control.\n";
740 std::cout <<
"Change the control mode from stop to velocity control.\n";
826 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
828 "Cannot send a velocity to the robot "
829 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
834 double scale_trans_sat = 1;
835 double scale_rot_sat = 1;
836 double scale_sat = 1;
851 vpERROR_TRACE (
"The velocity vector must have a size of 6 !!!!");
855 for (
unsigned int i = 0 ; i < 3; ++ i)
857 vel_abs = fabs (vel[i]);
860 vel_trans_max = vel_abs;
862 "(axis nr. %d).", vel[i], i+1);
865 vel_abs = fabs (vel[i+3]);
867 vel_rot_max = vel_abs;
869 "(axis nr. %d).", vel[i+3], i+4);
879 if ( (scale_trans_sat < 1) || (scale_rot_sat < 1) )
881 if (scale_trans_sat < scale_rot_sat)
882 scale_sat = scale_trans_sat;
884 scale_sat = scale_rot_sat;
894 vpERROR_TRACE (
"The velocity vector must have a size of 6 !!!!");
897 for (
unsigned int i = 0 ; i < 6; ++ i)
899 vel_abs = fabs (vel[i]);
902 vel_rot_max = vel_abs;
904 "(axis nr. %d).", vel[i], i+1);
909 if ( scale_rot_sat < 1 )
910 scale_sat = scale_rot_sat;
933 double scale_rot_sat = 1;
934 double scale_sat = 1;
952 articularVelocity = eJe_*eVc*velocityframe;
963 articularVelocity = fJe_*velocityframe;
969 articularVelocity = velocityframe;
986 for (
unsigned int i = 0 ; i < 6; ++ i)
988 vel_abs = fabs (articularVelocity[i]);
991 vel_rot_max = vel_abs;
993 "(axis nr. %d).", articularVelocity[i], i+1);
998 if ( scale_rot_sat < 1 )
999 scale_sat = scale_rot_sat;
1074 vel = cVe*eJe_*articularVelocity;
1079 vel = articularVelocity;
1086 vel = fJe_*articularVelocity;
1096 "Case not taken in account.");
1202 double velmax = fabs(q[0]);
1203 for (
unsigned int i = 1; i < 6; i++)
1205 if (velmax < fabs(q[i]))
1206 velmax = fabs(q[i]);
1293 "Modification of the robot state");
1310 for (
unsigned int i=0; i < 3; i++)
1327 qdes = articularCoordinates;
1332 error = qdes - articularCoordinates;
1349 "Position out of range.");
1351 }
while (errsqr > 1e-8 && nbSol > 0);
1361 error = q - articularCoordinates;
1374 }
while (errsqr > 1e-8);
1385 for (
unsigned int i=0; i < 3; i++)
1397 qdes = articularCoordinates;
1401 error = qdes - articularCoordinates;
1417 }
while (errsqr > 1e-8 && nbSol > 0);
1422 vpERROR_TRACE (
"Positionning error. Mixt frame not implemented");
1424 "Positionning error: "
1425 "Mixt frame not implemented.");
1504 position[0] = pos1 ;
1505 position[1] = pos2 ;
1506 position[2] = pos3 ;
1507 position[3] = pos4 ;
1508 position[4] = pos5 ;
1509 position[5] = pos6 ;
1565 "Bad position in filename.");
1661 for (
unsigned int i=0; i <3; i++)
1671 vpERROR_TRACE (
"Positionning error. Mixt frame not implemented");
1673 "Positionning error: "
1674 "Mixt frame not implemented.");
1736 for(
unsigned int j=0;j<3;j++)
1738 position[j]=posRxyz[j];
1739 position[j+3]=RtuVect[j];
1772 vpTRACE(
"Joint limit vector has not a size of 6 !");
1804 double c2 = cos(q2);
1805 double c3 = cos(q3);
1806 double s3 = sin(q3);
1807 double c23 = cos(q2+q3);
1808 double s23 = sin(q2+q3);
1809 double s5 = sin(q5);
1811 bool cond1 = fabs(s5) < 1e-1;
1812 bool cond2 = fabs(
a3*s3+c3*
d4) < 1e-1;
1813 bool cond3 = fabs(
a2*c2-
a3*c23+s23*d4+
a1) < 1e-1;
1834 J[1][0] = 0; J[2][0] = 0; J[3][0] = 0; J[4][0] = 0; J[5][0] = 0;
1835 J[1][1] = 0; J[2][1] = 0; J[3][1] = 0; J[4][1] = 0; J[5][1] = 0;
1836 J[1][2] = 0; J[2][2] = 0; J[3][2] = 0; J[4][2] = 0; J[5][2] = 0;
1842 J[0][0] = 0; J[3][0] = 0; J[4][0] = 0; J[5][0] = 0;
1843 J[0][1] = 0; J[3][1] = 0; J[4][1] = 0; J[5][1] = 0;
1861 for (
unsigned int i = 0; i < 6; i++)
1863 if (articularCoordinates[i] <=
joint_min[i])
1865 difft =
joint_min[i] - articularCoordinates[i];
1869 artNumb = -(int)i-1;
1874 for (
unsigned int i = 0; i < 6; i++)
1876 if (articularCoordinates[i] >=
joint_max[i])
1878 difft = articularCoordinates[i] -
joint_max[i];
1882 artNumb = (int)(i+1);
1888 std::cout <<
"\nWarning: Velocity control stopped: axis " << fabs((
float)artNumb) <<
" on joint limit!" <<std::endl;
1905 vpSimulatorViper850::getCameraDisplacement(
vpColVector &displacement)
1920 vpSimulatorViper850::getArticularDisplacement(
vpColVector &displacement)
1953 if ( ! first_time_getdis )
1959 std::cout <<
"getDisplacement() CAMERA_FRAME not implemented\n";
1966 displacement = q_cur - q_prev_getdis;
1972 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
1979 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
1987 first_time_getdis =
false;
1991 q_prev_getdis = q_cur;
2059 fd = fopen(filename,
"r") ;
2063 char line[FILENAME_MAX];
2064 char dummy[FILENAME_MAX];
2066 bool sortie =
false;
2070 if (fgets (line, FILENAME_MAX, fd) != NULL) {
2071 if ( strncmp (line,
"#", 1) != 0) {
2073 if ( strncmp (line, head,
sizeof(head)-1) == 0) {
2085 while ( sortie !=
true );
2089 int ret = sscanf(line,
"%s %lf %lf %lf %lf %lf %lf",
2091 &q[0], &q[1], &q[2], &q[3], &q[4], &q[5]);
2130 fd = fopen(filename,
"w") ;
2135 #Viper - Position - Version 1.0\n\
2138 # Joint position in degrees\n\
2143 fprintf(fd,
"R: %lf %lf %lf %lf %lf %lf\n",
2293 std::string scene_dir_;
2295 scene_dir_ = VISP_SCENES_DIR;
2299 std::cout <<
"The simulator uses data from VISP_SCENES_DIR=" << scene_dir_ << std::endl;
2302 std::cout <<
"Cannot get VISP_SCENES_DIR environment variable" << std::endl;
2306 unsigned int name_length = 30;
2307 if (scene_dir_.size() > FILENAME_MAX)
2310 unsigned int full_length = (
unsigned int)scene_dir_.size() + name_length;
2311 if (full_length > FILENAME_MAX)
2314 char *name_cam =
new char [full_length];
2316 strcpy(name_cam, scene_dir_.c_str());
2317 strcat(name_cam,
"/camera.bnd");
2320 if (arm_dir.size() > FILENAME_MAX)
2322 full_length = (
unsigned int)arm_dir.size() + name_length;
2323 if (full_length > FILENAME_MAX)
2326 char *name_arm =
new char [full_length];
2327 strcpy(name_arm, arm_dir.c_str());
2328 strcat(name_arm,
"/viper850_arm1.bnd");
2330 strcpy(name_arm, arm_dir.c_str());
2331 strcat(name_arm,
"/viper850_arm2.bnd");
2333 strcpy(name_arm, arm_dir.c_str());
2334 strcat(name_arm,
"/viper850_arm3.bnd");
2336 strcpy(name_arm, arm_dir.c_str());
2337 strcat(name_arm,
"/viper850_arm4.bnd");
2339 strcpy(name_arm, arm_dir.c_str());
2340 strcat(name_arm,
"/viper850_arm5.bnd");
2342 strcpy(name_arm, arm_dir.c_str());
2343 strcat(name_arm,
"/viper850_arm6.bnd");
2352 add_rfstack(IS_BACK);
2354 add_vwstack (
"start",
"depth", 0.0, 100.0);
2355 add_vwstack (
"start",
"window", -0.1,0.1,-0.1,0.1);
2356 add_vwstack (
"start",
"type", PERSPECTIVE);
2370 bool changed =
false;
2374 if (std::fabs(displacement[2][3]) > std::numeric_limits<double>::epsilon())
2397 float w44o[4][4],w44cext[4][4],x,y,z;
2401 add_vwstack (
"start",
"cop", w44cext[3][0],w44cext[3][1],w44cext[3][2]);
2402 x = w44cext[2][0] + w44cext[3][0];
2403 y = w44cext[2][1] + w44cext[3][1];
2404 z = w44cext[2][2] + w44cext[3][2];
2405 add_vwstack (
"start",
"vrp", x,y,z);
2406 add_vwstack (
"start",
"vpn", w44cext[2][0],w44cext[2][1],w44cext[2][2]);
2407 add_vwstack (
"start",
"vup", w44cext[1][0],w44cext[1][1],w44cext[1][2]);
2408 add_vwstack (
"start",
"window", -u, u, -v, v);
2416 vp2jlc_matrix(fMit[0],w44o);
2419 vp2jlc_matrix(fMit[1],w44o);
2422 vp2jlc_matrix(fMit[2],w44o);
2425 vp2jlc_matrix(fMit[3],w44o);
2428 vp2jlc_matrix(fMit[6],w44o);
2436 cMe = fMit[6] * cMe;
2437 vp2jlc_matrix(cMe,w44o);
2443 vp2jlc_matrix(
fMo,w44o);
2483 std::cout <<
"Used joint coordinates (rad): " << articularCoordinates.
t() << std::endl;
2513 fMo = fMit[7] * cMo_;
static void displayCamera(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color, unsigned int thickness)
Definition of the vpMatrix class.
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)
void get_eJe(const vpColVector &q, vpMatrix &eJe) const
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
bool singularityTest(const vpColVector q, vpMatrix &J)
vpHomogeneousMatrix eMc
End effector to camera transformation.
Error that can be emited by the vpRobot class and its derivates.
vpColVector get_artCoord()
virtual ~vpSimulatorViper850()
void get_fMi(vpHomogeneousMatrix *fMit)
void computeArticularVelocity()
static bool readPosFile(const char *filename, vpColVector &q)
static const vpToolType defaultTool
Default tool attached to the robot end effector.
unsigned int getWidth() const
void get_cMe(vpHomogeneousMatrix &cMe)
double getSamplingTime() const
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
unsigned int jointLimitArt
static void * launcher(void *arg)
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
Point coordinates conversion from normalized coordinates in meter to pixel coordinates ...
void getExternalImage(vpImage< vpRGBa > &I)
bool constantSamplingTimeMode
Flag used to force the sampling time in the thread computing the robot's displacement to a constant v...
bool singularityManagement
double getMaxTranslationVelocity(void) const
static const vpColor none
Initialize the position controller.
error that can be emited by ViSP classes.
void track(const vpHomogeneousMatrix &cMo)
void get_fJe(vpMatrix &fJe)
vpColVector get_velocity()
static double measureTimeMs()
double get_y() const
Get the point y coordinate in the image plane.
static const char *const CONST_MARLIN_F033C_CAMERA_NAME
static int wait(double t0, double t)
static const vpColor green
static void flush(const vpImage< unsigned char > &I)
double getMaxRotationVelocity(void) const
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Class that defines what is a point.
static Type maximum(const Type &a, const Type &b)
The vpRotationMatrix considers the particular case of a rotation matrix.
void initPersProjWithoutDistortion(const double px, const double py, const double u0, const double v0)
pthread_mutex_t mutex_artCoord
pthread_mutex_t mutex_display
void move(const char *filename)
vpDisplayRobotType displayType
Initialize the velocity controller.
vpCameraParameters cameraParam
void setJointLimit(const vpColVector &limitMin, const vpColVector &limitMax)
void setToolType(vpViper850::vpToolType tool)
Set the current tool type.
void setExternalCameraPosition(const vpHomogeneousMatrix camMf_)
Initialize the acceleration controller.
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
void set_displayBusy(const bool &status)
vpCameraParametersProjType
void initialiseObjectRelativeToCamera(const vpHomogeneousMatrix &cMo)
static void display(const vpImage< unsigned char > &I)
vpRowVector t() const
Transpose of a vector.
vpToolType
List of possible tools that can be attached to the robot end-effector.
Generic class defining intrinsic camera parameters.
vpHomogeneousMatrix getExternalCameraPosition() const
void getDisplacement(const vpRobot::vpControlFrameType frame, vpColVector &displacement)
Modelisation of the ADEPT Viper 850 robot.
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
double get_x() const
Get the point x coordinate in the image plane.
vpToolType getToolType() const
Get the current tool type.
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)
static Type minimum(const Type &a, const Type &b)
Class that consider the particular case of twist transformation matrix that allows to transform a vel...
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false) const
void set_velocity(const vpColVector &vel)
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
Construction from translation vector and rotation matrix.
static double rad(double deg)
void setExternalCameraParameters(const vpCameraParameters &cam)
vpControlFrameType getRobotFrame(void) const
void get_fJe(const vpColVector &q, vpMatrix &fJe) const
This class aims to be a basis used to create all the simulators of robots.
vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
vpHomogeneousMatrix * fMi
pthread_mutex_t mutex_fMi
void get_cMe(vpHomogeneousMatrix &cMe) const
void updateArticularPosition()
bool setVelocityCalled
Flag used to specify to the thread managing the robot displacements that the setVelocity() method has...
void display_scene(Matrix mat, Bound_scene &sc, const vpImage< vpRGBa > &I, const vpColor &color)
vpHomogeneousMatrix camMf
vpHomogeneousMatrix navigation(const vpImage< vpRGBa > &I, bool &changed)
static double deg(double rad)
Class that provides a data structure for the column vectors as well as a set of operations on these v...
void setCameraParameters(const vpCameraParameters &cam)
The pose is a complete representation of every rigid motion in the euclidian space.
vpHomogeneousMatrix inverse() const
virtual vpRobotStateType getRobotState(void) const
unsigned int getHeight() const
Class that consider the case of the Euler angle using the x-y-z convention, where are respectively ...
vpControlFrameType setRobotFrame(vpRobot::vpControlFrameType newFrame)
vpMatrix pseudoInverse(double svThreshold=1e-6) const
Compute the pseudo inverse of the matrix using the SVD.
static double measureTimeSecond()
void findHighestPositioningSpeed(vpColVector &q)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
void set_artCoord(const vpColVector &coord)
virtual void displayLine(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1)=0
void get_cVe(vpVelocityTwistMatrix &cVe)
vpCameraParameters::vpCameraParametersProjType projModel
void set_artVel(const vpColVector &vel)
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height)
unsigned int getRows() const
Return the number of rows of the matrix.
void getVelocity(const vpRobot::vpControlFrameType frame, vpColVector &q)
pthread_mutex_t mutex_velocity
static const double defaultPositioningVelocity
static bool savePosFile(const char *filename, const vpColVector &q)
Class that consider the case of a translation vector.
Class that consider the case of the parameterization for the rotation.
double getPositioningVelocity(void)
pthread_mutex_t mutex_artVel
static double minTimeForUsleepCall
static const unsigned int njoint
Number of joint.
vpHomogeneousMatrix camMf2
bool initialiseCameraRelativeToObject(const vpHomogeneousMatrix &cMo)
static const char *const CONST_PTGREY_FLEA2_CAMERA_NAME
void setWorldCoordinates(const double ox, const double oy, const double oz)
Set the point world coordinates. We mean here the coordinates of the point in the object frame...
void get_eJe(vpMatrix &eJe)
void resize(const unsigned int i, const bool flagNullify=true)