39 #include <visp3/core/vpConfig.h> 40 #ifdef VISP_HAVE_QBDEVICE 44 #include <qb_device_driver.h> 46 #include <visp3/robot/vpQbDevice.h> 47 #include <visp3/core/vpIoTools.h> 49 #ifndef DOXYGEN_SHOULD_SKIP_THIS 50 class vpQbDevice::Impl
54 : Impl(
std::make_shared<qb_device_driver::qbDeviceAPI>())
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(),
63 m_position_limits[0] = 0;
64 m_position_limits[1] = 19000;
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);
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)
82 return activate(
id,
true, max_repeats);
85 virtual bool close(
const std::string &serial_port);
87 virtual int deactivate(
const int &
id,
const int &max_repeats)
89 return activate(
id,
false, max_repeats);
96 virtual int getCurrents(
const int &
id,
const int &max_repeats, std::vector<short int> ¤ts);
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> ¤ts, std::vector<short int> &positions);
99 virtual int getParameters(
const int &
id, std::vector<int> &limits, std::vector<int> &resolutions);
103 return m_position_limits;
106 virtual int getPositions(
const int &
id,
const int &max_repeats, std::vector<short int> &positions);
108 virtual bool init(
const int &
id);
109 virtual int isActive(
const int &
id,
const int &max_repeats,
bool &status);
111 virtual int isConnected(
const int &
id,
const int &max_repeats);
115 return (m_connected_devices.count(
id) ?
true :
false);
118 virtual bool isInOpenMap(
const std::string &serial_port)
120 return (m_file_descriptors.count(serial_port) ?
true :
false);
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);
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);
134 std::map<std::string, std::unique_ptr<std::mutex>> m_serial_protectors;
135 std::map<int, std::string> m_connected_devices;
138 #if (defined(_WIN32) || defined (_WIN64)) 139 std::unique_ptr<std::mutex> m_mutex_dummy;
141 std::vector<short int> m_position_limits;
142 std::shared_ptr<qb_device_driver::qbDeviceAPI> m_device_api;
143 std::map<std::string, comm_settings> m_file_descriptors;
145 double m_current_max;
148 int vpQbDevice::Impl::activate(
const int &
id,
const bool &command,
const int &max_repeats)
150 std::string command_prefix = command ?
"" :
"de";
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;;
162 std::cout <<
"Device [" <<
id <<
"] motors have been " << command_prefix <<
"activated!" << std::endl;
165 std::cout <<
"Device [" <<
id <<
"] motors were already " << command_prefix <<
"activated!" << std::endl;
169 bool vpQbDevice::Impl::close(
const std::string &serial_port)
172 std::cout <<
"has not handled [" << serial_port <<
"]." << std::endl;
176 for (
auto const &device : m_connected_devices) {
177 if (device.second == serial_port) {
179 m_connected_devices.erase(device.first);
184 m_device_api->close(&m_file_descriptors.at(serial_port));
189 std::cout <<
"does not handle [" << serial_port <<
"] anymore." << std::endl;
193 int vpQbDevice::Impl::getCurrents(
const int &
id,
const int &max_repeats, std::vector<short int> ¤ts)
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) {
209 int vpQbDevice::Impl::getInfo(
const int &
id,
const int &max_repeats, std::string &info)
213 while (failures <= max_repeats) {
214 info = m_device_api->getInfo(&m_file_descriptors.at(m_connected_devices.at(
id)),
id);
224 int vpQbDevice::Impl::getMeasurements(
const int &
id,
const int &max_repeats, std::vector<short int> ¤ts, std::vector<short int> &positions)
230 std::vector<short int> measurements(5, 0);
231 while (failures <= max_repeats) {
232 if (m_device_api->getMeasurements(&m_file_descriptors.at(m_connected_devices.at(
id)),
id, measurements) < 0) {
236 std::copy(measurements.begin(), measurements.begin()+2, currents.begin());
237 std::copy(measurements.begin()+2, measurements.end(), positions.begin());
243 int vpQbDevice::Impl::getParameters(
const int &
id, std::vector<int> &limits, std::vector<int> &resolutions)
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()) {
254 int vpQbDevice::Impl::getPositions(
const int &
id,
const int &max_repeats, std::vector<short int> &positions)
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) {
270 int vpQbDevice::Impl::getSerialPortsAndDevices(
const int &max_repeats)
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);
276 for (
size_t i=0; i< static_cast<size_t>(serial_ports_number); i++) {
278 while (failures <= max_repeats) {
279 if (
open(serial_ports.at(i)) != 0) {
285 if (failures >= max_repeats) {
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>()));
293 m_serial_protectors.insert(std::make_pair(serial_ports.at(i), std::unique_ptr<std::mutex>(
new std::mutex())));
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++) {
300 if (devices.at(j) == 120) {
304 connected_devices.insert(std::make_pair(static_cast<int>(devices.at(j)), static_cast<std::string>(serial_ports.at(i))));
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;
313 m_connected_devices = connected_devices;
314 return static_cast<int>(m_connected_devices.size());
317 bool vpQbDevice::Impl::init(
const int &
id)
319 std::vector<int> encoder_resolutions;
320 std::vector<std::unique_lock<std::mutex>> serial_locks;
321 for (
auto const &mutex : m_serial_protectors) {
322 serial_locks.push_back(std::unique_lock<std::mutex>(*mutex.second));
329 std::cout <<
"fails while initializing device [" <<
id <<
"] because it is not connected." << std::endl;
333 std::vector<int> position_limits;
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;
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]);
348 std::cout <<
"has not initialized device [" <<
id <<
"] because it cannot get info." << std::endl;
352 std::string sep =
"\n";
353 std::string current_limit =
"Current limit:";
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) {
360 m_current_max = std::atof(subChainLimit[1].c_str());
361 current_max_found =
true;
365 if (! current_max_found) {
366 std::cout <<
"has not initialized device [" <<
id <<
"] because it cannot get the max current." << std::endl;
372 std::cout <<
"has not initialized device [" <<
id <<
"] because it cannot activate its motors (please, check the motor positions)." << std::endl;
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;
382 int vpQbDevice::Impl::isActive(
const int &
id,
const int &max_repeats,
bool &status)
387 while (failures <= max_repeats) {
388 if (!m_device_api->getStatus(&m_file_descriptors.at(m_connected_devices.at(
id)),
id, status)) {
397 int vpQbDevice::Impl::isConnected(
const int &
id,
const int &max_repeats)
401 while (failures <= max_repeats) {
402 if (!m_device_api->getStatus(&m_file_descriptors.at(m_connected_devices.at(
id)),
id)) {
411 int vpQbDevice::Impl::open(
const std::string &serial_port)
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;
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;
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;
431 std::cout <<
"vpQbDevice already handles [" << serial_port <<
"]." << std::endl;
435 m_device_api->open(&m_file_descriptors[serial_port], serial_port);
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;
439 m_file_descriptors.erase(serial_port);
443 std::cout <<
"Connect qb device to [" << serial_port <<
"]." << std::endl;
447 int vpQbDevice::Impl::setCommandsAndWait(
const int &
id,
const int &max_repeats, std::vector<short int> &commands)
452 while (failures <= max_repeats) {
453 if (m_device_api->setCommandsAndWait(&m_file_descriptors.at(m_connected_devices.at(
id)),
id, commands) < 0) {
462 int vpQbDevice::Impl::setCommandsAsync(
const int &
id, std::vector<short int> &commands)
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);
470 #endif // DOXYGEN_SHOULD_SKIP_THIS 501 return m_impl->activate(
id, command, max_repeats);
512 return m_impl->activate(
id, max_repeats);
523 return m_impl->close(serial_port);
534 return m_impl->deactivate(
id, max_repeats);
542 return m_impl->getCurrentMax();
557 return m_impl->getCurrents(
id, max_repeats, currents);
570 return m_impl->getInfo(
id, max_repeats, info);
589 return m_impl->getMeasurements(
id, max_repeats, currents, positions);
606 return m_impl->getParameters(
id, limits, resolutions);
614 return m_impl->getPositionLimits();
630 return m_impl->getPositions(
id, max_repeats, positions);
645 return m_impl->getSerialPortsAndDevices(max_repeats);
657 bool ret = m_impl->init(
id);
674 return m_impl->isActive(
id, max_repeats, status);
685 return m_impl->isConnected(
id, max_repeats);
696 return m_impl->isInConnectedSet(
id);
707 return m_impl->isInOpenMap(serial_port);
718 return m_impl->isReliable(failures, max_repeats);
730 return m_impl->open(serial_port);
744 return m_impl->setCommandsAndWait(
id, max_repeats, commands);
757 return m_impl->setCommandsAsync(
id, commands);
virtual int isActive(const int &id, const int &max_repeats, bool &status)
virtual int getPositions(const int &id, const int &max_repeats, std::vector< short int > &positions)
virtual int getInfo(const int &id, const int &max_repeats, std::string &info)
virtual int getCurrents(const int &id, const int &max_repeats, std::vector< short int > ¤ts)
bool m_init_done
Flag used to indicate if the device is initialized.
virtual bool close(const std::string &serial_port)
virtual int getParameters(const int &id, std::vector< int > &limits, std::vector< int > &resolutions)
virtual int getMeasurements(const int &id, const int &max_repeats, std::vector< short int > ¤ts, std::vector< short int > &positions)
int m_max_repeats
Max number of trials to send a command.
virtual bool isInConnectedSet(const int &id)
void setMaxRepeats(const int &max_repeats)
std::vector< short int > getPositionLimits() const
virtual int setCommandsAndWait(const int &id, const int &max_repeats, std::vector< short int > &commands)
virtual int getSerialPortsAndDevices(const int &max_repeats)
double getCurrentMax() const
virtual bool isInOpenMap(const std::string &serial_port)
bool isReliable(int const &failures, int const &max_repeats)
int isConnected(const int &id, const int &max_repeats)
virtual int setCommandsAsync(const int &id, std::vector< short int > &commands)
virtual bool init(const int &id)
virtual int activate(const int &id, const bool &command, const int &max_repeats)
virtual int open(const std::string &serial_port)
virtual int deactivate(const int &id, const int &max_repeats)