Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
tutorial-flir-ptu-ibvs.cpp
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
9 * See the file LICENSE.txt at the root directory of this source
10 * distribution for additional information about the GNU GPL.
11 *
12 * For using ViSP with software that can not be combined with the GNU
13 * GPL, please contact Inria about acquiring a ViSP Professional
14 * Edition License.
15 *
16 * See https://visp.inria.fr for more information.
17 *
18 * This software was developed at:
19 * Inria Rennes - Bretagne Atlantique
20 * Campus Universitaire de Beaulieu
21 * 35042 Rennes Cedex
22 * France
23 *
24 * If you have questions regarding the use of this file, please contact
25 * Inria at visp@inria.fr
26 *
27 * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28 * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29 *
30 * Description:
31 * tests the control law
32 * eye-in-hand control
33 * velocity computed in the camera frame
34 */
55
56#include <iostream>
57
58#include <visp3/core/vpCameraParameters.h>
59#include <visp3/core/vpConfig.h>
60#include <visp3/detection/vpDetectorAprilTag.h>
61#include <visp3/gui/vpDisplayFactory.h>
62#include <visp3/gui/vpPlot.h>
63#include <visp3/io/vpImageIo.h>
64#include <visp3/robot/vpRobotFlirPtu.h>
65#include <visp3/sensor/vpFlyCaptureGrabber.h>
66#include <visp3/visual_features/vpFeatureBuilder.h>
67#include <visp3/visual_features/vpFeaturePoint.h>
68#include <visp3/vs/vpServo.h>
69#include <visp3/vs/vpServoDisplay.h>
70
71#if defined(VISP_HAVE_FLIR_PTU_SDK) && defined(VISP_HAVE_FLYCAPTURE) && defined(VISP_HAVE_DISPLAY)
72
73int main(int argc, char **argv)
74{
75#ifdef ENABLE_VISP_NAMESPACE
76 using namespace VISP_NAMESPACE_NAME;
77#endif
78
79 std::string opt_portname;
80 int opt_baudrate = 9600;
81 bool opt_network = false;
82 std::string opt_extrinsic;
83 double opt_tag_size = 0.120; // Used to compute the distance of the cog wrt the camera
84 double opt_constant_gain = 0.5;
85
86 if (argc == 1) {
87 std::cout << "To see how to use this example, run: " << argv[0] << " --help" << std::endl;
88 return EXIT_SUCCESS;
89 }
90
91 for (int i = 1; i < argc; i++) {
92 if ((std::string(argv[i]) == "--portname" || std::string(argv[i]) == "-p") && (i + 1 < argc)) {
93 opt_portname = std::string(argv[i + 1]);
94 }
95 else if ((std::string(argv[i]) == "--baudrate" || std::string(argv[i]) == "-b") && (i + 1 < argc)) {
96 opt_baudrate = std::atoi(argv[i + 1]);
97 }
98 else if ((std::string(argv[i]) == "--network" || std::string(argv[i]) == "-n")) {
99 opt_network = true;
100 }
101 else if (std::string(argv[i]) == "--extrinsic" && i + 1 < argc) {
102 opt_extrinsic = std::string(argv[i + 1]);
103 }
104 else if (std::string(argv[i]) == "--constant-gain" || std::string(argv[i]) == "-g") {
105 opt_constant_gain = std::stod(argv[i + 1]);
106 ;
107 }
108 else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
109 std::cout << "SYNOPSIS" << std::endl
110 << " " << argv[0] << " [--portname <portname>] [--baudrate <rate>] [--network] "
111 << "[--extrinsic <extrinsic.yaml>] [--constant-gain] [--help] [-h]" << std::endl
112 << std::endl;
113 std::cout << "DESCRIPTION" << std::endl
114 << " --portname, -p <portname>" << std::endl
115 << " Set serial or tcp port name." << std::endl
116 << std::endl
117 << " --baudrate, -b <rate>" << std::endl
118 << " Set serial communication baud rate. Default: " << opt_baudrate << "." << std::endl
119 << std::endl
120 << " --network, -n" << std::endl
121 << " Get PTU network information (Hostname, IP, Gateway) and exit. " << std::endl
122 << std::endl
123 << " --extrinsic <extrinsic.yaml>" << std::endl
124 << " YAML file containing extrinsic camera parameters as a vpHomogeneousMatrix." << std::endl
125 << " It corresponds to the homogeneous transformation eMc, between end-effector" << std::endl
126 << " and camera frame." << std::endl
127 << std::endl
128 << " --constant-gain, -g" << std::endl
129 << " Constant gain value. Default value: " << opt_constant_gain << std::endl
130 << std::endl
131 << " --help, -h" << std::endl
132 << " Print this helper message. " << std::endl
133 << std::endl;
134 std::cout << "EXAMPLE" << std::endl
135 << " - How to get network IP" << std::endl
136#ifdef _WIN32
137 << " $ " << argv[0] << " --portname COM1 --network" << std::endl
138 << " Try to connect FLIR PTU to port: COM1 with baudrate: 9600" << std::endl
139#else
140 << " $ " << argv[0] << " --portname /dev/ttyUSB0 --network" << std::endl
141 << " Try to connect FLIR PTU to port: /dev/ttyUSB0 with baudrate: 9600" << std::endl
142#endif
143 << " PTU HostName: PTU-5" << std::endl
144 << " PTU IP : 169.254.110.254" << std::endl
145 << " PTU Gateway : 0.0.0.0" << std::endl
146 << " - How to run this binary using network communication" << std::endl
147 << " $ " << argv[0] << " --portname tcp:169.254.110.254 --tag-size 0.1 --gain 0.1" << std::endl;
148
149 return EXIT_SUCCESS;
150 }
151 }
152
153 vpRobotFlirPtu robot;
154
155#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
156 std::shared_ptr<vpDisplay> display;
157#else
158 vpDisplay *display = nullptr;
159#endif
160
161 try {
162 std::cout << "Try to connect FLIR PTU to port: " << opt_portname << " with baudrate: " << opt_baudrate << std::endl;
163 robot.connect(opt_portname, opt_baudrate);
164
165 if (opt_network) {
166 std::cout << "PTU HostName: " << robot.getNetworkHostName() << std::endl;
167 std::cout << "PTU IP : " << robot.getNetworkIP() << std::endl;
168 std::cout << "PTU Gateway : " << robot.getNetworkGateway() << std::endl;
169 return EXIT_SUCCESS;
170 }
171
173
175 g.open(I);
176
177 // Get camera extrinsics
180 eRc << 0, 0, 1, -1, 0, 0, 0, -1, 0;
181 etc << -0.1, -0.123, 0.035;
182 vpHomogeneousMatrix eMc(etc, eRc);
183
184 if (!opt_extrinsic.empty()) {
185 vpPoseVector ePc;
186 ePc.loadYAML(opt_extrinsic, ePc);
187 eMc.buildFrom(ePc);
188 }
189
190 std::cout << "Considered extrinsic transformation eMc:\n" << eMc << std::endl;
191
192 // Get camera intrinsics
193 vpCameraParameters cam(900, 900, I.getWidth() / 2., I.getHeight() / 2.);
194 std::cout << "Considered intrinsic camera parameters:\n" << cam << "\n";
195
196#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
197 display = vpDisplayFactory::createDisplay(I, 10, 10, "Color image");
198#else
199 display = vpDisplayFactory::allocateDisplay(I, 10, 10, "Color image");
200#endif
201
203 detector.setAprilTagPoseEstimationMethod(vpDetectorAprilTag::HOMOGRAPHY_VIRTUAL_VS);
204 detector.setDisplayTag(true);
205 detector.setAprilTagQuadDecimate(2);
206
207 // Create visual features
208 vpFeaturePoint p, pd; // We use 1 point, the tag cog
209
210 // Set desired position to the image center
211 pd.set_x(0);
212 pd.set_y(0);
213
215 // Add the visual feature point
216 task.addFeature(p, pd);
218 task.setInteractionMatrixType(vpServo::CURRENT);
219 task.setLambda(opt_constant_gain);
220
221 bool final_quit = false;
222 bool send_velocities = false;
223 vpMatrix eJe;
224
225 robot.set_eMc(eMc); // Set location of the camera wrt end-effector frame
226
227 vpVelocityTwistMatrix cVe = robot.get_cVe();
228 task.set_cVe(cVe);
229
230 robot.setRobotState(vpRobot::STATE_VELOCITY_CONTROL);
231
232 std::vector<vpHomogeneousMatrix> cMo_vec;
233 vpColVector qdot(2);
234
235 while (!final_quit) {
236 g.acquire(I);
237
239
240 detector.detect(I, opt_tag_size, cam, cMo_vec);
241
242 std::stringstream ss;
243 ss << "Left click to " << (send_velocities ? "stop the robot" : "servo the robot") << ", right click to quit.";
244 vpDisplay::displayText(I, 20, 20, ss.str(), vpColor::red);
245
246 // Only one tag has to be detected
247 if (detector.getNbObjects() == 1) {
248
249 vpImagePoint cog = detector.getCog(0);
250 double Z = cMo_vec[0][2][3];
251
252 // Update current feature from measured cog position
253 double x = 0, y = 0;
255 p.set_xyZ(x, y, Z);
256 pd.set_Z(Z);
257
258 // Get robot Jacobian
259 robot.get_eJe(eJe);
260 task.set_eJe(eJe);
261
262 qdot = task.computeControlLaw();
263
264 // Display the current and desired feature points in the image display
265 vpServoDisplay::display(task, cam, I);
266 } // end if (cMo_vec.size() == 1)
267 else {
268 qdot = 0;
269 }
270
271 if (!send_velocities) {
272 qdot = 0;
273 }
274
275 // Send to the robot
276 robot.setVelocity(vpRobot::JOINT_STATE, qdot);
277
279
281 if (vpDisplay::getClick(I, button, false)) {
282 switch (button) {
284 send_velocities = !send_velocities;
285 break;
286
288 final_quit = true;
289 qdot = 0;
290 break;
291
292 default:
293 break;
294 }
295 }
296 }
297 std::cout << "Stop the robot " << std::endl;
298 robot.setRobotState(vpRobot::STATE_STOP);
299 }
300 catch (const vpRobotException &e) {
301 std::cout << "Catch Flir Ptu exception: " << e.getMessage() << std::endl;
302 robot.setRobotState(vpRobot::STATE_STOP);
303 }
304
305#if (VISP_CXX_STANDARD < VISP_CXX_STANDARD_11)
306 if (display != nullptr) {
307 delete display;
308 }
309#endif
310 return EXIT_SUCCESS;
311}
312#else
313int main()
314{
315#if !defined(VISP_HAVE_FLYCAPTURE)
316 std::cout << "Install FLIR Flycapture" << std::endl;
317#endif
318#if !defined(VISP_HAVE_FLIR_PTU_SDK)
319 std::cout << "Install FLIR PTU SDK." << std::endl;
320#endif
321 return EXIT_SUCCESS;
322}
323#endif
static bool loadYAML(const std::string &filename, vpArray2D< Type > &A, char *header=nullptr)
Definition vpArray2D.h:874
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
static const vpColor red
Definition vpColor.h:198
@ TAG_36h11
AprilTag 36h11 pattern (recommended).
Class that defines generic functionalities for display.
Definition vpDisplay.h:171
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)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
Class that defines a 2D point visual feature which is composed by two parameters that are the cartes...
void set_y(double y)
void set_x(double x)
void set_Z(double Z)
void open(vpImage< unsigned char > &I)
void acquire(vpImage< unsigned char > &I)
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 of the vpImage class member functions.
Definition vpImage.h:131
Implementation of a matrix and operations on matrices.
Definition vpMatrix.h:175
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
Implementation of a pose vector and operations on poses.
Error that can be emitted by the vpRobot class and its derivatives.
@ JOINT_STATE
Definition vpRobot.h:79
@ STATE_VELOCITY_CONTROL
Initialize the velocity controller.
Definition vpRobot.h:64
@ STATE_STOP
Stops robot motion especially in velocity and acceleration control.
Definition vpRobot.h:63
Implementation of a rotation matrix and operations on such kind of matrices.
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)
@ EYEINHAND_L_cVe_eJe
Definition vpServo.h:183
@ CURRENT
Definition vpServo.h:217
Class that consider the case of a translation vector.
std::shared_ptr< vpDisplay > createDisplay()
Return a smart pointer vpDisplay specialization if a GUI library is available or nullptr otherwise.
vpDisplay * allocateDisplay()
Return a newly allocated vpDisplay specialization if a GUI library is available or nullptr otherwise.