Visual Servoing Platform version 3.5.0
vpQbDevice.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 * Interface for the qb robotics devices.
33 *
34 * Authors:
35 * Fabien Spindler
36 *
37 *****************************************************************************/
38
39#include <visp3/core/vpConfig.h>
40#ifdef VISP_HAVE_QBDEVICE
41
42#include <regex>
43
44#include <qb_device_driver.h>
45
46#include <visp3/robot/vpQbDevice.h>
47#include <visp3/core/vpIoTools.h>
48
49#ifndef DOXYGEN_SHOULD_SKIP_THIS
50class vpQbDevice::Impl
51{
52public:
53 Impl()
54 : Impl(std::make_shared<qb_device_driver::qbDeviceAPI>())
55 {
56 }
57 Impl(std::shared_ptr<qb_device_driver::qbDeviceAPI> device_api)
58 : m_serial_protectors(), m_connected_devices(),
59 m_position_limits(2), m_device_api(device_api), m_file_descriptors(),
60 m_max_repeats(1), m_current_max(750.)
61 {
62 // Default values updated after a call to init()
63 m_position_limits[0] = 0;
64 m_position_limits[1] = 19000;
65 }
66
67 virtual ~Impl()
68 {
69 for (auto it = m_file_descriptors.begin(); it != m_file_descriptors.end(); ) {
70 if (close(it->first)) {
71 it = m_file_descriptors.erase(it);
72 }
73 else {
74 ++ it;
75 }
76 }
77 }
78
79 virtual int activate(const int &id, const bool &command, const int &max_repeats);
80 virtual int activate(const int &id, const int &max_repeats)
81 {
82 return activate(id, true, max_repeats);
83 }
84
85 virtual bool close(const std::string &serial_port);
86
87 virtual int deactivate(const int &id, const int &max_repeats)
88 {
89 return activate(id, false, max_repeats);
90 }
91
92 inline double getCurrentMax() const {
93 return m_current_max;
94 }
95
96 virtual int getCurrents(const int &id, const int &max_repeats, std::vector<short int> &currents);
97 virtual int getInfo(const int &id, const int &max_repeats, std::string &info);
98 virtual int getMeasurements(const int &id, const int &max_repeats, std::vector<short int> &currents, std::vector<short int> &positions);
99 virtual int getParameters(const int &id, std::vector<int> &limits, std::vector<int> &resolutions);
100
101 std::vector<short int> getPositionLimits() const
102 {
103 return m_position_limits;
104 }
105
106 virtual int getPositions(const int &id, const int &max_repeats, std::vector<short int> &positions);
107 virtual int getSerialPortsAndDevices(const int &max_repeats);
108 virtual bool init(const int &id);
109 virtual int isActive(const int &id, const int &max_repeats, bool &status);
110
111 virtual int isConnected(const int &id, const int &max_repeats);
112
113 virtual bool isInConnectedSet(const int &id)
114 {
115 return (m_connected_devices.count(id) ? true : false);
116 }
117
118 virtual bool isInOpenMap(const std::string &serial_port)
119 {
120 return (m_file_descriptors.count(serial_port) ? true : false);
121 }
122
123 inline bool isReliable(int const &failures, int const &max_repeats) { return failures >= 0 && failures <= max_repeats; }
124 virtual int open(const std::string &serial_port);
125
126 virtual int setCommandsAndWait(const int &id, const int &max_repeats, std::vector<short int> &commands);
127 virtual int setCommandsAsync(const int &id, std::vector<short int> &commands);
128
129 void setMaxRepeats(const int &max_repeats) {
130 m_max_repeats = max_repeats;
131 }
132
133public:
134 std::map<std::string, std::unique_ptr<std::mutex>> m_serial_protectors; // only callbacks must lock the serial resources
135 std::map<int, std::string> m_connected_devices;
136
137protected:
138#if (defined(_WIN32) || defined (_WIN64))
139 std::unique_ptr<std::mutex> m_mutex_dummy; // FS: cannot build without this line with msvc
140#endif
141 std::vector<short int> m_position_limits; // min and max position values in ticks
142 std::shared_ptr<qb_device_driver::qbDeviceAPI> m_device_api;
143 std::map<std::string, comm_settings> m_file_descriptors;
144 int m_max_repeats;
145 double m_current_max;
146};
147
148int vpQbDevice::Impl::activate(const int &id, const bool &command, const int &max_repeats)
149{
150 std::string command_prefix = command ? "" : "de";
151 bool status = false;
152 int failures = 0;
153
154 failures = isActive(id, max_repeats, status);
155 if (status != command) {
156 m_device_api->activate(&m_file_descriptors.at(m_connected_devices.at(id)), id, command);
157 failures = std::max(failures, isActive(id, max_repeats, status));
158 if (status != command) {
159 std::cout << "Device [" << id << "] fails on " << command_prefix << "activation." << std::endl;;
160 return -1;
161 }
162 std::cout << "Device [" << id << "] motors have been " << command_prefix << "activated!" << std::endl;
163 return failures;
164 }
165 std::cout << "Device [" << id << "] motors were already " << command_prefix << "activated!" << std::endl;
166 return failures;
167}
168
169bool vpQbDevice::Impl::close(const std::string &serial_port)
170{
171 if (!isInOpenMap(serial_port)) {
172 std::cout << "has not handled [" << serial_port << "]." << std::endl;
173 return false; // no error: the communication is close anyway
174 }
175
176 for (auto const &device : m_connected_devices) {
177 if (device.second == serial_port) {
178 deactivate(device.first, m_max_repeats);
179 m_connected_devices.erase(device.first);
180 break;
181 }
182 }
183
184 m_device_api->close(&m_file_descriptors.at(serial_port));
185
186 // Note that m_file_descriptors.erase(serial_port) is done in the destructor.
187 // Cannot be done here since the iterator that is used in the destructor would be lost
188
189 std::cout << "does not handle [" << serial_port << "] anymore." << std::endl;
190 return true;
191}
192
193int vpQbDevice::Impl::getCurrents(const int &id, const int &max_repeats, std::vector<short int> &currents)
194{
195 // the API methods are called at most (i.e. very unlikely) 'max_repeats' times to guarantee the correct identification of a real fault in the communication
196 int failures = 0;
197 currents.resize(2); // required by 'getCurrents()'
198 std::lock_guard<std::mutex> serial_lock(*m_serial_protectors.at(m_connected_devices.at(id)));
199 while (failures <= max_repeats) {
200 if (m_device_api->getCurrents(&m_file_descriptors.at(m_connected_devices.at(id)), id, currents) < 0) {
201 failures++;
202 continue;
203 }
204 break;
205 }
206 return failures;
207}
208
209int vpQbDevice::Impl::getInfo(const int &id, const int &max_repeats, std::string &info)
210{
211 // the API methods are called at most (i.e. very unlikely) 'max_repeats' times to guarantee the correct identification of a real fault in the communication
212 int failures = 0;
213 while (failures <= max_repeats) {
214 info = m_device_api->getInfo(&m_file_descriptors.at(m_connected_devices.at(id)), id);
215 if (info == "") {
216 failures++;
217 continue;
218 }
219 break;
220 }
221 return failures;
222}
223
224int vpQbDevice::Impl::getMeasurements(const int &id, const int &max_repeats, std::vector<short int> &currents, std::vector<short int> &positions)
225{
226 // the API methods are called at most (i.e. very unlikely) 'max_repeats' times to guarantee the correct identification of a real fault in the communication
227 int failures = 0;
228 currents.resize(2);
229 positions.resize(3);
230 std::vector<short int> measurements(5, 0); // required by 'getMeasurements()'
231 while (failures <= max_repeats) {
232 if (m_device_api->getMeasurements(&m_file_descriptors.at(m_connected_devices.at(id)), id, measurements) < 0) {
233 failures++;
234 continue;
235 }
236 std::copy(measurements.begin(), measurements.begin()+2, currents.begin());
237 std::copy(measurements.begin()+2, measurements.end(), positions.begin());
238 break;
239 }
240 return failures;
241}
242
243int vpQbDevice::Impl::getParameters(const int &id, std::vector<int> &limits, std::vector<int> &resolutions)
244{
245 std::vector<int> input_mode = {-1};
246 std::vector<int> control_mode = {-1};
247 m_device_api->getParameters(&m_file_descriptors.at(m_connected_devices.at(id)), id, input_mode, control_mode, resolutions, limits);
248 if (!input_mode.front() && !control_mode.front()) { // both input and control modes equals 0 are required, i.e. respectively USB connected and position controlled
249 return 0;
250 }
251 return -1;
252}
253
254int vpQbDevice::Impl::getPositions(const int &id, const int &max_repeats, std::vector<short int> &positions)
255{
256 // the API methods are called at most (i.e. very unlikely) 'max_repeats' times to guarantee the correct identification of a real fault in the communication
257 int failures = 0;
258 positions.resize(3); // required by 'getPositions()'
259 std::lock_guard<std::mutex> serial_lock(*m_serial_protectors.at(m_connected_devices.at(id)));
260 while (failures <= max_repeats) {
261 if (m_device_api->getPositions(&m_file_descriptors.at(m_connected_devices.at(id)), id, positions) < 0) {
262 failures++;
263 continue;
264 }
265 break;
266 }
267 return failures;
268}
269
270int vpQbDevice::Impl::getSerialPortsAndDevices(const int &max_repeats)
271{
272 std::map<int, std::string> connected_devices;
273 std::array<char[255], 10> serial_ports;
274 int serial_ports_number = m_device_api->getSerialPorts(serial_ports);
275
276 for (size_t i=0; i< static_cast<size_t>(serial_ports_number); i++) {
277 int failures = 0;
278 while (failures <= max_repeats) {
279 if (open(serial_ports.at(i)) != 0) {
280 failures++;
281 continue;
282 }
283 break;
284 }
285 if (failures >= max_repeats) {
286 continue;
287 }
288
289 // 'serial_protectors_' is not cleared because of the previously acquired lock, do not do it!
290#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_14)
291 m_serial_protectors.insert(std::make_pair(serial_ports.at(i), std::make_unique<std::mutex>())); // never override
292#else
293 m_serial_protectors.insert(std::make_pair(serial_ports.at(i), std::unique_ptr<std::mutex>(new std::mutex()))); // never override
294#endif
295
296 std::array<char, 255> devices;
297 int devices_number = m_device_api->getDeviceIds(&m_file_descriptors.at(serial_ports.at(i)), devices);
298 for (size_t j=0; j < static_cast<size_t>(devices_number); j++) {
299
300 if (devices.at(j) == 120) {
301 continue; // ID 120 is reserved for dummy board which should not be considered as a connected device
302 }
303 // actually a std::map does not let same-id devices on distinct serial ports
304 connected_devices.insert(std::make_pair(static_cast<int>(devices.at(j)), static_cast<std::string>(serial_ports.at(i))));
305 }
306 }
307
308 std::cout << "has found [" << connected_devices.size() << "] devices connected:" << std::endl;
309 for (auto const &device : connected_devices) {
310 std::cout << " - device [" << device.first << "] connected through [" << device.second << "]" << std::endl;
311 }
312
313 m_connected_devices = connected_devices;
314 return static_cast<int>(m_connected_devices.size());
315}
316
317bool vpQbDevice::Impl::init(const int &id)
318{
319 std::vector<int> encoder_resolutions;
320 std::vector<std::unique_lock<std::mutex>> serial_locks; // need to lock on all the serial resources to scan for new ports/devices
321 for (auto const &mutex : m_serial_protectors) {
322 serial_locks.push_back(std::unique_lock<std::mutex>(*mutex.second));
323 }
324
325 // update connected devices
326 getSerialPortsAndDevices(m_max_repeats);
327
328 if (!isInConnectedSet(id) || !isReliable(isConnected(id, m_max_repeats), m_max_repeats)) {
329 std::cout << "fails while initializing device [" << id << "] because it is not connected." << std::endl;
330 return false;
331 }
332
333 std::vector<int> position_limits;
334
335 if (getParameters(id, position_limits, encoder_resolutions)) {
336 std::cout << "fails while initializing device [" << id << "] because it requires 'USB' input mode and 'Position' control mode." << std::endl;
337 return false;
338 }
339
340 m_position_limits.resize( position_limits.size() );
341 for (size_t i = 0; i < position_limits.size(); i++) {
342 m_position_limits[i] = static_cast<short int>(position_limits[i]);
343 }
344
345 std::string info;
346 int failures = getInfo(id, m_max_repeats, info);
347 if (!isReliable(failures, m_max_repeats)) {
348 std::cout << "has not initialized device [" << id << "] because it cannot get info." << std::endl;
349 return false;
350 }
351
352 std::string sep = "\n";
353 std::string current_limit = "Current limit:";
354 std::vector<std::string> subChain = vpIoTools::splitChain(info, sep);
355 bool current_max_found = false;
356 for (size_t i=0; i < subChain.size(); i++) {
357 if (subChain[i].compare(0, current_limit.size(), current_limit) == 0) {
358 sep = ":";
359 std::vector<std::string> subChainLimit = vpIoTools::splitChain(subChain[i], sep);
360 m_current_max = std::atof(subChainLimit[1].c_str());
361 current_max_found = true;
362 break;
363 }
364 }
365 if (! current_max_found) {
366 std::cout << "has not initialized device [" << id << "] because it cannot get the max current." << std::endl;
367 return false;
368 }
369
370 failures = activate(id, m_max_repeats);
371 if (!isReliable(failures, m_max_repeats)) {
372 std::cout << "has not initialized device [" << id << "] because it cannot activate its motors (please, check the motor positions)." << std::endl;
373 return false;
374 }
375
376 std::string serial_port = m_connected_devices.at(id);
377 std::cout << "Device [" + std::to_string(id) + "] connected on port [" << serial_port << "] initialization succeeds." << std::endl;
378
379 return true;
380}
381
382int vpQbDevice::Impl::isActive(const int &id, const int &max_repeats, bool &status)
383{
384 // the API methods are called at most (i.e. very unlikely) 'max_repeats' times to guarantee the correct identification of a real fault in the communication
385 int failures = 0;
386 status = false;
387 while (failures <= max_repeats) {
388 if (!m_device_api->getStatus(&m_file_descriptors.at(m_connected_devices.at(id)), id, status)) {
389 failures++;
390 continue;
391 }
392 break;
393 }
394 return failures;
395}
396
397int vpQbDevice::Impl::isConnected(const int &id, const int &max_repeats)
398{
399 // the API methods are called at most (i.e. very unlikely) 'max_repeats' times to guarantee the correct identification of a real fault in the communication
400 int failures = 0;
401 while (failures <= max_repeats) {
402 if (!m_device_api->getStatus(&m_file_descriptors.at(m_connected_devices.at(id)), id)) {
403 failures++;
404 continue;
405 }
406 break;
407 }
408 return failures;
409}
410
411int vpQbDevice::Impl::open(const std::string &serial_port)
412{
413#if (defined(__APPLE__) && defined(__MACH__))
414 if (!std::regex_match(serial_port, std::regex("/dev/tty.usbserial-[[:digit:]]+"))) {
415 std::cout << "vpQbDevice fails while opening [" << serial_port << "] because it does not match the expected pattern [/dev/tty.usbserial-*]." << std::endl;
416 return -1;
417 }
418#elif defined(__unix__) || defined(__unix)
419 if (!std::regex_match(serial_port, std::regex("/dev/ttyUSB[[:digit:]]+"))) {
420 std::cout << "vpQbDevice fails while opening [" << serial_port << "] because it does not match the expected pattern [/dev/ttyUSB*]." << std::endl;
421 return -1;
422 }
423#elif defined(_WIN32)
424 if (!std::regex_match(serial_port, std::regex("COM[[:digit:]]+"))) {
425 std::cout << "vpQbDevice fails while opening [" << serial_port << "] because it does not match the expected pattern [COM*]." << std::endl;
426 return -1;
427 }
428#endif
429
430 if (isInOpenMap(serial_port)) {
431 std::cout << "vpQbDevice already handles [" << serial_port << "]." << std::endl;
432 return 0; // no error: the communication is open anyway
433 }
434
435 m_device_api->open(&m_file_descriptors[serial_port], serial_port); // also create a pair in the map
436 if(m_file_descriptors.at(serial_port).file_handle == INVALID_HANDLE_VALUE) {
437 std::cout << "vpQbDevice fails while opening [" << serial_port << "] and sets errno [" << strerror(errno) << "]." << std::endl;
438 // remove file descriptor entry
439 m_file_descriptors.erase(serial_port);
440 return -1;
441 }
442
443 std::cout << "Connect qb device to [" << serial_port << "]." << std::endl;
444 return 0;
445}
446
447int vpQbDevice::Impl::setCommandsAndWait(const int &id, const int &max_repeats, std::vector<short int> &commands)
448{
449 // the API methods are called at most (i.e. very unlikely) 'max_repeats' times to guarantee the correct identification of a real fault in the communication
450 int failures = 0;
451 commands.resize(2); // required by 'setCommandsAndWait()'
452 while (failures <= max_repeats) {
453 if (m_device_api->setCommandsAndWait(&m_file_descriptors.at(m_connected_devices.at(id)), id, commands) < 0) {
454 failures++;
455 continue;
456 }
457 break;
458 }
459 return failures;
460}
461
462int vpQbDevice::Impl::setCommandsAsync(const int &id, std::vector<short int> &commands)
463{
464 // qbhand sets only inputs.at(0), but setCommandsAsync expects two-element vector (ok for both qbhand and qbmove)
465 commands.resize(2); // required by 'setCommandsAsync()'
466 std::lock_guard<std::mutex> serial_lock(*m_serial_protectors.at(m_connected_devices.at(id)));
467 m_device_api->setCommandsAsync(&m_file_descriptors.at(m_connected_devices.at(id)), id, commands);
468 return 0; // note that this is a non reliable method
469}
470#endif // DOXYGEN_SHOULD_SKIP_THIS
471
477 : m_impl(new Impl()), m_max_repeats(1), m_init_done(false)
478{
479 setMaxRepeats(2);
480}
481
487{
488 delete m_impl;
489}
490
499int vpQbDevice::activate(const int &id, const bool &command, const int &max_repeats)
500{
501 return m_impl->activate(id, command, max_repeats);
502}
503
510int vpQbDevice::activate(const int &id, const int &max_repeats)
511{
512 return m_impl->activate(id, max_repeats);
513}
514
521bool vpQbDevice::close(const std::string &serial_port)
522{
523 return m_impl->close(serial_port);
524}
525
532int vpQbDevice::deactivate(const int &id, const int &max_repeats)
533{
534 return m_impl->deactivate(id, max_repeats);
535}
536
541{
542 return m_impl->getCurrentMax();
543}
544
555int vpQbDevice::getCurrents(const int &id, const int &max_repeats, std::vector<short int> &currents)
556{
557 return m_impl->getCurrents(id, max_repeats, currents);
558}
559
568int vpQbDevice::getInfo(const int &id, const int &max_repeats, std::string &info)
569{
570 return m_impl->getInfo(id, max_repeats, info);
571}
572
587int vpQbDevice::getMeasurements(const int &id, const int &max_repeats, std::vector<short int> &currents, std::vector<short int> &positions)
588{
589 return m_impl->getMeasurements(id, max_repeats, currents, positions);
590}
591
604int vpQbDevice::getParameters(const int &id, std::vector<int> &limits, std::vector<int> &resolutions)
605{
606 return m_impl->getParameters(id, limits, resolutions);
607}
608
612std::vector<short int> vpQbDevice::getPositionLimits() const
613{
614 return m_impl->getPositionLimits();
615}
616
628int vpQbDevice::getPositions(const int &id, const int &max_repeats, std::vector<short int> &positions)
629{
630 return m_impl->getPositions(id, max_repeats, positions);
631}
632
643int vpQbDevice::getSerialPortsAndDevices(const int &max_repeats)
644{
645 return m_impl->getSerialPortsAndDevices(max_repeats);
646}
647
655bool vpQbDevice::init(const int &id)
656{
657 bool ret = m_impl->init(id);
658
659 if (ret) {
660 m_init_done = true;
661 }
662 return ret;
663}
664
672int vpQbDevice::isActive(const int &id, const int &max_repeats, bool &status)
673{
674 return m_impl->isActive(id, max_repeats, status);
675}
676
683int vpQbDevice::isConnected(const int &id, const int &max_repeats)
684{
685 return m_impl->isConnected(id, max_repeats);
686}
687
695{
696 return m_impl->isInConnectedSet(id);
697}
698
705bool vpQbDevice::isInOpenMap(const std::string &serial_port)
706{
707 return m_impl->isInOpenMap(serial_port);
708}
709
716bool vpQbDevice::isReliable(int const &failures, int const &max_repeats)
717{
718 return m_impl->isReliable(failures, max_repeats);
719}
720
728int vpQbDevice::open(const std::string &serial_port)
729{
730 return m_impl->open(serial_port);
731}
732
742int vpQbDevice::setCommandsAndWait(const int &id, const int &max_repeats, std::vector<short int> &commands)
743{
744 return m_impl->setCommandsAndWait(id, max_repeats, commands);
745}
746
755int vpQbDevice::setCommandsAsync(const int &id, std::vector<short int> &commands)
756{
757 return m_impl->setCommandsAsync(id, commands);
758}
759
763void vpQbDevice::setMaxRepeats(const int &max_repeats) {
764 m_max_repeats = max_repeats;
765 m_impl->setMaxRepeats(m_max_repeats);
766}
767
768#endif
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1900
virtual int deactivate(const int &id, const int &max_repeats)
Definition: vpQbDevice.cpp:532
bool isReliable(int const &failures, int const &max_repeats)
Definition: vpQbDevice.cpp:716
virtual bool isInOpenMap(const std::string &serial_port)
Definition: vpQbDevice.cpp:705
double getCurrentMax() const
Definition: vpQbDevice.cpp:540
virtual int getSerialPortsAndDevices(const int &max_repeats)
Definition: vpQbDevice.cpp:643
virtual bool isInConnectedSet(const int &id)
Definition: vpQbDevice.cpp:694
virtual bool init(const int &id)
Definition: vpQbDevice.cpp:655
int isConnected(const int &id, const int &max_repeats)
Definition: vpQbDevice.cpp:683
int m_max_repeats
Max number of trials to send a command.
Definition: vpQbDevice.h:114
virtual int getCurrents(const int &id, const int &max_repeats, std::vector< short int > &currents)
Definition: vpQbDevice.cpp:555
virtual bool close(const std::string &serial_port)
Definition: vpQbDevice.cpp:521
virtual int getMeasurements(const int &id, const int &max_repeats, std::vector< short int > &currents, std::vector< short int > &positions)
Definition: vpQbDevice.cpp:587
virtual int activate(const int &id, const bool &command, const int &max_repeats)
Definition: vpQbDevice.cpp:499
virtual int getParameters(const int &id, std::vector< int > &limits, std::vector< int > &resolutions)
Definition: vpQbDevice.cpp:604
std::vector< short int > getPositionLimits() const
Definition: vpQbDevice.cpp:612
virtual int getPositions(const int &id, const int &max_repeats, std::vector< short int > &positions)
Definition: vpQbDevice.cpp:628
virtual int getInfo(const int &id, const int &max_repeats, std::string &info)
Definition: vpQbDevice.cpp:568
void setMaxRepeats(const int &max_repeats)
Definition: vpQbDevice.cpp:763
virtual ~vpQbDevice()
Definition: vpQbDevice.cpp:486
virtual int setCommandsAndWait(const int &id, const int &max_repeats, std::vector< short int > &commands)
Definition: vpQbDevice.cpp:742
virtual int setCommandsAsync(const int &id, std::vector< short int > &commands)
Definition: vpQbDevice.cpp:755
virtual int isActive(const int &id, const int &max_repeats, bool &status)
Definition: vpQbDevice.cpp:672
virtual int open(const std::string &serial_port)
Definition: vpQbDevice.cpp:728
bool m_init_done
Flag used to indicate if the device is initialized.
Definition: vpQbDevice.h:115