Visual Servoing Platform  version 3.0.1
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
testRobotViper850Pose.cpp
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2017 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 
51 #include <visp3/core/vpConfig.h>
52 #include <visp3/core/vpImage.h>
53 #include <visp3/gui/vpDisplayX.h>
54 #include <visp3/gui/vpDisplayOpenCV.h>
55 #include <visp3/gui/vpDisplayGTK.h>
56 #include <visp3/robot/vpRobotViper850.h>
57 #include <visp3/core/vpCameraParameters.h>
58 #include <visp3/core/vpPixelMeterConversion.h>
59 #include <visp3/sensor/vp1394TwoGrabber.h>
60 #include <visp3/core/vpPoint.h>
61 #include <visp3/blob/vpDot.h>
62 #include <visp3/vision/vpPose.h>
63 #include <visp3/core/vpDebug.h>
64 #include <iostream>
65 #if defined(VISP_HAVE_VIPER850) && defined(VISP_HAVE_DC1394)
66 
67 int main()
68 {
69  try {
70  // Create an image B&W container
72 
73  // Create a firewire grabber based on libdc1394-2.x
74  bool reset = false;
75  vp1394TwoGrabber g(reset);
76 
77  // Grab an image from the firewire camera
78  g.acquire(I);
79 
80  // Create an image viewer for the image
81 #ifdef VISP_HAVE_X11
82  vpDisplayX display(I,100,100,"Current image") ;
83 #elif defined(VISP_HAVE_OPENCV)
84  vpDisplayOpenCV display(I,100,100,"Current image") ;
85 #elif defined(VISP_HAVE_GTK)
86  vpDisplayGTK display(I,100,100,"Current image") ;
87 #endif
88 
89  // Display the image
91  vpDisplay::flush(I) ;
92 
93  // Define a squared target
94  // The target is made of 4 planar points (square dim = 0.077m)
95  double sdim = 0.077; // square width and height
96  vpPoint target[4] ;
97  // Set the point world coordinates (x,y,z) in the object frame
98  // o ----> x
99  // |
100  // |
101  // \/
102  // y
103  target[0].setWorldCoordinates(-sdim/2., -sdim/2., 0) ;
104  target[1].setWorldCoordinates( sdim/2., -sdim/2., 0) ;
105  target[2].setWorldCoordinates( sdim/2., sdim/2., 0) ;
106  target[3].setWorldCoordinates(-sdim/2., sdim/2., 0) ;
107 
108  // Image processing to extract the 2D coordinates in sub-pixels of the 4
109  // points from the image acquired by the camera
110  // Creation of 4 trackers
111  vpDot dot[4];
112  vpImagePoint cog;
113  for (int i=0; i < 4; i ++) {
114  dot[i].setGraphics(true); // to display the tracking results
115  std::cout << "Click on dot " << i << std::endl;
116  dot[i].initTracking( I );
117  // The tracker computes the sub-pixels coordinates in the image
118  // i ----> u
119  // |
120  // |
121  // \/
122  // v
123  std::cout << " Coordinates: " << dot[i].getCog() << std::endl;
124  // Flush the tracking results in the viewer
125  vpDisplay::flush(I) ;
126  }
127 
128  // Create an intrinsic camera parameters structure
129  vpCameraParameters cam;
130 
131  // Create a robot access
132  vpRobotViper850 robot;
133 
134  // Load the end-effector to camera frame transformation obtained
135  // using a camera intrinsic model with distortion
138 
139  // Get the intrinsic camera parameters associated to the image
140  robot.getCameraParameters(cam, I);
141 
142  // Using the camera parameters, compute the perspective projection (transform
143  // the dot sub-pixel coordinates into coordinates in the camera frame in
144  // meter)
145  for (int i=0; i < 4; i ++) {
146  double x=0, y=0 ; // coordinates of the dots in the camera frame
147  // c ----> x
148  // |
149  // |
150  // \/
151  // y
152  //pixel to meter conversion
153  cog = dot[i].getCog();
154  vpPixelMeterConversion::convertPoint(cam, cog, x, y);
155  target[i].set_x(x) ;
156  target[i].set_y(y) ;
157  }
158 
159  // From now, in target[i], we have the 3D coordinates of a point in the
160  // object frame, and their correspondances in the camera frame. We can now
161  // compute the pose cMo between the camera and the object.
162  vpPose pose;
163  // Add the 4 points to compute the pose
164  for (int i=0; i < 4; i ++) {
165  pose.addPoint(target[i]) ;
166  }
167  // Create an homogeneous matrix for the camera to object transformation
168  // computed just bellow
171  vpRxyzVector r;
172  // Compute the pose: initialisation is done by Lagrange method, and the final
173  // pose is computed by the more accurate Virtual Visual Servoing method.
175 
176 
177  std::cout << "Pose cMo: " << std::endl << cMo;
178  cMo.extract(R);
179  r.buildFrom(R);
180  std::cout << " rotation: "
181  << vpMath::deg(r[0]) << " "
182  << vpMath::deg(r[1]) << " "
183  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
184 
185  // Get the robot position in the reference frame
187  vpColVector p; // position x,y,z,rx,ry,rz
189  std::cout << "Robot pose in reference frame: " << p << std::endl;
191  t[0] = p[0]; t[1] = p[1]; t[2] = p[2];
192  r[0] = p[3]; r[1] = p[4]; r[2] = p[5];
193  R.buildFrom(r);
194  rMc.buildFrom(t, R);
195  std::cout << "Pose rMc: " << std::endl << rMc;
196  rMc.extract(R);
197  r.buildFrom(R);
198  std::cout << " rotation: "
199  << vpMath::deg(r[0]) << " "
200  << vpMath::deg(r[1]) << " "
201  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
202 
204  std::cout << "Robot pose in articular: " << p << std::endl;
205 
206  robot.get_fMc(p, rMc);
207  std::cout << "Pose rMc from MGD: " << std::endl << rMc;
208  rMc.extract(R);
209  r.buildFrom(R);
210  std::cout << " rotation: "
211  << vpMath::deg(r[0]) << " "
212  << vpMath::deg(r[1]) << " "
213  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
214 
216  rMo = rMc * cMo;
217  std::cout << "Pose rMo = rMc * cMo: " << std::endl << rMo;
218  rMo.extract(R);
219  r.buildFrom(R);
220  std::cout << " rotation: "
221  << vpMath::deg(r[0]) << " "
222  << vpMath::deg(r[1]) << " "
223  << vpMath::deg(r[2]) << " deg" << std::endl << std::endl;
224 
225  }
226  catch(vpException &e) {
227  std::cout << "Catch an exception: " << e << std::endl;
228  }
229  return 0;
230 }
231 #else
232 int main()
233 {
234  std::cout << "Sorry, test not valid. You should have an Viper850 robot..."
235  << std::endl;
236  return 0;
237 }
238 
239 #endif
void getPosition(const vpRobot::vpControlFrameType frame, vpColVector &position)
vpRxyzVector buildFrom(const vpRotationMatrix &R)
static const vpToolType defaultTool
Default tool attached to the robot end effector.
Definition: vpViper850.h:137
Implementation of an homogeneous matrix and operations on such kind of matrices.
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
Definition: vpViper850.cpp:564
Control of Irisa's Viper S850 robot named Viper850.
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:153
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...
static void flush(const vpImage< unsigned char > &I)
Class that defines what is a point.
Definition: vpPoint.h:59
Implementation of a rotation matrix and operations on such kind of matrices.
vpImagePoint getCog() const
Definition: vpDot.h:225
vpRotationMatrix buildFrom(const vpHomogeneousMatrix &M)
static void display(const vpImage< unsigned char > &I)
The vpDisplayOpenCV allows to display image using the OpenCV library. Thus to enable this class OpenC...
Class used for pose computation from N points (pose from point only). Some of the algorithms implemen...
Definition: vpPose.h:76
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 3rd party library. Thus to enable this class G...
Definition: vpDisplayGTK.h:138
bool computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, bool(*func)(vpHomogeneousMatrix *)=NULL)
Definition: vpPose.cpp:372
void extract(vpRotationMatrix &R) const
vpHomogeneousMatrix get_fMc(const vpColVector &q) const
Definition: vpViper.cpp:616
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:359
This tracker is meant to track a dot (connected pixels with same gray level) on a vpImage...
Definition: vpDot.h:116
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)
Definition: vpPose.cpp:145
void initTracking(const vpImage< unsigned char > &I)
Definition: vpDot.cpp:654
Class that consider the case of a translation vector.