ViSP  2.6.2
servoAfma6Line2DCamVelocity.cpp
1 /****************************************************************************
2  *
3  * $Id: servoAfma6Line2DCamVelocity.cpp 3668 2012-04-04 09:07:10Z 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  * Eric Marchand
41  *
42  *****************************************************************************/
62 #include <visp/vpConfig.h>
63 #include <visp/vpDebug.h> // Debug trace
64 #include <stdlib.h>
65 #if (defined (VISP_HAVE_AFMA6) && defined (VISP_HAVE_DC1394_2))
66 
67 #include <visp/vp1394TwoGrabber.h>
68 #include <visp/vpImage.h>
69 #include <visp/vpDisplay.h>
70 #include <visp/vpDisplayX.h>
71 
72 #include <visp/vpMath.h>
73 #include <visp/vpHomogeneousMatrix.h>
74 #include <visp/vpFeatureLine.h>
75 #include <visp/vpLine.h>
76 #include <visp/vpMeLine.h>
77 #include <visp/vpServo.h>
78 #include <visp/vpFeatureBuilder.h>
79 
80 #include <visp/vpRobotAfma6.h>
81 
82 // Exception
83 #include <visp/vpException.h>
84 #include <visp/vpMatrixException.h>
85 #include <visp/vpServoDisplay.h>
86 
87 int
88 main()
89 {
90  try
91  {
93 
97 
98  g.open(I) ;
99 
100  g.acquire(I) ;
101 
102 
103  vpDisplayX display(I,100,100,"Example using one line.cpp ") ;
104  vpTRACE(" ") ;
105 
106  vpDisplay::display(I) ;
107  vpDisplay::flush(I) ;
108 
109 
110  vpServo task ;
111 
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 
123  vpMeLine line ;
124 
125  vpMe me ;
126  me.setRange(10) ;
127  me.setPointsToTrack(100) ;
128  me.setThreshold(100000) ;
129  me.setSampleStep(10);
131 
132 
133  line.setMe(&me) ;
134 
135  //Initialize the tracking. Define the line to track.
136  line.initTracking(I) ;
137  line.track(I) ;
138 
139  vpRobotAfma6 robot ;
140  // robot.move("pos-init.pos") ;
141 
142  vpCameraParameters cam ;
143  // Update camera parameters
144  robot.getCameraParameters (cam, I);
145 
146  vpTRACE("sets the current position of the visual feature ") ;
147  vpFeatureLine p ;
148  vpFeatureBuilder::create(p,cam, line) ;
149 
150  vpTRACE("sets the desired position of the visual feature ") ;
151  vpLine lined;
152  lined.setWorldCoordinates(1,0,0,0,0,0,1,0);
153  vpHomogeneousMatrix cMo(0,0,0.3,0,0,vpMath::rad(0));
154  lined.project(cMo);
155  lined.setRho(-fabs(lined.getRho()));
156  lined.setTheta(0);
157 
158  vpFeatureLine pd ;
159  vpFeatureBuilder::create(pd,lined);
160 
161  vpTRACE("define the task") ;
162  vpTRACE("\t we want an eye-in-hand control law") ;
163  vpTRACE("\t robot is controlled in the camera frame") ;
165 
166  vpTRACE("\t we want to see a point on a point..") ;
167  std::cout << std::endl ;
168  task.addFeature(p,pd) ;
169 
170  vpTRACE("\t set the gain") ;
171  task.setLambda(0.2) ;
172 
173 
174  vpTRACE("Display task information " ) ;
175  task.print() ;
176 
177 
179 
180  unsigned int iter=0 ;
181  vpTRACE("\t loop") ;
182  vpColVector v ;
183  for ( ; ; )
184  {
185  std::cout << "---------------------------------------------" << iter <<std::endl ;
186 
187  try {
188  g.acquire(I) ;
189  vpDisplay::display(I) ;
190 
191  //Track the line
192  line.track(I) ;
193  line.display(I, vpColor::red) ;
194 
195  //Update the current line feature
196  vpFeatureBuilder::create(p,cam,line);
197 
198  //displqy the current and the desired features
199  p.display(cam, I, vpColor::red) ;
200  pd.display(cam, I, vpColor::green) ;
201 
202  v = task.computeControlLaw() ;
203 
204  vpDisplay::flush(I) ;
205  if (iter==0) vpDisplay::getClick(I) ;
207  }
208  catch(...)
209  {
210  v =0 ;
212  robot.stopMotion() ;
213  exit(1) ;
214  }
215 
216  vpTRACE("\t\t || s - s* || = %f ", ( task.getError() ).sumSquare()) ;
217  iter++;
218  }
219 
220  vpTRACE("Display task information " ) ;
221  task.print() ;
222  task.kill();
223  }
224  catch (...)
225  {
226  vpERROR_TRACE(" Test failed") ;
227  return 0;
228  }
229 }
230 
231 #else
232 int
233 main()
234 {
235  vpERROR_TRACE("You do not have an afma6 robot or a firewire framegrabber connected to your computer...");
236 }
237 
238 #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 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:98
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
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
double getRho() const
Definition: vpLine.h:177
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:124
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
static double rad(double deg)
Definition: vpMath.h:100
void setRho(const double rho)
Definition: vpLine.h:144
void setTheta(const double theta)
Definition: vpLine.h:154
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