ViSP  3.0.0
testRobotAfma6Pose.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2015 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
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 http://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  * Test for Afma 6 dof robot.
32  *
33  * Authors:
34  * Fabien Spindler
35  *
36  *****************************************************************************/
37 
50 #include <visp3/core/vpImage.h>
51 #include <visp3/gui/vpDisplayX.h>
52 #include <visp3/gui/vpDisplayOpenCV.h>
53 #include <visp3/gui/vpDisplayGTK.h>
54 #include <visp3/robot/vpRobotAfma6.h>
55 #include <visp3/core/vpCameraParameters.h>
56 #include <visp3/core/vpPixelMeterConversion.h>
57 #include <visp3/sensor/vp1394TwoGrabber.h>
58 #include <visp3/core/vpPoint.h>
59 #include <visp3/blob/vpDot.h>
60 #include <visp3/vision/vpPose.h>
61 #include <visp3/core/vpDebug.h>
62 #include <iostream>
63 #if defined(VISP_HAVE_AFMA6) && defined(VISP_HAVE_DC1394)
64 
65 int main()
66 {
67  try {
68  // Create an image B&W container
70 
71  // Create a firewire grabber based on libdc1394-2.x
73 
74  // Grab an image from the firewire camera
75  g.acquire(I);
76 
77  // Create an image viewer for the image
78 #ifdef VISP_HAVE_X11
79  vpDisplayX display(I,100,100,"Current image") ;
80 #elif defined(VISP_HAVE_OPENCV)
81  vpDisplayOpenCV display(I,100,100,"Current image") ;
82 #elif defined(VISP_HAVE_GTK)
83  vpDisplayGTK display(I,100,100,"Current image") ;
84 #endif
85 
86  // Display the image
88  vpDisplay::flush(I) ;
89 
90  // Define a squared target
91  // The target is made of 4 planar points (square dim = 0.077m)
92  double sdim = 0.077; // square width and height
93  vpPoint target[4] ;
94  // Set the point world coordinates (x,y,z) in the object frame
95  // o ----> x
96  // |
97  // |
98  // \/
99  // y
100  target[0].setWorldCoordinates(-sdim/2., -sdim/2., 0) ;
101  target[1].setWorldCoordinates( sdim/2., -sdim/2., 0) ;
102  target[2].setWorldCoordinates( sdim/2., sdim/2., 0) ;
103  target[3].setWorldCoordinates(-sdim/2., sdim/2., 0) ;
104 
105  // Image processing to extract the 2D coordinates in sub-pixels of the 4
106  // points from the image acquired by the camera
107  // Creation of 4 trackers
108  vpDot dot[4];
109  vpImagePoint cog;
110  for (int i=0; i < 4; i ++) {
111  dot[i].setGraphics(true); // to display the tracking results
112  std::cout << "Click on dot " << i << std::endl;
113  dot[i].initTracking( I );
114  // The tracker computes the sub-pixels coordinates in the image
115  // i ----> u
116  // |
117  // |
118  // \/
119  // v
120  std::cout << " Coordinates: " << dot[i].getCog() << std::endl;
121  // Flush the tracking results in the viewer
122  vpDisplay::flush(I) ;
123  }
124 
125  // Create an intrinsic camera parameters structure
126  vpCameraParameters cam;
127 
128  // Create a robot access
129  vpRobotAfma6 robot;
130 
131  // Load the end-effector to camera frame transformation obtained
132  // using a camera intrinsic model with distortion
135 
136  // Get the intrinsic camera parameters associated to the image
137  robot.getCameraParameters(cam, I);
138 
139  // Using the camera parameters, compute the perspective projection (transform
140  // the dot sub-pixel coordinates into coordinates in the camera frame in
141  // meter)
142  for (int i=0; i < 4; i ++) {
143  double x=0, y=0 ; // coordinates of the dots in the camera frame
144  // c ----> x
145  // |
146  // |
147  // \/
148  // y
149  //pixel to meter conversion
150  cog = dot[i].getCog();
151  vpPixelMeterConversion::convertPoint(cam, cog, x, y);
152  target[i].set_x(x) ;
153  target[i].set_y(y) ;
154  }
155 
156  // From now, in target[i], we have the 3D coordinates of a point in the
157  // object frame, and their correspondances in the camera frame. We can now
158  // compute the pose cMo between the camera and the object.
159  vpPose pose;
160  // Add the 4 points to compute the pose
161  for (int i=0; i < 4; i ++) {
162  pose.addPoint(target[i]) ;
163  }
164  // Create an homogeneous matrix for the camera to object transformation
165  // computed just bellow
168  vpRxyzVector r;
169  // Compute the pose: initialisation is done by Lagrange method, and the final
170  // pose is computed by the more accurate Virtual Visual Servoing method.
172 
173 
174  std::cout << "Pose cMo: " << std::endl << cMo;
175  cMo.extract(R);
176  r.buildFrom(R);
177  std::cout << " rotation: "
178  << vpMath::deg(r[0]) << " "
179  << vpMath::deg(r[1]) << " "
180  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
181 
182  // Get the robot position in the reference frame
184  vpColVector p; // position x,y,z,rx,ry,rz
186  std::cout << "Robot pose in reference frame: " << p << std::endl;
188  t[0] = p[0]; t[1] = p[1]; t[2] = p[2];
189  r[0] = p[3]; r[1] = p[4]; r[2] = p[5];
190  R.buildFrom(r);
191  rMc.buildFrom(t, R);
192  std::cout << "Pose rMc: " << std::endl << rMc;
193  rMc.extract(R);
194  r.buildFrom(R);
195  std::cout << " rotation: "
196  << vpMath::deg(r[0]) << " "
197  << vpMath::deg(r[1]) << " "
198  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
199 
201  std::cout << "Robot pose in articular: " << p << std::endl;
202 
203  robot.get_fMc(p, rMc);
204  std::cout << "Pose rMc from MGD: " << std::endl << rMc;
205  rMc.extract(R);
206  r.buildFrom(R);
207  std::cout << " rotation: "
208  << vpMath::deg(r[0]) << " "
209  << vpMath::deg(r[1]) << " "
210  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
211 
213  rMo = rMc * cMo;
214  std::cout << "Pose rMo = rMc * cMo: " << std::endl << rMo;
215  rMo.extract(R);
216  r.buildFrom(R);
217  std::cout << " rotation: "
218  << vpMath::deg(r[0]) << " "
219  << vpMath::deg(r[1]) << " "
220  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
221 
222  }
223  catch(vpException e) {
224  std::cout << "Catch an exception: " << e << std::endl;
225  }
226  return 0;
227 }
228 #else
229 int main()
230 {
231  std::cout << "Sorry, test not valid. You should have an Afma6 robot..."
232  << std::endl;
233  return 0;
234 }
235 
236 #endif
vpRxyzVector buildFrom(const vpRotationMatrix &R)
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
Definition: vpAfma6.cpp:1244
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpAfma6.cpp:741
Define the X11 console to display images.
Definition: vpDisplayX.h:148
error that can be emited by ViSP classes.
Definition: vpException.h:73
void set_x(const double x)
Set the point x coordinate in the image plane.
Definition: vpPoint.cpp:496
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:2233
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
Control of Irisa's gantry robot named Afma6.
Definition: vpRobotAfma6.h:210
Class that defines what is a point.
Definition: vpPoint.h:59
Implementation of a rotation matrix and operations on such kind of matrices.
void init(void)
vpImagePoint getCog() const
Definition: vpDot.h:224
vpRotationMatrix buildFrom(const vpHomogeneousMatrix &M)
bool computePose(vpPoseMethodType methode, vpHomogeneousMatrix &cMo, bool(*func)(vpHomogeneousMatrix *)=NULL)
compute the pose for a given method
Definition: vpPose.cpp:382
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:74
Generic class defining intrinsic camera parameters.
void set_y(const double y)
Set the point y coordinate in the image plane.
Definition: vpPoint.cpp:498
The vpDisplayGTK allows to display image using the GTK+ library version 1.2.
Definition: vpDisplayGTK.h:141
void extract(vpRotationMatrix &R) const
Perspective projection with distortion model.
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
static double deg(double rad)
Definition: vpMath.h:97
void setWorldCoordinates(const double oX, const double oY, const double oZ)
Definition: vpPoint.cpp:111
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
void setGraphics(const bool activate)
Definition: vpDot.h:351
This tracker is meant to track a dot (connected pixels with same gray level) on a vpImage...
Definition: vpDot.h:115
Implementation of a rotation vector as Euler angle minimal representation.
Definition: vpRxyzVector.h:154
Class for firewire ieee1394 video devices using libdc1394-2.x api.
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:88
void addPoint(const vpPoint &P)
Add a new point in this array.
Definition: vpPose.cpp:151
void initTracking(const vpImage< unsigned char > &I)
Definition: vpDot.cpp:654
Class that consider the case of a translation vector.