Visual Servoing Platform  version 3.4.0
servoSimuPoint2DhalfCamVelocity3.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2019 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See http://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Simulation of a 2 1/2 D visual servoing using theta U visual features.
33  *
34  * Authors:
35  * Eric Marchand
36  * Fabien Spindler
37  *
38  *****************************************************************************/
39 
49 #include <stdio.h>
50 #include <stdlib.h>
51 
52 #include <visp3/core/vpHomogeneousMatrix.h>
53 #include <visp3/core/vpMath.h>
54 #include <visp3/core/vpPoint.h>
55 #include <visp3/io/vpParseArgv.h>
56 #include <visp3/robot/vpSimulatorCamera.h>
57 #include <visp3/visual_features/vpFeatureBuilder.h>
58 #include <visp3/visual_features/vpFeaturePoint.h>
59 #include <visp3/visual_features/vpFeatureThetaU.h>
60 #include <visp3/visual_features/vpGenericFeature.h>
61 #include <visp3/vs/vpServo.h>
62 
63 // List of allowed command line options
64 #define GETOPTARGS "h"
65 
66 void usage(const char *name, const char *badparam);
67 bool getOptions(int argc, const char **argv);
68 
77 void usage(const char *name, const char *badparam)
78 {
79  fprintf(stdout, "\n\
80 Simulation of a 2 1/2 D visual servoing (x,y,logZ, theta U):\n\
81 - eye-in-hand control law,\n\
82 - velocity computed in the camera frame,\n\
83 - without display.\n\
84  \n\
85 SYNOPSIS\n\
86  %s [-h]\n", name);
87 
88  fprintf(stdout, "\n\
89 OPTIONS: Default\n\
90  \n\
91  -h\n\
92  Print the help.\n");
93 
94  if (badparam)
95  fprintf(stdout, "\nERROR: Bad parameter [%s]\n", badparam);
96 }
97 
107 bool getOptions(int argc, const char **argv)
108 {
109  const char *optarg_;
110  int c;
111  while ((c = vpParseArgv::parse(argc, argv, GETOPTARGS, &optarg_)) > 1) {
112 
113  switch (c) {
114  case 'h':
115  usage(argv[0], NULL);
116  return false;
117 
118  default:
119  usage(argv[0], optarg_);
120  return false;
121  }
122  }
123 
124  if ((c == 1) || (c == -1)) {
125  // standalone param or error
126  usage(argv[0], NULL);
127  std::cerr << "ERROR: " << std::endl;
128  std::cerr << " Bad argument " << optarg_ << std::endl << std::endl;
129  return false;
130  }
131 
132  return true;
133 }
134 
135 int main(int argc, const char **argv)
136 {
137 #if (defined(VISP_HAVE_LAPACK) || defined(VISP_HAVE_EIGEN3) || defined(VISP_HAVE_OPENCV))
138  try {
139  // Read the command line options
140  if (getOptions(argc, argv) == false) {
141  exit(-1);
142  }
143 
144  std::cout << std::endl;
145  std::cout << "-------------------------------------------------------" << std::endl;
146  std::cout << " simulation of a 2 1/2 D visual servoing " << std::endl;
147  std::cout << "-------------------------------------------------------" << std::endl;
148  std::cout << std::endl;
149 
150  // In this example we will simulate a visual servoing task.
151  // In simulation, we have to define the scene frane Ro and the
152  // camera frame Rc.
153  // The camera location is given by an homogenous matrix cMo that
154  // describes the position of the scene or object frame in the camera frame.
155 
156  vpServo task;
157 
158  // sets the initial camera location
159  // we give the camera location as a size 6 vector (3 translations in meter
160  // and 3 rotation (theta U representation)
161  vpPoseVector c_r_o(0.1, 0.2, 2, vpMath::rad(20), vpMath::rad(10), vpMath::rad(50));
162 
163  // this pose vector is then transformed in a 4x4 homogeneous matrix
164  vpHomogeneousMatrix cMo(c_r_o);
165 
166  // We define a robot
167  // The vpSimulatorCamera implements a simple moving that is juste defined
168  // by its location cMo
169  vpSimulatorCamera robot;
170 
171  // Compute the position of the object in the world frame
172  vpHomogeneousMatrix wMc, wMo;
173  robot.getPosition(wMc);
174  wMo = wMc * cMo;
175 
176  // Now that the current camera position has been defined,
177  // let us defined the defined camera location.
178  // It is defined by cdMo
179  // sets the desired camera location " ) ;
180  vpPoseVector cd_r_o(0, 0, 1, vpMath::rad(0), vpMath::rad(0), vpMath::rad(0));
181  vpHomogeneousMatrix cdMo(cd_r_o);
182 
183  //----------------------------------------------------------------------
184  // A 2 1/2 D visual servoing can be defined by
185  // - the position of a point x,y
186  // - the difference between this point depth and a desire depth
187  // modeled by log Z/Zd to be regulated to 0
188  // - the rotation that the camera has to realized cdMc
189 
190  // Let us now defined the current value of these features
191 
192  // since we simulate we have to define a 3D point that will
193  // forward-projected to define the current position x,y of the
194  // reference point
195 
196  //------------------------------------------------------------------
197  // First feature (x,y)
198  //------------------------------------------------------------------
199  // Let oP be this ... point,
200  // a vpPoint class has three main member
201  // .oP : 3D coordinates in scene frame
202  // .cP : 3D coordinates in camera frame
203  // .p : 2D
204 
205  //------------------------------------------------------------------
206  // sets the point coordinates in the world frame
207  vpPoint P(0, 0, 0);
208  // computes the P coordinates in the camera frame and its
209  // 2D coordinates cP and then p
210  // computes the point coordinates in the camera frame and its 2D
211  // coordinates
212  P.track(cMo);
213 
214  // We also defined (again by forward projection) the desired position
215  // of this point according to the desired camera position
216  vpPoint Pd(0, 0, 0);
217  Pd.track(cdMo);
218 
219  // Nevertheless, a vpPoint is not a feature, this is just a "tracker"
220  // from which the feature are built
221  // a feature is juste defined by a vector s, a way to compute the
222  // interaction matrix and the error, and if required a (or a vector of)
223  // 3D information
224 
225  // for a point (x,y) Visp implements the vpFeaturePoint class.
226  // we no defined a feature for x,y (and for (x*,y*))
227  vpFeaturePoint p, pd;
228 
229  // and we initialized the vector s=(x,y) of p from the tracker P
230  // Z coordinates in p is also initialized, it will be used to compute
231  // the interaction matrix
233  vpFeatureBuilder::create(pd, Pd);
234 
235  // This visual has to be regulated to zero
236 
237  //------------------------------------------------------------------
238  // 2nd feature ThetaUz and 3rd feature t
239  // The thetaU feature is defined, tu represents the rotation that the
240  // camera has to realized. t the translation. the complete displacement is
241  // then defined by:
242  //------------------------------------------------------------------
243  vpHomogeneousMatrix cdMc;
244  // compute the rotation that the camera has to achieve
245  cdMc = cdMo * cMo.inverse();
246 
247  // from this displacement, we extract the rotation cdRc represented by
248  // the angle theta and the rotation axis u
250  tuz.buildFrom(cdMc);
251  // And the translations
253  t.buildFrom(cdMc);
254 
255  // This visual has to be regulated to zero
256 
257  // sets the desired rotation (always zero !)
258  // since s is the rotation that the camera has to achieve
259 
260  //------------------------------------------------------------------
261  // Let us now the task itself
262  //------------------------------------------------------------------
263 
264  // define the task
265  // - we want an eye-in-hand control law
266  // - robot is controlled in the camera frame
267  // we choose to control the robot in the camera frame
269  // Interaction matrix is computed with the current value of s
271 
272  // we build the task by "stacking" the visual feature
273  // previously defined
274  task.addFeature(t);
275  task.addFeature(p, pd);
276  task.addFeature(tuz, vpFeatureThetaU::TUz); // selection of TUz
277 
278  // addFeature(X,Xd) means X should be regulated to Xd
279  // addFeature(X) means that X should be regulated to 0
280  // some features such as vpFeatureThetaU MUST be regulated to zero
281  // (otherwise, it will results in an error at exectution level)
282 
283  // set the gain
284  task.setLambda(1);
285 
286  // Display task information " ) ;
287  task.print();
288  //------------------------------------------------------------------
289  // An now the closed loop
290 
291  unsigned int iter = 0;
292  // loop
293  while (iter++ < 200) {
294  std::cout << "---------------------------------------------" << iter << std::endl;
295  vpColVector v;
296 
297  // get the robot position
298  robot.getPosition(wMc);
299  // Compute the position of the object frame in the camera frame
300  cMo = wMc.inverse() * wMo;
301 
302  // update the feature
303  P.track(cMo);
305 
306  cdMc = cdMo * cMo.inverse();
307  tuz.buildFrom(cdMc);
308  t.buildFrom(cdMc);
309 
310  // compute the control law: v = -lambda L^+(s-sd)
311  v = task.computeControlLaw();
312 
313  // send the camera velocity to the controller
315 
316  std::cout << "|| s - s* || = " << (task.getError()).sumSquare() << std::endl;
317  }
318 
319  // Display task information
320  task.print();
321  // Final camera location
322  std::cout << "Final camera location: \n" << cMo << std::endl;
323  return EXIT_SUCCESS;
324  } catch (const vpException &e) {
325  std::cout << "Catch a ViSP exception: " << e << std::endl;
326  return EXIT_SUCCESS;
327  }
328 #else
329  (void)argc;
330  (void)argv;
331  std::cout << "Cannot run this example: install Lapack, Eigen3 or OpenCV" << std::endl;
332  return EXIT_SUCCESS;
333 #endif
334 }
Class that defines the translation visual feature .
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
Implementation of an homogeneous matrix and operations on such kind of matrices.
Class that defines the simplest robot: a free flying camera.
void addFeature(vpBasicFeature &s, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition: vpServo.cpp:490
error that can be emited by ViSP classes.
Definition: vpException.h:71
Class that defines a 2D point visual feature which is composed by two parameters that are the cartes...
static bool parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, int flags)
Definition: vpParseArgv.cpp:69
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:81
vpColVector getError() const
Definition: vpServo.h:278
vpColVector computeControlLaw()
Definition: vpServo.cpp:929
void setLambda(double c)
Definition: vpServo.h:404
vpHomogeneousMatrix getPosition() const
void buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Definition: vpServo.cpp:567
static double rad(double deg)
Definition: vpMath.h:110
Implementation of column vector and the associated operations.
Definition: vpColVector.h:130
Implementation of a pose vector and operations on poses.
Definition: vpPoseVector.h:151
vpHomogeneousMatrix inverse() const
Class that defines a 3D visual feature from a axis/angle parametrization that represent the rotatio...
void print(const vpServo::vpServoPrintType display_level=ALL, std::ostream &os=std::cout)
Definition: vpServo.cpp:306
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpDot &d)
void setServo(const vpServoType &servo_type)
Definition: vpServo.cpp:218