Visual Servoing Platform  version 3.4.0
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 int main()
89 {
90  try {
92 
96  g.open(I);
97 
98  g.acquire(I);
99 
100 #ifdef VISP_HAVE_X11
101  vpDisplayX display(I, 100, 100, "Current image");
102 #elif defined(VISP_HAVE_OPENCV)
103  vpDisplayOpenCV display(I, 100, 100, "Current image");
104 #elif defined(VISP_HAVE_GTK)
105  vpDisplayGTK display(I, 100, 100, "Current image");
106 #endif
107 
109  vpDisplay::flush(I);
110 
111  vpServo task;
112 
113  std::cout << std::endl;
114  std::cout << "-------------------------------------------------------" << std::endl;
115  std::cout << " Test program for vpServo " << std::endl;
116  std::cout << " Eye-in-hand task control, velocity computed in the camera frame" << std::endl;
117  std::cout << " Simulation " << std::endl;
118  std::cout << " task : servo a line " << std::endl;
119  std::cout << "-------------------------------------------------------" << std::endl;
120  std::cout << std::endl;
121 
122  int i;
123  int nbline = 4;
124 
125  vpMeLine line[nbline];
126 
127  vpMe me;
128  me.setRange(10);
129  me.setPointsToTrack(100);
130  me.setThreshold(50000);
131  me.setSampleStep(10);
132 
133  // Initialize the tracking. Define the four lines to track.
134  for (i = 0; i < nbline; i++) {
136  line[i].setMe(&me);
137 
138  line[i].initTracking(I);
139  line[i].track(I);
140  }
141 
142  vpRobotAfma6 robot;
143  // robot.move("zero.pos") ;
144 
145  vpCameraParameters cam;
146  // Update camera parameters
147  robot.getCameraParameters(cam, I);
148 
149  vpTRACE("sets the current position of the visual feature ");
150  vpFeatureLine p[nbline];
151  for (i = 0; i < nbline; i++)
152  vpFeatureBuilder::create(p[i], cam, line[i]);
153 
154  vpTRACE("sets the desired position of the visual feature ");
155  vpLine lined[nbline];
156  lined[0].setWorldCoordinates(1, 0, 0, 0.05, 0, 0, 1, 0);
157  lined[1].setWorldCoordinates(0, 1, 0, 0.05, 0, 0, 1, 0);
158  lined[2].setWorldCoordinates(1, 0, 0, -0.05, 0, 0, 1, 0);
159  lined[3].setWorldCoordinates(0, 1, 0, -0.05, 0, 0, 1, 0);
160 
161  vpHomogeneousMatrix cMo(0, 0, 0.5, 0, 0, vpMath::rad(0));
162 
163  lined[0].project(cMo);
164  lined[1].project(cMo);
165  lined[2].project(cMo);
166  lined[3].project(cMo);
167 
168  // Those lines are needed to keep the conventions define in vpMeLine
169  // (Those in vpLine are less restrictive) Another way to have the
170  // coordinates of the desired features is to learn them before executing
171  // the program.
172  lined[0].setRho(-fabs(lined[0].getRho()));
173  lined[0].setTheta(0);
174  lined[1].setRho(-fabs(lined[1].getRho()));
175  lined[1].setTheta(M_PI / 2);
176  lined[2].setRho(-fabs(lined[2].getRho()));
177  lined[2].setTheta(M_PI);
178  lined[3].setRho(-fabs(lined[3].getRho()));
179  lined[3].setTheta(-M_PI / 2);
180 
181  vpFeatureLine pd[nbline];
182 
183  vpFeatureBuilder::create(pd[0], lined[0]);
184  vpFeatureBuilder::create(pd[1], lined[1]);
185  vpFeatureBuilder::create(pd[2], lined[2]);
186  vpFeatureBuilder::create(pd[3], lined[3]);
187 
188  vpTRACE("define the task");
189  vpTRACE("\t we want an eye-in-hand control law");
190  vpTRACE("\t robot is controlled in the camera frame");
193 
194  vpTRACE("\t we want to see a point on a point..");
195  std::cout << std::endl;
196  for (i = 0; i < nbline; i++)
197  task.addFeature(p[i], pd[i]);
198 
199  vpTRACE("\t set the gain");
200  task.setLambda(0.2);
201 
202  vpTRACE("Display task information ");
203  task.print();
204 
206 
207  unsigned int iter = 0;
208  vpTRACE("\t loop");
209  vpColVector v;
210  vpImage<vpRGBa> Ic;
211  double lambda_av = 0.05;
212  double alpha = 0.05;
213  double beta = 3;
214 
215  for (;;) {
216  std::cout << "---------------------------------------------" << iter << std::endl;
217 
218  try {
219  g.acquire(I);
221 
222  // Track the lines and update the features
223  for (i = 0; i < nbline; i++) {
224  line[i].track(I);
225  line[i].display(I, vpColor::red);
226 
227  vpFeatureBuilder::create(p[i], cam, line[i]);
228 
229  p[i].display(cam, I, vpColor::red);
230  pd[i].display(cam, I, vpColor::green);
231  }
232 
233  double gain;
234  {
235  if (std::fabs(alpha) <= std::numeric_limits<double>::epsilon())
236  gain = lambda_av;
237  else {
238  gain = alpha * exp(-beta * (task.getError()).sumSquare()) + lambda_av;
239  }
240  }
241 
242  task.setLambda(gain);
243 
244  v = task.computeControlLaw();
245 
246  vpDisplay::flush(I);
247 
248  if (iter == 0)
250  if (v.sumSquare() > 0.5) {
251  v = 0;
253  robot.stopMotion();
255  }
256 
258 
259  } catch (...) {
260  v = 0;
262  robot.stopMotion();
263  exit(1);
264  }
265 
266  vpTRACE("\t\t || s - s* || = %f ", (task.getError()).sumSquare());
267  iter++;
268  }
269 
270  vpTRACE("Display task information ");
271  task.print();
272  return EXIT_SUCCESS;
273  }
274  catch (const vpException &e) {
275  std::cout << "Test failed with exception: " << e << std::endl;
276  return EXIT_FAILURE;
277  }
278 }
279 
280 #else
281 int main()
282 {
283  std::cout << "You do not have an afma6 robot connected to your computer..." << std::endl;
284  return EXIT_SUCCESS;
285 }
286 
287 #endif
Class for firewire ieee1394 video devices using libdc1394-2.x api.
void acquire(vpImage< unsigned char > &I)
void setVideoMode(vp1394TwoVideoModeType videomode)
void setFramerate(vp1394TwoFramerateType fps)
void open(vpImage< unsigned char > &I)
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:131
double sumSquare() const
static const vpColor red
Definition: vpColor.h:217
static const vpColor green
Definition: vpColor.h:220
The vpDisplayGTK allows to display image using the GTK 3rd party library. Thus to enable this class G...
Definition: vpDisplayGTK.h:135
The vpDisplayOpenCV allows to display image using the OpenCV library. Thus to enable this class OpenC...
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:151
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void flush(const vpImage< unsigned char > &I)
error that can be emited by ViSP classes.
Definition: vpException.h:72
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpDot &d)
Class that defines a 2D line visual feature which is composed by two parameters that are and ,...
void display(const vpCameraParameters &cam, const vpImage< unsigned char > &I, const vpColor &color=vpColor::green, unsigned int thickness=1) const
Implementation of an homogeneous matrix and operations on such kind of matrices.
Class that defines a 3D line in the object frame and allows forward projection of the line in the cam...
Definition: vpLine.h:105
void setRho(double rho)
Definition: vpLine.h:153
void setTheta(double theta)
Definition: vpLine.h:163
void setWorldCoordinates(const double &oA1, const double &oB1, const double &oC1, const double &oD1, const double &oA2, const double &oB2, const double &oC2, const double &oD2)
Definition: vpLine.cpp:85
static double rad(double deg)
Definition: vpMath.h:110
Class that tracks in an image a line moving edges.
Definition: vpMeLine.h:152
void display(const vpImage< unsigned char > &I, vpColor col)
Definition: vpMeLine.cpp:224
void track(const vpImage< unsigned char > &Im)
Definition: vpMeLine.cpp:746
void initTracking(const vpImage< unsigned char > &I)
Definition: vpMeLine.cpp:236
@ RANGE_RESULT
Definition: vpMeSite.h:74
void setDisplay(vpMeSite::vpMeSiteDisplayType select)
Definition: vpMeTracker.h:152
void setMe(vpMe *p_me)
Definition: vpMeTracker.h:173
Definition: vpMe.h:61
void setSampleStep(const double &s)
Definition: vpMe.h:278
void setRange(const unsigned int &r)
Definition: vpMe.h:271
void setPointsToTrack(const int &n)
Definition: vpMe.h:264
void setThreshold(const double &t)
Definition: vpMe.h:300
Control of Irisa's gantry robot named Afma6.
Definition: vpRobotAfma6.h:212
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
@ CAMERA_FRAME
Definition: vpRobot.h:82
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:66
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Definition: vpServo.cpp:567
@ EYEINHAND_CAMERA
Definition: vpServo.h:155
void print(const vpServo::vpServoPrintType display_level=ALL, std::ostream &os=std::cout)
Definition: vpServo.cpp:306
void setLambda(double c)
Definition: vpServo.h:404
void setServo(const vpServoType &servo_type)
Definition: vpServo.cpp:218
vpColVector getError() const
Definition: vpServo.h:278
@ PSEUDO_INVERSE
Definition: vpServo.h:202
vpColVector computeControlLaw()
Definition: vpServo.cpp:929
@ DESIRED
Definition: vpServo.h:186
void addFeature(vpBasicFeature &s, vpBasicFeature &s_star, unsigned int select=vpBasicFeature::FEATURE_ALL)
Definition: vpServo.cpp:490
#define vpTRACE
Definition: vpDebug.h:416