Visual Servoing Platform version 3.5.0
servoPtu46Point2DArtVelocity.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 articular
35 *
36 * Authors:
37 * Fabien Spindler
38 *
39 *****************************************************************************/
40
60#include <visp3/core/vpConfig.h>
61#include <visp3/core/vpDebug.h> // Debug trace
62#if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX
63#include <unistd.h>
64#endif
65#include <signal.h>
66
67#if (defined(VISP_HAVE_PTU46) & defined(VISP_HAVE_DC1394))
68
69#ifdef VISP_HAVE_PTHREAD
70#include <pthread.h>
71#endif
72
73#include <visp3/core/vpDisplay.h>
74#include <visp3/core/vpImage.h>
75#include <visp3/gui/vpDisplayX.h>
76#include <visp3/sensor/vp1394TwoGrabber.h>
77
78#include <visp3/core/vpHomogeneousMatrix.h>
79#include <visp3/core/vpMath.h>
80#include <visp3/core/vpPoint.h>
81#include <visp3/visual_features/vpFeatureBuilder.h>
82#include <visp3/visual_features/vpFeaturePoint.h>
83#include <visp3/vs/vpServo.h>
84
85#include <visp3/robot/vpRobotPtu46.h>
86
87// Exception
88#include <visp3/core/vpException.h>
89#include <visp3/vs/vpServoDisplay.h>
90
91#include <visp3/blob/vpDot2.h>
92
93#ifdef VISP_HAVE_PTHREAD
94pthread_mutex_t mutexEndLoop = PTHREAD_MUTEX_INITIALIZER;
95#endif
96
97void signalCtrC(int signumber)
98{
99 (void)(signumber);
100#ifdef VISP_HAVE_PTHREAD
101 pthread_mutex_unlock(&mutexEndLoop);
102#endif
103 usleep(1000 * 10);
104 vpTRACE("Ctrl-C pressed...");
105}
106
107int main()
108{
109 std::cout << std::endl;
110 std::cout << "-------------------------------------------------------" << std::endl;
111 std::cout << " Test program for vpServo " << std::endl;
112 std::cout << " Eye-in-hand task control, velocity computed in the camera frame" << std::endl;
113 std::cout << " Simulation " << std::endl;
114 std::cout << " task : servo a point " << std::endl;
115 std::cout << "-------------------------------------------------------" << std::endl;
116 std::cout << std::endl;
117
118 try {
119
120#ifdef VISP_HAVE_PTHREAD
121 pthread_mutex_lock(&mutexEndLoop);
122#endif
123 signal(SIGINT, &signalCtrC);
124
125 vpRobotPtu46 robot;
126 {
127 vpColVector q(2);
128 q = 0;
130 robot.setPosition(vpRobot::ARTICULAR_FRAME, q);
131 }
132
134
136
137 g.open(I);
138
139 try {
140 g.acquire(I);
141 } catch (...) {
142 vpERROR_TRACE(" Error caught");
143 return (-1);
144 }
145
146 vpDisplayX display(I, 100, 100, "testDisplayX.cpp ");
147 vpTRACE(" ");
148
149 try {
152 } catch (...) {
153 vpERROR_TRACE(" Error caught");
154 return (-1);
155 }
156
157 vpServo task;
158
159 vpDot2 dot;
160
161 try {
162 vpERROR_TRACE("start dot.initTracking(I) ");
163 vpImagePoint germ;
164 vpDisplay::getClick(I, germ);
165 dot.setCog(germ);
166 vpDEBUG_TRACE(25, "Click!");
167 // dot.initTracking(I) ;
168 dot.track(I);
169 vpERROR_TRACE("after dot.initTracking(I) ");
170 } catch (...) {
171 vpERROR_TRACE(" Error caught ");
172 return (-1);
173 }
174
176
177 vpTRACE("sets the current position of the visual feature ");
179 vpFeatureBuilder::create(p, cam, dot); // retrieve x,y and Z of the vpPoint structure
180
181 p.set_Z(1);
182 vpTRACE("sets the desired position of the visual feature ");
184 pd.buildFrom(0, 0, 1);
185
186 vpTRACE("define the task");
187 vpTRACE("\t we want an eye-in-hand control law");
188 vpTRACE("\t articular velocity are computed");
191
192 vpTRACE("Set the position of the end-effector frame in the camera frame");
194 // robot.get_cMe(cMe) ;
195
197 robot.get_cVe(cVe);
198 std::cout << cVe << std::endl;
199 task.set_cVe(cVe);
200
202 vpTRACE("Set the Jacobian (expressed in the end-effector frame)");
203 vpMatrix eJe;
204 robot.get_eJe(eJe);
205 task.set_eJe(eJe);
206
207 vpTRACE("\t we want to see a point on a point..");
208 std::cout << std::endl;
209 task.addFeature(p, pd);
210
211 vpTRACE("\t set the gain");
212 task.setLambda(0.1);
213
214 vpTRACE("Display task information ");
215 task.print();
216
218
219 unsigned int iter = 0;
220 vpTRACE("\t loop");
221#ifdef VISP_HAVE_PTHREAD
222 while (0 != pthread_mutex_trylock(&mutexEndLoop))
223#else
224 for (;;)
225#endif
226 {
227 std::cout << "---------------------------------------------" << iter << std::endl;
228
229 g.acquire(I);
231
232 dot.track(I);
233
234 // vpDisplay::displayCross(I,(int)dot.I(), (int)dot.J(),
235 // 10,vpColor::green) ;
236
237 vpFeatureBuilder::create(p, cam, dot);
238
239 // get the jacobian
240 robot.get_eJe(eJe);
241 task.set_eJe(eJe);
242
243 // std::cout << (vpMatrix)cVe*eJe << std::endl ;
244
245 vpColVector v;
246 v = task.computeControlLaw();
247
248 vpServoDisplay::display(task, cam, I);
249 std::cout << v.t();
252
253 vpTRACE("\t\t || s - s* || = %f ", (task.getError()).sumSquare());
254 }
255
256 vpTRACE("Display task information ");
257 task.print();
258 }
259 catch (const vpException &e) {
260 std::cout << "Sorry PtU46 not available. Got exception: " << e << std::endl;
261 return EXIT_FAILURE
262 }
263 return EXIT_SUCCESS;
264}
265
266#else
267int main()
268{
269 std::cout << "You do not have an PTU46 PT robot connected to your computer..." << std::endl;
270}
271#endif
Class for firewire ieee1394 video devices using libdc1394-2.x api.
void acquire(vpImage< unsigned char > &I)
void open(vpImage< unsigned char > &I)
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:131
vpRowVector t() const
Use the X11 console to display images on unix-like OS. Thus to enable this class X11 should be instal...
Definition: vpDisplayX.h:135
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)
This tracker is meant to track a blob (connex pixels with same gray level) on a vpImage.
Definition: vpDot2.h:127
void track(const vpImage< unsigned char > &I, bool canMakeTheWindowGrow=true)
Definition: vpDot2.cpp:441
void setCog(const vpImagePoint &ip)
Definition: vpDot2.h:260
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 point visual feature which is composed by two parameters that are the cartes...
void buildFrom(double x, double y, double Z)
void set_Z(double Z)
Implementation of an homogeneous matrix and operations on such kind of matrices.
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:88
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:154
void setVelocity(const vpRobot::vpControlFrameType frame, const vpColVector &vel)
void get_eJe(vpMatrix &eJe)
Interface for the Directed Perception ptu-46 pan, tilt head .
Definition: vpRobotPtu46.h:81
@ ARTICULAR_FRAME
Definition: vpRobot.h:78
@ STATE_POSITION_CONTROL
Initialize the position controller.
Definition: vpRobot.h:67
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition: vpRobot.h:66
virtual vpRobotStateType setRobotState(const vpRobot::vpRobotStateType newState)
Definition: vpRobot.cpp:201
static void display(const vpServo &s, const vpCameraParameters &cam, const vpImage< unsigned char > &I, vpColor currentColor=vpColor::green, vpColor desiredColor=vpColor::red, unsigned int thickness=1)
void setInteractionMatrixType(const vpServoIteractionMatrixType &interactionMatrixType, const vpServoInversionType &interactionMatrixInversion=PSEUDO_INVERSE)
Definition: vpServo.cpp:567
@ EYEINHAND_L_cVe_eJe
Definition: vpServo.h:159
void set_cVe(const vpVelocityTwistMatrix &cVe_)
Definition: vpServo.h:448
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 set_eJe(const vpMatrix &eJe_)
Definition: vpServo.h:506
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
vpVelocityTwistMatrix get_cVe() const
Definition: vpUnicycle.h:82
#define vpTRACE
Definition: vpDebug.h:416
#define vpDEBUG_TRACE
Definition: vpDebug.h:487
#define vpERROR_TRACE
Definition: vpDebug.h:393