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