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)
75 DWORD dwThreadIdArray;
83 #elif defined (VISP_HAVE_PTHREAD)
90 pthread_attr_init(&attr);
91 pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE);
93 pthread_create(&thread, NULL,
launcher, (
void *)
this);
113 mutex_fMi = CreateMutex(NULL,FALSE,NULL);
120 DWORD dwThreadIdArray;
128 #elif defined(VISP_HAVE_PTHREAD)
135 pthread_attr_init(&attr);
136 pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE);
138 pthread_create(&thread, NULL,
launcher, (
void *)
this);
152 WaitForSingleObject(
hThread,INFINITE);
159 #elif defined(VISP_HAVE_PTHREAD)
160 pthread_attr_destroy(&attr);
161 pthread_join(thread, NULL);
172 for(
int i = 0; i < 6; i++)
193 arm_dir = VISP_ROBOT_ARMS_DIR;
197 std::cout <<
"The simulator uses data from VISP_ROBOT_ARMS_DIR=" << arm_dir << std::endl;
200 std::cout <<
"Cannot get VISP_ROBOT_ARMS_DIR environment variable" << std::endl;
214 zeroPos[1] = -M_PI/2; zeroPos[2] = M_PI;
217 reposPos[1] = -M_PI/2; reposPos[2] = M_PI; reposPos[4] = M_PI/2;
224 first_time_getdis =
true;
306 etc[0] = -0.04558630174;
307 etc[1] = -0.00134326752;
308 etc[2] = 0.001000828017;
315 std::cout <<
"This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
339 const unsigned int &image_width,
340 const unsigned int &image_height)
350 if (image_width == 640 && image_height == 480)
352 std::cout <<
"Get default camera parameters for camera \""
357 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
363 if (image_width == 640 && image_height == 480) {
364 std::cout <<
"Get default camera parameters for camera \""
369 vpTRACE(
"Cannot get default intrinsic camera parameters for this image resolution");
375 std::cout <<
"This tool is not handled in vpSimulatorViper850.cpp" << std::endl;
433 double tcur_1 =
tcur;
446 double ellapsedTime = (
tcur -
tprev) * 1e-3;
463 articularVelocities = 0.0;
469 articularCoordinates[0] = articularCoordinates[0] + ellapsedTime*articularVelocities[0];
470 articularCoordinates[1] = articularCoordinates[1] + ellapsedTime*articularVelocities[1];
471 articularCoordinates[2] = articularCoordinates[2] + ellapsedTime*articularVelocities[2];
472 articularCoordinates[3] = articularCoordinates[3] + ellapsedTime*articularVelocities[3];
473 articularCoordinates[4] = articularCoordinates[4] + ellapsedTime*articularVelocities[4];
474 articularCoordinates[5] = articularCoordinates[5] + ellapsedTime*articularVelocities[5];
481 ellapsedTime = (
joint_min[(
unsigned int)(-jl-1)] - articularCoordinates[(
unsigned int)(-jl-1)])/(articularVelocities[(
unsigned int)(-jl-1)]);
483 ellapsedTime = (
joint_max[(
unsigned int)(jl-1)] - articularCoordinates[(
unsigned int)(jl-1)])/(articularVelocities[(
unsigned int)(jl-1)]);
485 for (
unsigned int i = 0; i < 6; i++)
486 articularCoordinates[i] = articularCoordinates[i] + ellapsedTime*articularVelocities[i];
528 for (
int k = 1; k < 7; k++)
581 double c23 = cos(q2+q3);
582 double s23 = sin(q2+q3);
599 fMit[0][0][3] =
a1*c1;
600 fMit[0][1][3] =
a1*s1;
603 fMit[1][0][0] = c1*c2;
604 fMit[1][1][0] = s1*c2;
606 fMit[1][0][1] = -c1*s2;
607 fMit[1][1][1] = -s1*s2;
612 fMit[1][0][3] = c1*(
a2*c2+
a1);
613 fMit[1][1][3] = s1*(
a2*c2+
a1);
614 fMit[1][2][3] =
d1-
a2*s2;
616 double quickcomp1 =
a3*c23-
a2*c2-
a1;
618 fMit[2][0][0] = -c1*c23;
619 fMit[2][1][0] = -s1*c23;
624 fMit[2][0][2] = c1*s23;
625 fMit[2][1][2] = s1*s23;
627 fMit[2][0][3] = -c1*quickcomp1;
628 fMit[2][1][3] = -s1*quickcomp1;
629 fMit[2][2][3] =
a3*s23-
a2*s2+
d1;
631 double quickcomp2 = c1*(s23*
d4 - quickcomp1);
632 double quickcomp3 = s1*(s23*
d4 - quickcomp1);
634 fMit[3][0][0] = -c1*c23*c4+s1*s4;
635 fMit[3][1][0] = -s1*c23*c4-c1*s4;
636 fMit[3][2][0] = s23*c4;
637 fMit[3][0][1] = c1*s23;
638 fMit[3][1][1] = s1*s23;
640 fMit[3][0][2] = -c1*c23*s4-s1*c4;
641 fMit[3][1][2] = -s1*c23*s4+c1*c4;
642 fMit[3][2][2] = s23*s4;
643 fMit[3][0][3] = quickcomp2;
644 fMit[3][1][3] = quickcomp3;
645 fMit[3][2][3] = c23*
d4+
a3*s23-
a2*s2+
d1;
647 fMit[4][0][0] = c1*(s23*s5-c5*c23*c4)+s1*c5*s4;
648 fMit[4][1][0] = s1*(s23*s5-c5*c23*c4)-c1*c5*s4;
649 fMit[4][2][0] = s23*c4*c5+c23*s5;
650 fMit[4][0][1] = c1*c23*s4+s1*c4;
651 fMit[4][1][1] = s1*c23*s4-c1*c4;
652 fMit[4][2][1] = -s23*s4;
653 fMit[4][0][2] = c1*(s23*c5+s5*c23*c4)-s1*s5*s4;
654 fMit[4][1][2] = s1*(s23*c5+s5*c23*c4)+c1*s5*s4;
655 fMit[4][2][2] = -s23*c4*s5+c23*c5;
656 fMit[4][0][3] = quickcomp2;
657 fMit[4][1][3] = quickcomp3;
658 fMit[4][2][3] = c23*
d4+
a3*s23-
a2*s2+
d1;
660 fMit[5][0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
661 fMit[5][1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
662 fMit[5][2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
663 fMit[5][0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
664 fMit[5][1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
665 fMit[5][2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
666 fMit[5][0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
667 fMit[5][1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
668 fMit[5][2][2] = -s23*c4*s5+c23*c5;
669 fMit[5][0][3] = quickcomp2;
670 fMit[5][1][3] = quickcomp3;
671 fMit[5][2][3] = s23*
a3+c23*
d4-
a2*s2+
d1;
673 fMit[6][0][0] = c1*(c23*(c4*c5*c6-s4*s6)-s23*s5*c6)-s1*(s4*c5*c6+c4*s6);
674 fMit[6][1][0] = -s1*(c23*(-c4*c5*c6+s4*s6)+s23*s5*c6)+c1*(s4*c5*c6+c4*s6);
675 fMit[6][2][0] = s23*(s4*s6-c4*c5*c6)-c23*s5*c6;
676 fMit[6][0][1] = -c1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)+s1*(s4*c5*s6-c4*c6);
677 fMit[6][1][1] = -s1*(c23*(c4*c5*s6+s4*c6)-s23*s5*s6)-c1*(s4*c5*s6-c4*c6);
678 fMit[6][2][1] = s23*(c4*c5*s6+s4*c6)+c23*s5*s6;
679 fMit[6][0][2] = c1*(c23*c4*s5+s23*c5)-s1*s4*s5;
680 fMit[6][1][2] = s1*(c23*c4*s5+s23*c5)+c1*s4*s5;
681 fMit[6][2][2] = -s23*c4*s5+c23*c5;
682 fMit[6][0][3] = c1*(c23*(c4*s5*
d6-
a3)+s23*(c5*
d6+
d4)+a1+
a2*c2)-s1*s4*s5*
d6;
683 fMit[6][1][3] = s1*(c23*(c4*s5*
d6-
a3)+s23*(c5*
d6+
d4)+a1+
a2*c2)+c1*s4*s5*
d6;
684 fMit[6][2][3] = s23*(
a3-c4*s5*
d6)+c23*(c5*
d6+
d4)-
a2*s2+
d1;
694 for (
int i = 0; i < 8; i++)
697 #elif defined(VISP_HAVE_PTHREAD)
699 for (
int i = 0; i < 8; i++)
724 std::cout <<
"Change the control mode from velocity to position control.\n";
734 std::cout <<
"Change the control mode from stop to velocity control.\n";
820 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
822 "Cannot send a velocity to the robot "
823 "use setRobotState(vpRobot::STATE_VELOCITY_CONTROL) first) ");
828 double scale_trans_sat = 1;
829 double scale_rot_sat = 1;
830 double scale_sat = 1;
845 vpERROR_TRACE (
"The velocity vector must have a size of 6 !!!!");
849 for (
unsigned int i = 0 ; i < 3; ++ i)
851 vel_abs = fabs (vel[i]);
854 vel_trans_max = vel_abs;
856 "(axis nr. %d).", vel[i], i+1);
859 vel_abs = fabs (vel[i+3]);
861 vel_rot_max = vel_abs;
863 "(axis nr. %d).", vel[i+3], i+4);
873 if ( (scale_trans_sat < 1) || (scale_rot_sat < 1) )
875 if (scale_trans_sat < scale_rot_sat)
876 scale_sat = scale_trans_sat;
878 scale_sat = scale_rot_sat;
888 vpERROR_TRACE (
"The velocity vector must have a size of 6 !!!!");
891 for (
unsigned int i = 0 ; i < 6; ++ i)
893 vel_abs = fabs (vel[i]);
896 vel_rot_max = vel_abs;
898 "(axis nr. %d).", vel[i], i+1);
903 if ( scale_rot_sat < 1 )
904 scale_sat = scale_rot_sat;
927 double scale_rot_sat = 1;
928 double scale_sat = 1;
946 articularVelocity = eJe*eVc*velocityframe;
957 articularVelocity = fJe*velocityframe;
963 articularVelocity = velocityframe;
980 for (
unsigned int i = 0 ; i < 6; ++ i)
982 vel_abs = fabs (articularVelocity[i]);
985 vel_rot_max = vel_abs;
987 "(axis nr. %d).", articularVelocity[i], i+1);
992 if ( scale_rot_sat < 1 )
993 scale_sat = scale_rot_sat;
1068 vel = cVe*eJe*articularVelocity;
1073 vel = articularVelocity;
1080 vel = fJe*articularVelocity;
1090 "Case not taken in account.");
1152 double velmax = fabs(q[0]);
1153 for (
unsigned int i = 1; i < 6; i++)
1155 if (velmax < fabs(q[i]))
1156 velmax = fabs(q[i]);
1243 "Modification of the robot state");
1260 for (
unsigned int i=0; i < 3; i++)
1277 qdes = articularCoordinates;
1282 error = qdes - articularCoordinates;
1299 "Position out of range.");
1301 }
while (errsqr > 1e-8 && nbSol > 0);
1311 error = q - articularCoordinates;
1324 }
while (errsqr > 1e-8);
1335 for (
unsigned int i=0; i < 3; i++)
1347 qdes = articularCoordinates;
1351 error = qdes - articularCoordinates;
1367 }
while (errsqr > 1e-8 && nbSol > 0);
1372 vpERROR_TRACE (
"Positionning error. Mixt frame not implemented");
1374 "Positionning error: "
1375 "Mixt frame not implemented.");
1454 position[0] = pos1 ;
1455 position[1] = pos2 ;
1456 position[2] = pos3 ;
1457 position[3] = pos4 ;
1458 position[4] = pos5 ;
1459 position[5] = pos6 ;
1515 "Bad position in filename.");
1611 for (
unsigned int i=0; i <3; i++)
1621 vpERROR_TRACE (
"Positionning error. Mixt frame not implemented");
1623 "Positionning error: "
1624 "Mixt frame not implemented.");
1653 for(
unsigned int j=0;j<3;j++)
1655 position[j]=posRxyz[j];
1656 position[j+3]=RtuVect[j];
1671 vpTRACE(
"Joint limit vector has not a size of 6 !");
1703 double c2 = cos(q2);
1704 double c3 = cos(q3);
1705 double s3 = sin(q3);
1706 double c23 = cos(q2+q3);
1707 double s23 = sin(q2+q3);
1708 double s5 = sin(q5);
1710 bool cond1 = fabs(s5) < 1e-1;
1711 bool cond2 = fabs(
a3*s3+c3*
d4) < 1e-1;
1712 bool cond3 = fabs(
a2*c2-
a3*c23+s23*d4+
a1) < 1e-1;
1733 J[1][0] = 0; J[2][0] = 0; J[3][0] = 0; J[4][0] = 0; J[5][0] = 0;
1734 J[1][1] = 0; J[2][1] = 0; J[3][1] = 0; J[4][1] = 0; J[5][1] = 0;
1735 J[1][2] = 0; J[2][2] = 0; J[3][2] = 0; J[4][2] = 0; J[5][2] = 0;
1741 J[0][0] = 0; J[3][0] = 0; J[4][0] = 0; J[5][0] = 0;
1742 J[0][1] = 0; J[3][1] = 0; J[4][1] = 0; J[5][1] = 0;
1760 for (
unsigned int i = 0; i < 6; i++)
1762 if (articularCoordinates[i] <=
joint_min[i])
1764 difft =
joint_min[i] - articularCoordinates[i];
1768 artNumb = -(int)i-1;
1773 for (
unsigned int i = 0; i < 6; i++)
1775 if (articularCoordinates[i] >=
joint_max[i])
1777 difft = articularCoordinates[i] -
joint_max[i];
1781 artNumb = (int)(i+1);
1787 std::cout <<
"\nWarning: Velocity control stopped: axis " << fabs((
float)artNumb) <<
" on joint limit!" <<std::endl;
1804 vpSimulatorViper850::getCameraDisplacement(
vpColVector &displacement)
1819 vpSimulatorViper850::getArticularDisplacement(
vpColVector &displacement)
1852 if ( ! first_time_getdis )
1858 std::cout <<
"getDisplacement() CAMERA_FRAME not implemented\n";
1865 displacement = q_cur - q_prev_getdis;
1871 std::cout <<
"getDisplacement() REFERENCE_FRAME not implemented\n";
1878 std::cout <<
"getDisplacement() MIXT_FRAME not implemented\n";
1886 first_time_getdis =
false;
1890 q_prev_getdis = q_cur;
1959 fd = fopen(filename,
"r") ;
1963 char line[FILENAME_MAX];
1964 char dummy[FILENAME_MAX];
1966 bool sortie =
false;
1970 if (fgets (line, FILENAME_MAX, fd) != NULL) {
1971 if ( strncmp (line,
"#", 1) != 0) {
1973 if ( strncmp (line, head,
sizeof(head)-1) == 0) {
1985 while ( sortie !=
true );
1989 sscanf(line,
"%s %lf %lf %lf %lf %lf %lf",
1991 &q[0], &q[1], &q[2],
1992 &q[3], &q[4], &q[5]);
2027 fd = fopen(filename,
"w") ;
2032 #Viper - Position - Version 1.0\n\
2035 # Joint position in degrees\n\
2040 fprintf(fd,
"R: %lf %lf %lf %lf %lf %lf\n",
2190 std::string scene_dir;
2192 scene_dir = VISP_SCENES_DIR;
2196 std::cout <<
"The simulator uses data from VISP_SCENES_DIR=" << scene_dir << std::endl;
2199 std::cout <<
"Cannot get VISP_SCENES_DIR environment variable" << std::endl;
2203 char name_cam[FILENAME_MAX];
2205 strcpy(name_cam, scene_dir.c_str());
2206 strcat(name_cam,
"/camera.bnd");
2209 char name_arm[FILENAME_MAX];
2210 strcpy(name_arm, arm_dir.c_str());
2211 strcat(name_arm,
"/viper850_arm1.bnd");
2213 strcpy(name_arm, arm_dir.c_str());
2214 strcat(name_arm,
"/viper850_arm2.bnd");
2216 strcpy(name_arm, arm_dir.c_str());
2217 strcat(name_arm,
"/viper850_arm3.bnd");
2219 strcpy(name_arm, arm_dir.c_str());
2220 strcat(name_arm,
"/viper850_arm4.bnd");
2222 strcpy(name_arm, arm_dir.c_str());
2223 strcat(name_arm,
"/viper850_arm5.bnd");
2225 strcpy(name_arm, arm_dir.c_str());
2226 strcat(name_arm,
"/viper850_arm6.bnd");
2235 add_rfstack(IS_BACK);
2237 add_vwstack (
"start",
"depth", 0.0, 100.0);
2238 add_vwstack (
"start",
"window", -0.1,0.1,-0.1,0.1);
2239 add_vwstack (
"start",
"type", PERSPECTIVE);
2250 bool changed =
false;
2254 if (std::fabs(displacement[2][3]) > std::numeric_limits<double>::epsilon())
2277 float w44o[4][4],w44cext[4][4],x,y,z;
2281 add_vwstack (
"start",
"cop", w44cext[3][0],w44cext[3][1],w44cext[3][2]);
2282 x = w44cext[2][0] + w44cext[3][0];
2283 y = w44cext[2][1] + w44cext[3][1];
2284 z = w44cext[2][2] + w44cext[3][2];
2285 add_vwstack (
"start",
"vrp", x,y,z);
2286 add_vwstack (
"start",
"vpn", w44cext[2][0],w44cext[2][1],w44cext[2][2]);
2287 add_vwstack (
"start",
"vup", w44cext[1][0],w44cext[1][1],w44cext[1][2]);
2288 add_vwstack (
"start",
"window", -u, u, -v, v);
2296 vp2jlc_matrix(fMit[0],w44o);
2299 vp2jlc_matrix(fMit[1],w44o);
2302 vp2jlc_matrix(fMit[2],w44o);
2305 vp2jlc_matrix(fMit[3],w44o);
2308 vp2jlc_matrix(fMit[6],w44o);
2316 cMe = fMit[6] * cMe;
2317 vp2jlc_matrix(cMe,w44o);
2323 vp2jlc_matrix(
fMo,w44o);
2363 std::cout <<
"Used joint coordinates (rad): " << articularCoordinates.
t() << std::endl;
static void displayCamera(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color, unsigned int thickness)
vpToolType getToolType()
Get the current tool type.
Definition of the vpMatrix class.
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &q)
void setPosition(const vpRobot::vpControlFrameType frame, const vpColVector &q)
vpColVector get_artVel() 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.
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...
void get_eJe(const vpColVector &q, vpMatrix &eJe)
unsigned int jointLimitArt
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 ...
vpColVector get_artCoord() const
virtual vpRobotStateType getRobotState(void)
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.
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)
double sumSquare() const
return sum of the Aij^2 (for all i, for all j)
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)
vpControlFrameType getRobotFrame(void)
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.
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 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
double get_x() const
Get the point x coordinate in the image plane.
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...
void set_velocity(const vpColVector &vel)
static void displayFrame(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double size, const vpColor &color, unsigned int thickness=1)
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)
void get_fJe(const vpColVector &q, vpMatrix &fJe)
This class aims to be a basis used to create all the simulators of robots.
vpRobot::vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
vpHomogeneousMatrix * fMi
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)
void setExternalCameraPosition(const vpHomogeneousMatrix camMf)
vpHomogeneousMatrix camMf
vpHomogeneousMatrix navigation(const vpImage< vpRGBa > &I, bool &changed)
static double deg(double rad)
vpMatrix eJe
robot Jacobian expressed in the end-effector frame
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
void get_cMe(vpHomogeneousMatrix &cMe)
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.
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)
static DWORD WINAPI launcher(LPVOID lpParam)
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)
static const double defaultPositioningVelocity
vpMatrix fJe
robot Jacobian expressed in the robot reference frame available
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)
static double minTimeForUsleepCall
unsigned int getInverseKinematics(const vpHomogeneousMatrix &fMc, vpColVector &q, const bool &verbose=false)
static const unsigned int njoint
Number of joint.
vpHomogeneousMatrix get_fMc(const vpColVector &q)
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)