ViSP  2.8.0
servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp
1 /****************************************************************************
2  *
3  * $Id: servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp 4107 2013-02-06 10:04:49Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2013 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  * tests the control law
36  * eye-in-hand control
37  * velocity computed in the camera frame
38  *
39  * Authors:
40  * Nicolas Melchior
41  *
42  *****************************************************************************/
43 
63 #include <visp/vpConfig.h>
64 #include <visp/vpDebug.h> // Debug trace
65 #include <stdlib.h>
66 #include <cmath> // std::fabs
67 #include <limits> // numeric_limits
68 #if (defined (VISP_HAVE_AFMA6) && defined (VISP_HAVE_DC1394_2))
69 
70 #include <visp/vp1394TwoGrabber.h>
71 #include <visp/vpImage.h>
72 #include <visp/vpImageIo.h>
73 #include <visp/vpDisplay.h>
74 #include <visp/vpDisplayX.h>
75 #include <visp/vpDisplayOpenCV.h>
76 #include <visp/vpDisplayGTK.h>
77 
78 #include <visp/vpMath.h>
79 #include <visp/vpHomogeneousMatrix.h>
80 #include <visp/vpFeatureLine.h>
81 #include <visp/vpMeLine.h>
82 #include <visp/vpCylinder.h>
83 #include <visp/vpServo.h>
84 #include <visp/vpFeatureBuilder.h>
85 
86 #include <visp/vpRobotAfma6.h>
87 
88 // Exception
89 #include <visp/vpException.h>
90 #include <visp/vpMatrixException.h>
91 #include <visp/vpServoDisplay.h>
92 
93 
94 int
95 main()
96 {
97  try
98  {
100 
104  g.open(I) ;
105 
106  g.acquire(I) ;
107 
108 #ifdef VISP_HAVE_X11
109  vpDisplayX display(I,100,100,"Current image") ;
110 #elif defined(VISP_HAVE_OPENCV)
111  vpDisplayOpenCV display(I,100,100,"Current image") ;
112 #elif defined(VISP_HAVE_GTK)
113  vpDisplayGTK display(I,100,100,"Current image") ;
114 #endif
115 
116  vpDisplay::display(I) ;
117  vpDisplay::flush(I) ;
118 
119  vpServo task ;
120 
121  std::cout << std::endl ;
122  std::cout << "-------------------------------------------------------" << std::endl ;
123  std::cout << " Test program for vpServo " <<std::endl ;
124  std::cout << " Eye-in-hand task control, velocity computed in the camera frame" << std::endl ;
125  std::cout << " Simulation " << std::endl ;
126  std::cout << " task : servo a point " << std::endl ;
127  std::cout << "-------------------------------------------------------" << std::endl ;
128  std::cout << std::endl ;
129 
130 
131  int i ;
132  int nbline =2 ;
133  vpMeLine line[nbline] ;
134 
135  vpMe me ;
136  me.setRange(20) ;
137  me.setPointsToTrack(100) ;
138  me.setThreshold(2000) ;
139  me.setSampleStep(10);
140 
141  //Initialize the tracking of the two edges of the cylinder
142  for (i=0 ; i < nbline ; i++)
143  {
145  line[i].setMe(&me) ;
146 
147  line[i].initTracking(I) ;
148  line[i].track(I) ;
149  }
150 
151  vpRobotAfma6 robot ;
152  //robot.move("zero.pos") ;
153 
154  vpCameraParameters cam ;
155  // Update camera parameters
156  robot.getCameraParameters (cam, I);
157 
158  vpTRACE("sets the current position of the visual feature ") ;
159  vpFeatureLine p[nbline] ;
160  for (i=0 ; i < nbline ; i++)
161  vpFeatureBuilder::create(p[i],cam, line[i]) ;
162 
163  vpTRACE("sets the desired position of the visual feature ") ;
164  vpCylinder cyld(0,1,0,0,0,0,0.04);
165 
166  vpHomogeneousMatrix cMo(0,0,0.5,0,0,vpMath::rad(0));
167 
168  cyld.project(cMo);
169 
170  vpFeatureLine pd[nbline] ;
173 
174  //Those lines are needed to keep the conventions define in vpMeLine (Those in vpLine are less restrictive)
175  //Another way to have the coordinates of the desired features is to learn them before executing the program.
176  pd[0].setRhoTheta(-fabs(pd[0].getRho()),0);
177  pd[1].setRhoTheta(-fabs(pd[1].getRho()),M_PI);
178 
179  vpTRACE("define the task") ;
180  vpTRACE("\t we want an eye-in-hand control law") ;
181  vpTRACE("\t robot is controlled in the camera frame") ;
184 
185  vpTRACE("\t we want to see a point on a point..") ;
186  std::cout << std::endl ;
187  for (i=0 ; i < nbline ; i++)
188  task.addFeature(p[i],pd[i]) ;
189 
190  vpTRACE("\t set the gain") ;
191  task.setLambda(0.3) ;
192 
193 
194  vpTRACE("Display task information " ) ;
195  task.print() ;
196 
197 
199 
200  unsigned int iter=0 ;
201  vpTRACE("\t loop") ;
202  vpColVector v ;
203  vpImage<vpRGBa> Ic ;
204  double lambda_av =0.05;
205  double alpha = 0.02;
206  double beta =3;
207  double erreur = 1;
208 
209 
210  //First loop to reach the convergence position
211  while(erreur > 0.00001)
212  {
213  std::cout << "---------------------------------------------" << iter <<std::endl ;
214 
215  try {
216  g.acquire(I) ;
217  vpDisplay::display(I) ;
218 
219  //Track the two edges and update the features
220  for (i=0 ; i < nbline ; i++)
221  {
222  line[i].track(I) ;
223  line[i].display(I, vpColor::red) ;
224 
225  vpFeatureBuilder::create(p[i],cam,line[i]);
226 
227  p[i].display(cam, I, vpColor::red) ;
228  pd[i].display(cam, I, vpColor::green) ;
229  }
230 
231  vpDisplay::flush(I) ;
232 
233  //Adaptative gain
234  double gain ;
235  {
236  if (std::fabs(alpha) <= std::numeric_limits<double>::epsilon())
237  gain = lambda_av ;
238  else
239  {
240  gain = alpha * exp (-beta * ( task.getError() ).sumSquare() ) + lambda_av ;
241  }
242  }
243  task.setLambda(gain) ;
244 
245  v = task.computeControlLaw() ;
246 
247  if (iter==0) vpDisplay::getClick(I) ;
248  }
249  catch(...)
250  {
251  v =0 ;
253  robot.stopMotion() ;
254  exit(1) ;
255  }
256 
258  erreur = ( task.getError() ).sumSquare();
259  vpTRACE("\t\t || s - s* || = %f ", ( task.getError() ).sumSquare()) ;
260  iter++;
261  }
262 
263  /**********************************************************************************************/
264 
265  //Second loop is to compute the control while taking into account the secondary task.
266  vpColVector e1(6) ; e1 = 0 ;
267  vpColVector e2(6) ; e2 = 0 ;
268  vpColVector proj_e1 ;
269  vpColVector proj_e2 ;
270  iter = 0;
271  double rapport = 0;
272  double vitesse = 0.02;
273  unsigned int tempo = 1200;
274 
275  for ( ; ; )
276  {
277  std::cout << "---------------------------------------------" << iter <<std::endl ;
278 
279  try {
280  g.acquire(I) ;
281  vpDisplay::display(I) ;
282 
283  //Track the two edges and update the features
284  for (i=0 ; i < nbline ; i++)
285  {
286  line[i].track(I) ;
287  line[i].display(I, vpColor::red) ;
288 
289  vpFeatureBuilder::create(p[i],cam,line[i]);
290 
291  p[i].display(cam, I, vpColor::red) ;
292  pd[i].display(cam, I, vpColor::green) ;
293  }
294 
295  vpDisplay::flush(I) ;
296 
297  v = task.computeControlLaw() ;
298 
299  //Compute the new control law corresponding to the secondary task
300  if ( iter%tempo < 400 /*&& iter%tempo >= 0*/)
301  {
302  e2 = 0;
303  e1[0] = fabs(vitesse) ;
304  proj_e1 = task.secondaryTask(e1);
305  rapport = vitesse/proj_e1[0];
306  proj_e1 *= rapport ;
307  v += proj_e1 ;
308  if ( iter == 199 ) iter+=200; //This line is needed to make on ly an half turn during the first cycle
309  }
310 
311  if ( iter%tempo < 600 && iter%tempo >= 400)
312  {
313  e1 = 0;
314  e2[1] = fabs(vitesse) ;
315  proj_e2 = task.secondaryTask(e2);
316  rapport = vitesse/proj_e2[1];
317  proj_e2 *= rapport ;
318  v += proj_e2 ;
319  }
320 
321  if ( iter%tempo < 1000 && iter%tempo >= 600)
322  {
323  e2 = 0;
324  e1[0] = -fabs(vitesse) ;
325  proj_e1 = task.secondaryTask(e1);
326  rapport = -vitesse/proj_e1[0];
327  proj_e1 *= rapport ;
328  v += proj_e1 ;
329  }
330 
331  if ( iter%tempo < 1200 && iter%tempo >= 1000)
332  {
333  e1 = 0;
334  e2[1] = -fabs(vitesse) ;
335  proj_e2 = task.secondaryTask(e2);
336  rapport = -vitesse/proj_e2[1];
337  proj_e2 *= rapport ;
338  v += proj_e2 ;
339  }
340 
342  }
343  catch(...)
344  {
345  v =0 ;
347  robot.stopMotion() ;
348  exit(1) ;
349  }
350 
351  vpTRACE("\t\t || s - s* || = %f ", ( task.getError() ).sumSquare()) ;
352  iter++;
353  }
354 
355 
356  vpTRACE("Display task information " ) ;
357  task.print() ;
358  task.kill();
359  }
360  catch (...)
361  {
362  vpERROR_TRACE(" Test failed") ;
363  return 0;
364  }
365 }
366 
367 #else
368 int
369 main()
370 {
371  vpERROR_TRACE("You do not have an afma6 robot or a firewire framegrabber connected to your computer...");
372 }
373 
374 #endif
void setPointsToTrack(const int &n)
Definition: vpMe.h:215
The class provides a data structure for the homogeneous matrices as well as a set of operations on th...
#define vpERROR_TRACE
Definition: vpDebug.h:379
#define vpTRACE
Definition: vpDebug.h:401
void getCameraParameters(vpCameraParameters &cam, const unsigned int &image_width, const unsigned int &image_height)
Definition: vpAfma6.cpp:1234
void setSampleStep(const double &s)
Definition: vpMe.h:271
Define the X11 console to display images.
Definition: vpDisplayX.h:152
void addFeature(vpBasicFeature &s, vpBasicFeature &s_star, const unsigned int select=vpBasicFeature::FEATURE_ALL)
create a new ste of two visual features
Definition: vpServo.cpp:444
void setLambda(double _lambda)
set the gain lambda
Definition: vpServo.h:253
void track(const vpImage< unsigned char > &Im)
Definition: vpMeLine.cpp:810
Contains predetermined masks for sites and holds moving edges tracking parameters.
Definition: vpMe.h:70
vpColVector secondaryTask(vpColVector &de2dt)
Add a secondary task.
Definition: vpServo.cpp:1053
static const vpColor green
Definition: vpColor.h:170
void acquire(vpImage< unsigned char > &I)
static void flush(const vpImage< unsigned char > &I)
Definition: vpDisplay.cpp:1991
Control of Irisa's gantry robot named Afma6.
Definition: vpRobotAfma6.h:214
static const vpColor red
Definition: vpColor.h:167
void display(const vpImage< unsigned char > &I, vpColor col)
Definition: vpMeLine.cpp:238
void open(vpImage< unsigned char > &I)
void kill()
destruction (memory deallocation if required)
Definition: vpServo.cpp:177
Initialize the velocity controller.
Definition: vpRobot.h:70
vpColVector getError() const
Definition: vpServo.h:301
vpColVector computeControlLaw()
compute the desired control law
Definition: vpServo.cpp:883
void display(const vpCameraParameters &cam, const vpImage< unsigned char > &I, const vpColor &color=vpColor::green, unsigned int thickness=1) const
void setDisplay(vpMeSite::vpMeSiteDisplayType select)
Definition: vpMeTracker.h:108
static void display(const vpImage< unsigned char > &I)
Definition: vpDisplay.cpp:203
Class that tracks in an image a line moving edges.
Definition: vpMeLine.h:156
The vpDisplayOpenCV allows to display image using the opencv library.
Generic class defining intrinsic camera parameters.
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+ library version 1.2.
Definition: vpDisplayGTK.h:145
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
void initTracking(const vpImage< unsigned char > &I)
Definition: vpMeLine.cpp:252
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Set the type of the interaction matrix (current, mean, desired, user).
Definition: vpServo.cpp:509
static double rad(double deg)
Definition: vpMath.h:100
Class that defines what is a cylinder.
Definition: vpCylinder.h:97
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 setFramerate(vp1394TwoFramerateType fps)
void setVideoMode(vp1394TwoVideoModeType videomode)
void setThreshold(const double &t)
Definition: vpMe.h:299
void print(const vpServo::vpServoPrintType display_level=ALL, std::ostream &os=std::cout)
Definition: vpServo.cpp:258
Class for firewire ieee1394 video devices using libdc1394-2.x api.
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &velocity)
virtual bool getClick(bool blocking=true)=0
static void create(vpFeaturePoint &s, const vpCameraParameters &cam, const vpDot &d)
void setRange(const unsigned int &r)
Definition: vpMe.h:229
Class required to compute the visual servoing control law descbribed in and .
Definition: vpServo.h:153
void setServo(vpServoType _servo_type)
Choice of the visual servoing control law.
Definition: vpServo.cpp:214
void setMe(vpMe *me)
Definition: vpMeTracker.h:140
void setRhoTheta(const double rho, const double theta)