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