ViSP  2.9.0
testRobotViper850Pose.cpp
1 /****************************************************************************
2  *
3  * $Id: testRobotViper850Pose.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 
55 #include <visp/vpConfig.h>
56 #include <visp/vpImage.h>
57 #include <visp/vpDisplayX.h>
58 #include <visp/vpDisplayOpenCV.h>
59 #include <visp/vpDisplayGTK.h>
60 #include <visp/vpRobotViper850.h>
61 #include <visp/vpCameraParameters.h>
62 #include <visp/vpPixelMeterConversion.h>
63 #include <visp/vp1394TwoGrabber.h>
64 #include <visp/vpPoint.h>
65 #include <visp/vpDot.h>
66 #include <visp/vpPose.h>
67 #include <visp/vpDebug.h>
68 #include <iostream>
69 #if defined(VISP_HAVE_VIPER850) && defined(VISP_HAVE_DC1394_2)
70 
71 int main()
72 {
73  try {
74  // Create an image B&W container
76 
77  // Create a firewire grabber based on libdc1394-2.x
78  bool reset = false;
79  vp1394TwoGrabber g(reset);
80 
81  // Grab an image from the firewire camera
82  g.acquire(I);
83 
84  // Create an image viewer for the image
85 #ifdef VISP_HAVE_X11
86  vpDisplayX display(I,100,100,"Current image") ;
87 #elif defined(VISP_HAVE_OPENCV)
88  vpDisplayOpenCV display(I,100,100,"Current image") ;
89 #elif defined(VISP_HAVE_GTK)
90  vpDisplayGTK display(I,100,100,"Current image") ;
91 #endif
92 
93  // Display the image
95  vpDisplay::flush(I) ;
96 
97  // Define a squared target
98  // The target is made of 4 planar points (square dim = 0.077m)
99  double sdim = 0.077; // square width and height
100  vpPoint target[4] ;
101  // Set the point world coordinates (x,y,z) in the object frame
102  // o ----> x
103  // |
104  // |
105  // \/
106  // y
107  target[0].setWorldCoordinates(-sdim/2., -sdim/2., 0) ;
108  target[1].setWorldCoordinates( sdim/2., -sdim/2., 0) ;
109  target[2].setWorldCoordinates( sdim/2., sdim/2., 0) ;
110  target[3].setWorldCoordinates(-sdim/2., sdim/2., 0) ;
111 
112  // Image processing to extract the 2D coordinates in sub-pixels of the 4
113  // points from the image acquired by the camera
114  // Creation of 4 trackers
115  vpDot dot[4];
116  vpImagePoint cog;
117  for (int i=0; i < 4; i ++) {
118  dot[i].setGraphics(true); // to display the tracking results
119  std::cout << "Click on dot " << i << std::endl;
120  dot[i].initTracking( I );
121  // The tracker computes the sub-pixels coordinates in the image
122  // i ----> u
123  // |
124  // |
125  // \/
126  // v
127  std::cout << " Coordinates: " << dot[i].getCog() << std::endl;
128  // Flush the tracking results in the viewer
129  vpDisplay::flush(I) ;
130  }
131 
132  // Create an intrinsic camera parameters structure
133  vpCameraParameters cam;
134 
135  // Create a robot access
136  vpRobotViper850 robot;
137 
138  // Load the end-effector to camera frame transformation obtained
139  // using a camera intrinsic model with distortion
142 
143  // Get the intrinsic camera parameters associated to the image
144  robot.getCameraParameters(cam, I);
145 
146  // Using the camera parameters, compute the perspective projection (transform
147  // the dot sub-pixel coordinates into coordinates in the camera frame in
148  // meter)
149  for (int i=0; i < 4; i ++) {
150  double x=0, y=0 ; // coordinates of the dots in the camera frame
151  // c ----> x
152  // |
153  // |
154  // \/
155  // y
156  //pixel to meter conversion
157  cog = dot[i].getCog();
158  vpPixelMeterConversion::convertPoint(cam, cog, x, y);
159  target[i].set_x(x) ;
160  target[i].set_y(y) ;
161  }
162 
163  // From now, in target[i], we have the 3D coordinates of a point in the
164  // object frame, and their correspondances in the camera frame. We can now
165  // compute the pose cMo between the camera and the object.
166  vpPose pose;
167  // Add the 4 points to compute the pose
168  for (int i=0; i < 4; i ++) {
169  pose.addPoint(target[i]) ;
170  }
171  // Create an homogeneous matrix for the camera to object transformation
172  // computed just bellow
175  vpRxyzVector r;
176  // Compute the pose: initialisation is done by Lagrange method, and the final
177  // pose is computed by the more accurate Virtual Visual Servoing method.
179 
180 
181  std::cout << "Pose cMo: " << std::endl << cMo;
182  cMo.extract(R);
183  r.buildFrom(R);
184  std::cout << " rotation: "
185  << vpMath::deg(r[0]) << " "
186  << vpMath::deg(r[1]) << " "
187  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
188 
189  // Get the robot position in the reference frame
191  vpColVector p; // position x,y,z,rx,ry,rz
193  std::cout << "Robot pose in reference frame: " << p << std::endl;
195  t[0] = p[0]; t[1] = p[1]; t[2] = p[2];
196  r[0] = p[3]; r[1] = p[4]; r[2] = p[5];
197  R.buildFrom(r);
198  rMc.buildFrom(t, R);
199  std::cout << "Pose rMc: " << std::endl << rMc;
200  rMc.extract(R);
201  r.buildFrom(R);
202  std::cout << " rotation: "
203  << vpMath::deg(r[0]) << " "
204  << vpMath::deg(r[1]) << " "
205  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
206 
208  std::cout << "Robot pose in articular: " << p << std::endl;
209 
210  robot.get_fMc(p, rMc);
211  std::cout << "Pose rMc from MGD: " << std::endl << rMc;
212  rMc.extract(R);
213  r.buildFrom(R);
214  std::cout << " rotation: "
215  << vpMath::deg(r[0]) << " "
216  << vpMath::deg(r[1]) << " "
217  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
218 
220  rMo = rMc * cMo;
221  std::cout << "Pose rMo = rMc * cMo: " << std::endl << rMo;
222  rMo.extract(R);
223  r.buildFrom(R);
224  std::cout << " rotation: "
225  << vpMath::deg(r[0]) << " "
226  << vpMath::deg(r[1]) << " "
227  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
228 
229  }
230  catch(vpException e) {
231  std::cout << "Catch an exception: " << e << std::endl;
232  }
233  return 0;
234 }
235 #else
236 int main()
237 {
238  std::cout << "Sorry, test not valid. You should have an Viper850 robot..."
239  << std::endl;
240  return 0;
241 }
242 
243 #endif
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper850.h:99
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
Definition: vpViper850.cpp:580
Control of Irisa's Viper S850 robot named Viper850.
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...
static void flush(const vpImage< unsigned char > &I)
Definition: vpDisplay.cpp:1994
Class that defines what is a point.
Definition: vpPoint.h:65
The vpRotationMatrix considers the particular case of a rotation matrix.
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
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:615
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