Visual Servoing Platform  version 3.2.0 under development (2019-01-22)
servoAfma6SquareLines2DCamVelocity.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  * tests the control law
33  * eye-in-hand control
34  * velocity computed in the camera frame
35  *
36  * Authors:
37  * Eric Marchand
38  *
39  *****************************************************************************/
59 #include <cmath> // std::fabs
60 #include <limits> // numeric_limits
61 #include <stdlib.h>
62 #include <visp3/core/vpConfig.h>
63 #include <visp3/core/vpDebug.h> // Debug trace
64 #if (defined(VISP_HAVE_AFMA6) && defined(VISP_HAVE_DC1394))
65 
66 #include <visp3/core/vpDisplay.h>
67 #include <visp3/core/vpImage.h>
68 #include <visp3/gui/vpDisplayGTK.h>
69 #include <visp3/gui/vpDisplayOpenCV.h>
70 #include <visp3/gui/vpDisplayX.h>
71 #include <visp3/io/vpImageIo.h>
72 #include <visp3/sensor/vp1394TwoGrabber.h>
73 
74 #include <visp3/core/vpHomogeneousMatrix.h>
75 #include <visp3/core/vpLine.h>
76 #include <visp3/core/vpMath.h>
77 #include <visp3/me/vpMeLine.h>
78 #include <visp3/visual_features/vpFeatureBuilder.h>
79 #include <visp3/visual_features/vpFeatureLine.h>
80 #include <visp3/vs/vpServo.h>
81 
82 #include <visp3/robot/vpRobotAfma6.h>
83 
84 // Exception
85 #include <visp3/core/vpException.h>
86 #include <visp3/vs/vpServoDisplay.h>
87 
88 #include <visp3/blob/vpDot.h>
89 
90 int main()
91 {
92  try {
94 
98  g.open(I);
99 
100  g.acquire(I);
101 
102 #ifdef VISP_HAVE_X11
103  vpDisplayX display(I, 100, 100, "Current image");
104 #elif defined(VISP_HAVE_OPENCV)
105  vpDisplayOpenCV display(I, 100, 100, "Current image");
106 #elif defined(VISP_HAVE_GTK)
107  vpDisplayGTK display(I, 100, 100, "Current image");
108 #endif
109 
111  vpDisplay::flush(I);
112 
113  vpServo task;
114 
115  std::cout << std::endl;
116  std::cout << "-------------------------------------------------------" << std::endl;
117  std::cout << " Test program for vpServo " << std::endl;
118  std::cout << " Eye-in-hand task control, velocity computed in the camera frame" << std::endl;
119  std::cout << " Simulation " << std::endl;
120  std::cout << " task : servo a line " << std::endl;
121  std::cout << "-------------------------------------------------------" << std::endl;
122  std::cout << std::endl;
123 
124  int i;
125  int nbline = 4;
126 
127  vpMeLine line[nbline];
128 
129  vpMe me;
130  me.setRange(10);
131  me.setPointsToTrack(100);
132  me.setThreshold(50000);
133  me.setSampleStep(10);
134 
135  // Initialize the tracking. Define the four lines to track.
136  for (i = 0; i < nbline; i++) {
138  line[i].setMe(&me);
139 
140  line[i].initTracking(I);
141  line[i].track(I);
142  }
143 
144  vpRobotAfma6 robot;
145  // robot.move("zero.pos") ;
146 
147  vpCameraParameters cam;
148  // Update camera parameters
149  robot.getCameraParameters(cam, I);
150 
151  vpTRACE("sets the current position of the visual feature ");
152  vpFeatureLine p[nbline];
153  for (i = 0; i < nbline; i++)
154  vpFeatureBuilder::create(p[i], cam, line[i]);
155 
156  vpTRACE("sets the desired position of the visual feature ");
157  vpLine lined[nbline];
158  lined[0].setWorldCoordinates(1, 0, 0, 0.05, 0, 0, 1, 0);
159  lined[1].setWorldCoordinates(0, 1, 0, 0.05, 0, 0, 1, 0);
160  lined[2].setWorldCoordinates(1, 0, 0, -0.05, 0, 0, 1, 0);
161  lined[3].setWorldCoordinates(0, 1, 0, -0.05, 0, 0, 1, 0);
162 
163  vpHomogeneousMatrix cMo(0, 0, 0.5, 0, 0, vpMath::rad(0));
164 
165  lined[0].project(cMo);
166  lined[1].project(cMo);
167  lined[2].project(cMo);
168  lined[3].project(cMo);
169 
170  // Those lines are needed to keep the conventions define in vpMeLine
171  // (Those in vpLine are less restrictive) Another way to have the
172  // coordinates of the desired features is to learn them before executing
173  // the program.
174  lined[0].setRho(-fabs(lined[0].getRho()));
175  lined[0].setTheta(0);
176  lined[1].setRho(-fabs(lined[1].getRho()));
177  lined[1].setTheta(M_PI / 2);
178  lined[2].setRho(-fabs(lined[2].getRho()));
179  lined[2].setTheta(M_PI);
180  lined[3].setRho(-fabs(lined[3].getRho()));
181  lined[3].setTheta(-M_PI / 2);
182 
183  vpFeatureLine pd[nbline];
184 
185  vpFeatureBuilder::create(pd[0], lined[0]);
186  vpFeatureBuilder::create(pd[1], lined[1]);
187  vpFeatureBuilder::create(pd[2], lined[2]);
188  vpFeatureBuilder::create(pd[3], lined[3]);
189 
190  vpTRACE("define the task");
191  vpTRACE("\t we want an eye-in-hand control law");
192  vpTRACE("\t robot is controlled in the camera frame");
195 
196  vpTRACE("\t we want to see a point on a point..");
197  std::cout << std::endl;
198  for (i = 0; i < nbline; i++)
199  task.addFeature(p[i], pd[i]);
200 
201  vpTRACE("\t set the gain");
202  task.setLambda(0.2);
203 
204  vpTRACE("Display task information ");
205  task.print();
206 
208 
209  unsigned int iter = 0;
210  vpTRACE("\t loop");
211  vpColVector v;
212  vpImage<vpRGBa> Ic;
213  double lambda_av = 0.05;
214  double alpha = 0.05;
215  double beta = 3;
216 
217  for (;;) {
218  std::cout << "---------------------------------------------" << iter << std::endl;
219 
220  try {
221  g.acquire(I);
223 
224  // Track the lines and update the features
225  for (i = 0; i < nbline; i++) {
226  line[i].track(I);
227  line[i].display(I, vpColor::red);
228 
229  vpFeatureBuilder::create(p[i], cam, line[i]);
230 
231  p[i].display(cam, I, vpColor::red);
232  pd[i].display(cam, I, vpColor::green);
233  }
234 
235  double gain;
236  {
237  if (std::fabs(alpha) <= std::numeric_limits<double>::epsilon())
238  gain = lambda_av;
239  else {
240  gain = alpha * exp(-beta * (task.getError()).sumSquare()) + lambda_av;
241  }
242  }
243 
244  task.setLambda(gain);
245 
246  v = task.computeControlLaw();
247 
248  vpDisplay::flush(I);
249 
250  if (iter == 0)
252  if (v.sumSquare() > 0.5) {
253  v = 0;
255  robot.stopMotion();
257  }
258 
260 
261  } catch (...) {
262  v = 0;
264  robot.stopMotion();
265  exit(1);
266  }
267 
268  vpTRACE("\t\t || s - s* || = %f ", (task.getError()).sumSquare());
269  iter++;
270  }
271 
272  vpTRACE("Display task information ");
273  task.print();
274  task.kill();
275  return EXIT_SUCCESS;
276  }
277  catch (const vpException &e) {
278  std::cout << "Test failed with exception: " << e << std::endl;
279  return EXIT_FAILURE;
280  }
281 }
282 
283 #else
284 int main()
285 {
286  std::cout << "You do not have an afma6 robot connected to your computer..." << std::endl;
287  return EXIT_SUCCESS;
288 }
289 
290 #endif
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height) const
Definition: vpAfma6.cpp:1190
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
void setPointsToTrack(const int &n)
Definition: vpMe.h:264
Implementation of an homogeneous matrix and operations on such kind of matrices.
void setWorldCoordinates(const double &A1, const double &B1, const double &C1, const double &D1, const double &A2, const double &B2, const double &C2, const double &D2)
Definition: vpLine.cpp:85
void setSampleStep(const double &s)
Definition: vpMe.h:278
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:151
void addFeature(vpBasicFeature &s, vpBasicFeature &s_star, const unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition: vpServo.cpp:497
error that can be emited by ViSP classes.
Definition: vpException.h:71
void track(const vpImage< unsigned char > &Im)
Definition: vpMeLine.cpp:747
Definition: vpMe.h:60
static const vpColor green
Definition: vpColor.h:183
void acquire(vpImage< unsigned char > &I)
static void flush(const vpImage< unsigned char > &I)
Control of Irisa&#39;s gantry robot named Afma6.
Definition: vpRobotAfma6.h:212
static const vpColor red
Definition: vpColor.h:180
void display(const vpImage< unsigned char > &I, vpColor col)
Definition: vpMeLine.cpp:224
void open(vpImage< unsigned char > &I)
Class that defines a line in the object frame, the camera frame and the image plane. All the parameters must be set in meter.
Definition: vpLine.h:105
void kill()
Definition: vpServo.cpp:192
Initialize the velocity controller.
Definition: vpRobot.h:67
vpColVector getError() const
Definition: vpServo.h:282
vpColVector computeControlLaw()
Definition: vpServo.cpp:935
void display(const vpCameraParameters &cam, const vpImage< unsigned char > &I, const vpColor &color=vpColor::green, unsigned int thickness=1) const
#define vpTRACE
Definition: vpDebug.h:416
void setDisplay(vpMeSite::vpMeSiteDisplayType select)
Definition: vpMeTracker.h:104
static void display(const vpImage< unsigned char > &I)
Class that tracks in an image a line moving edges.
Definition: vpMeLine.h:151
The vpDisplayOpenCV allows to display image using the OpenCV library. Thus to enable this class OpenC...
Generic class defining intrinsic camera parameters.
void setLambda(double c)
Definition: vpServo.h:406
Class that defines a 2D line visual feature which is composed by two parameters that are and ...
The vpDisplayGTK allows to display image using the GTK 3rd party library. Thus to enable this class G...
Definition: vpDisplayGTK.h:138
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
void initTracking(const vpImage< unsigned char > &I)
Definition: vpMeLine.cpp:236
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Definition: vpServo.cpp:574
static double rad(double deg)
Definition: vpMath.h:102
void setRho(const double rho)
Definition: vpLine.h:124
double sumSquare() const
void setTheta(const double theta)
Definition: vpLine.h:134
Implementation of column vector and the associated operations.
Definition: vpColVector.h:72
void setFramerate(vp1394TwoFramerateType fps)
void setVideoMode(vp1394TwoVideoModeType videomode)
void setThreshold(const double &t)
Definition: vpMe.h:300
void print(const vpServo::vpServoPrintType display_level=ALL, std::ostream &os=std::cout)
Definition: vpServo.cpp:313
Class for firewire ieee1394 video devices using libdc1394-2.x api.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpDot &d)
void setRange(const unsigned int &r)
Definition: vpMe.h:271
void setMe(vpMe *p_me)
Definition: vpMeTracker.h:144
void setServo(const vpServoType &servo_type)
Definition: vpServo.cpp:223