ViSP  2.6.2
servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp
1 /****************************************************************************
2  *
3  * $Id: servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp 3747 2012-05-30 07:39:39Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2012 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 
76 #include <visp/vpMath.h>
77 #include <visp/vpHomogeneousMatrix.h>
78 #include <visp/vpFeatureLine.h>
79 #include <visp/vpMeLine.h>
80 #include <visp/vpCylinder.h>
81 #include <visp/vpServo.h>
82 #include <visp/vpFeatureBuilder.h>
83 
84 #include <visp/vpRobotAfma6.h>
85 
86 // Exception
87 #include <visp/vpException.h>
88 #include <visp/vpMatrixException.h>
89 #include <visp/vpServoDisplay.h>
90 
91 
92 int
93 main()
94 {
95  try
96  {
98 
102  g.open(I) ;
103 
104  g.acquire(I) ;
105 
106  vpDisplayX display(I,100,100,"testDisplayX.cpp ") ;
107  vpTRACE(" ") ;
108 
109  vpDisplay::display(I) ;
110  vpDisplay::flush(I) ;
111 
112  vpServo task ;
113 
114  std::cout << std::endl ;
115  std::cout << "-------------------------------------------------------" << std::endl ;
116  std::cout << " Test program for vpServo " <<std::endl ;
117  std::cout << " Eye-in-hand task control, velocity computed in the camera frame" << std::endl ;
118  std::cout << " Simulation " << std::endl ;
119  std::cout << " task : servo a point " << std::endl ;
120  std::cout << "-------------------------------------------------------" << std::endl ;
121  std::cout << std::endl ;
122 
123 
124  int i ;
125  int nbline =2 ;
126  vpMeLine line[nbline] ;
127 
128  vpMe me ;
129  me.setRange(20) ;
130  me.setPointsToTrack(100) ;
131  me.setThreshold(2000) ;
132  me.setSampleStep(10);
133 
134  //Initialize the tracking of the two edges of the cylinder
135  for (i=0 ; i < nbline ; i++)
136  {
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  vpCylinder cyld(0,1,0,0,0,0,0.04);
158 
159  vpHomogeneousMatrix cMo(0,0,0.5,0,0,vpMath::rad(0));
160 
161  cyld.project(cMo);
162 
163  vpFeatureLine pd[nbline] ;
166 
167  //Those lines are needed to keep the conventions define in vpMeLine (Those in vpLine are less restrictive)
168  //Another way to have the coordinates of the desired features is to learn them before executing the program.
169  pd[0].setRhoTheta(-fabs(pd[0].getRho()),0);
170  pd[1].setRhoTheta(-fabs(pd[1].getRho()),M_PI);
171 
172  vpTRACE("define the task") ;
173  vpTRACE("\t we want an eye-in-hand control law") ;
174  vpTRACE("\t robot is controlled in the camera frame") ;
177 
178  vpTRACE("\t we want to see a point on a point..") ;
179  std::cout << std::endl ;
180  for (i=0 ; i < nbline ; i++)
181  task.addFeature(p[i],pd[i]) ;
182 
183  vpTRACE("\t set the gain") ;
184  task.setLambda(0.3) ;
185 
186 
187  vpTRACE("Display task information " ) ;
188  task.print() ;
189 
190 
192 
193  unsigned int iter=0 ;
194  vpTRACE("\t loop") ;
195  vpColVector v ;
196  vpImage<vpRGBa> Ic ;
197  double lambda_av =0.05;
198  double alpha = 0.02;
199  double beta =3;
200  double erreur = 1;
201 
202 
203  //First loop to reach the convergence position
204  while(erreur > 0.00001)
205  {
206  std::cout << "---------------------------------------------" << iter <<std::endl ;
207 
208  try {
209  g.acquire(I) ;
210  vpDisplay::display(I) ;
211 
212  //Track the two edges and update the features
213  for (i=0 ; i < nbline ; i++)
214  {
215  line[i].track(I) ;
216  line[i].display(I, vpColor::red) ;
217 
218  vpFeatureBuilder::create(p[i],cam,line[i]);
219 
220  p[i].display(cam, I, vpColor::red) ;
221  pd[i].display(cam, I, vpColor::green) ;
222  }
223 
224  vpDisplay::flush(I) ;
225 
226  //Adaptative gain
227  double gain ;
228  {
229  if (std::fabs(alpha) <= std::numeric_limits<double>::epsilon())
230  gain = lambda_av ;
231  else
232  {
233  gain = alpha * exp (-beta * ( task.getError() ).sumSquare() ) + lambda_av ;
234  }
235  }
236  task.setLambda(gain) ;
237 
238  v = task.computeControlLaw() ;
239 
240  if (iter==0) vpDisplay::getClick(I) ;
241  }
242  catch(...)
243  {
244  v =0 ;
246  robot.stopMotion() ;
247  exit(1) ;
248  }
249 
251  erreur = ( task.getError() ).sumSquare();
252  vpTRACE("\t\t || s - s* || = %f ", ( task.getError() ).sumSquare()) ;
253  iter++;
254  }
255 
256  /**********************************************************************************************/
257 
258  //Second loop is to compute the control while taking into account the secondary task.
259  vpColVector e1(6) ; e1 = 0 ;
260  vpColVector e2(6) ; e2 = 0 ;
261  vpColVector proj_e1 ;
262  vpColVector proj_e2 ;
263  iter = 0;
264  double rapport = 0;
265  double vitesse = 0.02;
266  int tempo = 1200;
267 
268  for ( ; ; )
269  {
270  std::cout << "---------------------------------------------" << iter <<std::endl ;
271 
272  try {
273  g.acquire(I) ;
274  vpDisplay::display(I) ;
275 
276  //Track the two edges and update the features
277  for (i=0 ; i < nbline ; i++)
278  {
279  line[i].track(I) ;
280  line[i].display(I, vpColor::red) ;
281 
282  vpFeatureBuilder::create(p[i],cam,line[i]);
283 
284  p[i].display(cam, I, vpColor::red) ;
285  pd[i].display(cam, I, vpColor::green) ;
286  }
287 
288  vpDisplay::flush(I) ;
289 
290  v = task.computeControlLaw() ;
291 
292  //Compute the new control law corresponding to the secondary task
293  if ( iter%tempo < 400 /*&& iter%tempo >= 0*/)
294  {
295  e2 = 0;
296  e1[0] = fabs(vitesse) ;
297  proj_e1 = task.secondaryTask(e1);
298  rapport = vitesse/proj_e1[0];
299  proj_e1 *= rapport ;
300  v += proj_e1 ;
301  if ( iter == 199 ) iter+=200; //This line is needed to make on ly an half turn during the first cycle
302  }
303 
304  if ( iter%tempo < 600 && iter%tempo >= 400)
305  {
306  e1 = 0;
307  e2[1] = fabs(vitesse) ;
308  proj_e2 = task.secondaryTask(e2);
309  rapport = vitesse/proj_e2[1];
310  proj_e2 *= rapport ;
311  v += proj_e2 ;
312  }
313 
314  if ( iter%tempo < 1000 && iter%tempo >= 600)
315  {
316  e2 = 0;
317  e1[0] = -fabs(vitesse) ;
318  proj_e1 = task.secondaryTask(e1);
319  rapport = -vitesse/proj_e1[0];
320  proj_e1 *= rapport ;
321  v += proj_e1 ;
322  }
323 
324  if ( iter%tempo < 1200 && iter%tempo >= 1000)
325  {
326  e1 = 0;
327  e2[1] = -fabs(vitesse) ;
328  proj_e2 = task.secondaryTask(e2);
329  rapport = -vitesse/proj_e2[1];
330  proj_e2 *= rapport ;
331  v += proj_e2 ;
332  }
333 
335  }
336  catch(...)
337  {
338  v =0 ;
340  robot.stopMotion() ;
341  exit(1) ;
342  }
343 
344  vpTRACE("\t\t || s - s* || = %f ", ( task.getError() ).sumSquare()) ;
345  iter++;
346  }
347 
348 
349  vpTRACE("Display task information " ) ;
350  task.print() ;
351  task.kill();
352  }
353  catch (...)
354  {
355  vpERROR_TRACE(" Test failed") ;
356  return 0;
357  }
358 }
359 
360 #else
361 int
362 main()
363 {
364  vpERROR_TRACE("You do not have an afma6 robot or a firewire framegrabber connected to your computer...");
365 }
366 
367 #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:1226
void setSampleStep(const double &s)
Definition: vpMe.h:277
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:250
void track(const vpImage< unsigned char > &Im)
Definition: vpMeLine.cpp:784
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:1055
static const vpColor green
Definition: vpColor.h:168
void acquire(vpImage< unsigned char > &I)
static void flush(const vpImage< unsigned char > &I)
Definition: vpDisplay.cpp:1964
Control of Irisa's gantry robot named Afma6.
Definition: vpRobotAfma6.h:214
static const vpColor red
Definition: vpColor.h:165
void display(const vpImage< unsigned char > &I, vpColor col)
Definition: vpMeLine.cpp:229
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:298
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:186
Class that tracks in an image a line moving edges.
Definition: vpMeLine.h:149
Generic class defining intrinsic camera parameters.
Class that defines a 2D line visual feature which is composed by two parameters that are and ...
vpRobot::vpRobotStateType setRobotState(vpRobot::vpRobotStateType newState)
void initTracking(const vpImage< unsigned char > &I)
Definition: vpMeLine.cpp:243
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:305
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.
Definition: vpServo.h:150
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)