Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
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 BEGIN_VISP_NAMESPACE
47 #ifndef DOXYGEN_SHOULD_SKIP_THIS
48 class vpQbDevice::Impl
49 {
50 public:
51  Impl() : Impl(std::make_shared<qb_device_driver::qbDeviceAPI>()) { }
52  Impl(std::shared_ptr<qb_device_driver::qbDeviceAPI> device_api)
53  : m_serial_protectors(), m_connected_devices(), m_position_limits(2), m_device_api(device_api),
54  m_file_descriptors(), m_max_repeats(1), m_current_max(750.)
55  {
56  // Default values updated after a call to init()
57  m_position_limits[0] = 0;
58  m_position_limits[1] = 19000;
59  }
60 
61  virtual ~Impl()
62  {
63  for (auto it = m_file_descriptors.begin(); it != m_file_descriptors.end();) {
64  if (close(it->first)) {
65  it = m_file_descriptors.erase(it);
66  }
67  else {
68  ++it;
69  }
70  }
71  }
72 
73  virtual int activate(const int &id, const bool &command, const int &max_repeats);
74  virtual int activate(const int &id, const int &max_repeats) { return activate(id, true, max_repeats); }
75 
76  virtual bool close(const std::string &serial_port);
77 
78  virtual int deactivate(const int &id, const int &max_repeats) { return activate(id, false, max_repeats); }
79 
80  inline double getCurrentMax() const { return m_current_max; }
81 
82  virtual int getCurrents(const int &id, const int &max_repeats, std::vector<short int> &currents);
83  virtual int getInfo(const int &id, const int &max_repeats, std::string &info);
84  virtual int getMeasurements(const int &id, const int &max_repeats, std::vector<short int> &currents,
85  std::vector<short int> &positions);
86  virtual int getParameters(const int &id, std::vector<int> &limits, std::vector<int> &resolutions);
87 
88  std::vector<short int> getPositionLimits() const { return m_position_limits; }
89 
90  virtual int getPositions(const int &id, const int &max_repeats, std::vector<short int> &positions);
91  virtual int getSerialPortsAndDevices(const int &max_repeats);
92  virtual bool init(const int &id);
93  virtual int isActive(const int &id, const int &max_repeats, bool &status);
94 
95  virtual int isConnected(const int &id, const int &max_repeats);
96 
97  virtual bool isInConnectedSet(const int &id) { return (m_connected_devices.count(id) ? true : false); }
98 
99  virtual bool isInOpenMap(const std::string &serial_port)
100  {
101  return (m_file_descriptors.count(serial_port) ? true : false);
102  }
103 
104  inline bool isReliable(int const &failures, int const &max_repeats)
105  {
106  return failures >= 0 && failures <= max_repeats;
107  }
108  virtual int open(const std::string &serial_port);
109 
110  virtual int setCommandsAndWait(const int &id, const int &max_repeats, std::vector<short int> &commands);
111  virtual int setCommandsAsync(const int &id, std::vector<short int> &commands);
112 
113  void setMaxRepeats(const int &max_repeats) { m_max_repeats = max_repeats; }
114 
115 public:
116  std::map<std::string, std::unique_ptr<std::mutex> >
117  m_serial_protectors; // only callbacks must lock the serial resources
118  std::map<int, std::string> m_connected_devices;
119 
120 protected:
121 #if (defined(_WIN32) || defined(_WIN64))
122  std::unique_ptr<std::mutex> m_mutex_dummy; // FS: cannot build without this line with msvc
123 #endif
124  std::vector<short int> m_position_limits; // min and max position values in ticks
125  std::shared_ptr<qb_device_driver::qbDeviceAPI> m_device_api;
126  std::map<std::string, comm_settings> m_file_descriptors;
127  int m_max_repeats;
128  double m_current_max;
129 };
130 
131 int vpQbDevice::Impl::activate(const int &id, const bool &command, const int &max_repeats)
132 {
133  std::string command_prefix = command ? "" : "de";
134  bool status = false;
135  int failures = 0;
136 
137  failures = isActive(id, max_repeats, status);
138  if (status != command) {
139  m_device_api->activate(&m_file_descriptors.at(m_connected_devices.at(id)), id, command);
140  failures = std::max<int>(failures, isActive(id, max_repeats, status));
141  if (status != command) {
142  std::cout << "Device [" << id << "] fails on " << command_prefix << "activation." << std::endl;
143  ;
144  return -1;
145  }
146  std::cout << "Device [" << id << "] motors have been " << command_prefix << "activated!" << std::endl;
147  return failures;
148  }
149  std::cout << "Device [" << id << "] motors were already " << command_prefix << "activated!" << std::endl;
150  return failures;
151 }
152 
153 bool vpQbDevice::Impl::close(const std::string &serial_port)
154 {
155  if (!isInOpenMap(serial_port)) {
156  std::cout << "has not handled [" << serial_port << "]." << std::endl;
157  return false; // no error: the communication is close anyway
158  }
159 
160  for (auto const &device : m_connected_devices) {
161  if (device.second == serial_port) {
162  deactivate(device.first, m_max_repeats);
163  m_connected_devices.erase(device.first);
164  break;
165  }
166  }
167 
168  m_device_api->close(&m_file_descriptors.at(serial_port));
169 
170  // Note that m_file_descriptors.erase(serial_port) is done in the destructor.
171  // Cannot be done here since the iterator that is used in the destructor would be lost
172 
173  std::cout << "does not handle [" << serial_port << "] anymore." << std::endl;
174  return true;
175 }
176 
177 int vpQbDevice::Impl::getCurrents(const int &id, const int &max_repeats, std::vector<short int> &currents)
178 {
179  // the API methods are called at most (i.e. very unlikely) 'max_repeats' times to guarantee the correct identification
180  // of a real fault in the communication
181  int failures = 0;
182  currents.resize(2); // required by 'getCurrents()'
183  std::lock_guard<std::mutex> serial_lock(*m_serial_protectors.at(m_connected_devices.at(id)));
184  while (failures <= max_repeats) {
185  if (m_device_api->getCurrents(&m_file_descriptors.at(m_connected_devices.at(id)), id, currents) < 0) {
186  failures++;
187  continue;
188  }
189  break;
190  }
191  return failures;
192 }
193 
194 int vpQbDevice::Impl::getInfo(const int &id, const int &max_repeats, std::string &info)
195 {
196  // the API methods are called at most (i.e. very unlikely) 'max_repeats' times to guarantee the correct identification
197  // of a real fault in the communication
198  int failures = 0;
199  while (failures <= max_repeats) {
200  info = m_device_api->getInfo(&m_file_descriptors.at(m_connected_devices.at(id)), id);
201  if (info == "") {
202  failures++;
203  continue;
204  }
205  break;
206  }
207  return failures;
208 }
209 
210 int vpQbDevice::Impl::getMeasurements(const int &id, const int &max_repeats, std::vector<short int> &currents,
211  std::vector<short int> &positions)
212 {
213  // the API methods are called at most (i.e. very unlikely) 'max_repeats' times to guarantee the correct identification
214  // of a real fault in the communication
215  int failures = 0;
216  currents.resize(2);
217  positions.resize(3);
218  std::vector<short int> measurements(5, 0); // required by 'getMeasurements()'
219  while (failures <= max_repeats) {
220  if (m_device_api->getMeasurements(&m_file_descriptors.at(m_connected_devices.at(id)), id, measurements) < 0) {
221  failures++;
222  continue;
223  }
224  std::copy(measurements.begin(), measurements.begin() + 2, currents.begin());
225  std::copy(measurements.begin() + 2, measurements.end(), positions.begin());
226  break;
227  }
228  return failures;
229 }
230 
231 int vpQbDevice::Impl::getParameters(const int &id, std::vector<int> &limits, std::vector<int> &resolutions)
232 {
233  std::vector<int> input_mode = { -1 };
234  std::vector<int> control_mode = { -1 };
235  m_device_api->getParameters(&m_file_descriptors.at(m_connected_devices.at(id)), id, input_mode, control_mode,
236  resolutions, limits);
237  if (!input_mode.front() && !control_mode.front()) { // both input and control modes equals 0 are required, i.e.
238  // respectively USB connected and position controlled
239  return 0;
240  }
241  return -1;
242 }
243 
244 int vpQbDevice::Impl::getPositions(const int &id, const int &max_repeats, std::vector<short int> &positions)
245 {
246  // the API methods are called at most (i.e. very unlikely) 'max_repeats' times to guarantee the correct identification
247  // of a real fault in the communication
248  int failures = 0;
249  positions.resize(3); // required by 'getPositions()'
250  std::lock_guard<std::mutex> serial_lock(*m_serial_protectors.at(m_connected_devices.at(id)));
251  while (failures <= max_repeats) {
252  if (m_device_api->getPositions(&m_file_descriptors.at(m_connected_devices.at(id)), id, positions) < 0) {
253  failures++;
254  continue;
255  }
256  break;
257  }
258  return failures;
259 }
260 
261 int vpQbDevice::Impl::getSerialPortsAndDevices(const int &max_repeats)
262 {
263  std::map<int, std::string> connected_devices;
264  std::array<char[255], 10> serial_ports;
265  int serial_ports_number = m_device_api->getSerialPorts(serial_ports);
266 
267  for (size_t i = 0; i < static_cast<size_t>(serial_ports_number); i++) {
268  int failures = 0;
269  while (failures <= max_repeats) {
270  if (open(serial_ports.at(i)) != 0) {
271  failures++;
272  continue;
273  }
274  break;
275  }
276  if (failures >= max_repeats) {
277  continue;
278  }
279 
280  // 'serial_protectors_' is not cleared because of the previously acquired lock, do not do it!
281  // Check if std:c++14 or higher
282 #if ((__cplusplus >= 201402L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201402L)))
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 END_VISP_NAMESPACE
742 #endif
static std::vector< std::string > splitChain(const std::string &chain, const std::string &sep)
Definition: vpIoTools.cpp:1661
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:113
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:114