ViSP  2.9.0
testRobotAfma6Pose.cpp
1 /****************************************************************************
2  *
3  * $Id: testRobotAfma6Pose.cpp 4574 2014-01-09 08:48:51Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2014 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  *
34  * Description:
35  * Test for Afma 6 dof robot.
36  *
37  * Authors:
38  * Fabien Spindler
39  *
40  *****************************************************************************/
41 
54 #include <visp/vpImage.h>
55 #include <visp/vpDisplayX.h>
56 #include <visp/vpDisplayOpenCV.h>
57 #include <visp/vpDisplayGTK.h>
58 #include <visp/vpRobotAfma6.h>
59 #include <visp/vpCameraParameters.h>
60 #include <visp/vpPixelMeterConversion.h>
61 #include <visp/vp1394TwoGrabber.h>
62 #include <visp/vpPoint.h>
63 #include <visp/vpDot.h>
64 #include <visp/vpPose.h>
65 #include <visp/vpDebug.h>
66 #include <iostream>
67 #if defined(VISP_HAVE_AFMA6) && defined(VISP_HAVE_DC1394_2)
68 
69 int main()
70 {
71  try {
72  // Create an image B&W container
74 
75  // Create a firewire grabber based on libdc1394-2.x
77 
78  // Grab an image from the firewire camera
79  g.acquire(I);
80 
81  // Create an image viewer for the image
82 #ifdef VISP_HAVE_X11
83  vpDisplayX display(I,100,100,"Current image") ;
84 #elif defined(VISP_HAVE_OPENCV)
85  vpDisplayOpenCV display(I,100,100,"Current image") ;
86 #elif defined(VISP_HAVE_GTK)
87  vpDisplayGTK display(I,100,100,"Current image") ;
88 #endif
89 
90  // Display the image
92  vpDisplay::flush(I) ;
93 
94  // Define a squared target
95  // The target is made of 4 planar points (square dim = 0.077m)
96  double sdim = 0.077; // square width and height
97  vpPoint target[4] ;
98  // Set the point world coordinates (x,y,z) in the object frame
99  // o ----> x
100  // |
101  // |
102  // \/
103  // y
104  target[0].setWorldCoordinates(-sdim/2., -sdim/2., 0) ;
105  target[1].setWorldCoordinates( sdim/2., -sdim/2., 0) ;
106  target[2].setWorldCoordinates( sdim/2., sdim/2., 0) ;
107  target[3].setWorldCoordinates(-sdim/2., sdim/2., 0) ;
108 
109  // Image processing to extract the 2D coordinates in sub-pixels of the 4
110  // points from the image acquired by the camera
111  // Creation of 4 trackers
112  vpDot dot[4];
113  vpImagePoint cog;
114  for (int i=0; i < 4; i ++) {
115  dot[i].setGraphics(true); // to display the tracking results
116  std::cout << "Click on dot " << i << std::endl;
117  dot[i].initTracking( I );
118  // The tracker computes the sub-pixels coordinates in the image
119  // i ----> u
120  // |
121  // |
122  // \/
123  // v
124  std::cout << " Coordinates: " << dot[i].getCog() << std::endl;
125  // Flush the tracking results in the viewer
126  vpDisplay::flush(I) ;
127  }
128 
129  // Create an intrinsic camera parameters structure
130  vpCameraParameters cam;
131 
132  // Create a robot access
133  vpRobotAfma6 robot;
134 
135  // Load the end-effector to camera frame transformation obtained
136  // using a camera intrinsic model with distortion
139 
140  // Get the intrinsic camera parameters associated to the image
141  robot.getCameraParameters(cam, I);
142 
143  // Using the camera parameters, compute the perspective projection (transform
144  // the dot sub-pixel coordinates into coordinates in the camera frame in
145  // meter)
146  for (int i=0; i < 4; i ++) {
147  double x=0, y=0 ; // coordinates of the dots in the camera frame
148  // c ----> x
149  // |
150  // |
151  // \/
152  // y
153  //pixel to meter conversion
154  cog = dot[i].getCog();
155  vpPixelMeterConversion::convertPoint(cam, cog, x, y);
156  target[i].set_x(x) ;
157  target[i].set_y(y) ;
158  }
159 
160  // From now, in target[i], we have the 3D coordinates of a point in the
161  // object frame, and their correspondances in the camera frame. We can now
162  // compute the pose cMo between the camera and the object.
163  vpPose pose;
164  // Add the 4 points to compute the pose
165  for (int i=0; i < 4; i ++) {
166  pose.addPoint(target[i]) ;
167  }
168  // Create an homogeneous matrix for the camera to object transformation
169  // computed just bellow
172  vpRxyzVector r;
173  // Compute the pose: initialisation is done by Lagrange method, and the final
174  // pose is computed by the more accurate Virtual Visual Servoing method.
176 
177 
178  std::cout << "Pose cMo: " << std::endl << cMo;
179  cMo.extract(R);
180  r.buildFrom(R);
181  std::cout << " rotation: "
182  << vpMath::deg(r[0]) << " "
183  << vpMath::deg(r[1]) << " "
184  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
185 
186  // Get the robot position in the reference frame
188  vpColVector p; // position x,y,z,rx,ry,rz
190  std::cout << "Robot pose in reference frame: " << p << std::endl;
192  t[0] = p[0]; t[1] = p[1]; t[2] = p[2];
193  r[0] = p[3]; r[1] = p[4]; r[2] = p[5];
194  R.buildFrom(r);
195  rMc.buildFrom(t, R);
196  std::cout << "Pose rMc: " << std::endl << rMc;
197  rMc.extract(R);
198  r.buildFrom(R);
199  std::cout << " rotation: "
200  << vpMath::deg(r[0]) << " "
201  << vpMath::deg(r[1]) << " "
202  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
203 
205  std::cout << "Robot pose in articular: " << p << std::endl;
206 
207  robot.get_fMc(p, rMc);
208  std::cout << "Pose rMc from MGD: " << std::endl << rMc;
209  rMc.extract(R);
210  r.buildFrom(R);
211  std::cout << " rotation: "
212  << vpMath::deg(r[0]) << " "
213  << vpMath::deg(r[1]) << " "
214  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
215 
217  rMo = rMc * cMo;
218  std::cout << "Pose rMo = rMc * cMo: " << std::endl << rMo;
219  rMo.extract(R);
220  r.buildFrom(R);
221  std::cout << " rotation: "
222  << vpMath::deg(r[0]) << " "
223  << vpMath::deg(r[1]) << " "
224  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
225 
226  }
227  catch(vpException e) {
228  std::cout << "Catch an exception: " << e << std::endl;
229  }
230  return 0;
231 }
232 #else
233 int main()
234 {
235  std::cout << "Sorry, test not valid. You should have an Afma6 robot..."
236  << std::endl;
237  return 0;
238 }
239 
240 #endif
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
Definition: vpAfma6.cpp:1248
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpAfma6.cpp:745
Define the X11 console to display images.
Definition: vpDisplayX.h:152
error that can be emited by ViSP classes.
Definition: vpException.h:76
void set_x(const double x)
Set the point x coordinate in the image plane.
Definition: vpPoint.h:194
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
Point coordinates conversion from pixel coordinates to normalized coordinates in meter...
void acquire(vpImage< unsigned char > &I)
static void flush(const vpImage< unsigned char > &I)
Definition: vpDisplay.cpp:1994
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
Control of Irisa's gantry robot named Afma6.
Definition: vpRobotAfma6.h:214
Class that defines what is a point.
Definition: vpPoint.h:65
The vpRotationMatrix considers the particular case of a rotation matrix.
void init(void)
vpRotationMatrix buildFrom(const vpThetaUVector &v)
Transform a vector vpThetaUVector into an rotation matrix.
vpImagePoint getCog() const
Definition: vpDot.h:223
static void display(const vpImage< unsigned char > &I)
Definition: vpDisplay.cpp:206
The vpDisplayOpenCV allows to display image using the opencv library.
Class used for pose computation from N points (pose from point only).
Definition: vpPose.h:78
Generic class defining intrinsic camera parameters.
void set_y(const double y)
Set the point y coordinate in the image plane.
Definition: vpPoint.h:196
The vpDisplayGTK allows to display image using the GTK+ library version 1.2.
Definition: vpDisplayGTK.h:145
void extract(vpRotationMatrix &R) const
Perspective projection with distortion model.
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
Construction from translation vector and rotation matrix.
static double deg(double rad)
Definition: vpMath.h:93
Class that provides a data structure for the column vectors as well as a set of operations on these v...
Definition: vpColVector.h:72
void setGraphics(const bool activate)
Definition: vpDot.h:350
This tracker is meant to track a dot (connected pixels with same gray level) on a vpImage...
Definition: vpDot.h:114
Class that consider the case of the Euler angle using the x-y-z convention, where are respectively ...
Definition: vpRxyzVector.h:152
Class for firewire ieee1394 video devices using libdc1394-2.x api.
void computePose(vpPoseMethodType methode, vpHomogeneousMatrix &cMo)
compute the pose for a given method
Definition: vpPose.cpp:386
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:92
void addPoint(const vpPoint &P)
Add a new point in this array.
Definition: vpPose.cpp:155
void buildFrom(const double phi, const double theta, const double psi)
Definition: vpRxyzVector.h:184
void initTracking(const vpImage< unsigned char > &I)
Definition: vpDot.cpp:658
Class that consider the case of a translation vector.
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...
Definition: vpPoint.cpp:74