sick_tim_common_usb.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2013, Osnabrück University
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Osnabrück University nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Created on: 24.05.2012
30  *
31  * Authors:
32  * Jochen Sprickerhof <jochen@sprickerhof.de>
33  * Martin Günther <mguenthe@uos.de>
34  *
35  * Based on the TiM communication example by SICK AG.
36  *
37  */
38 
40 
41 namespace sick_tim
42 {
43 
44 SickTimCommonUsb::SickTimCommonUsb(AbstractParser* parser, int device_number) : SickTimCommon(parser),
45  ctx_(NULL), numberOfDevices_(0), devices_(NULL), device_handle_(NULL), device_number_(device_number)
46 {
47 }
48 
50 {
51  stop_scanner();
52  close_device();
53 }
54 
56 {
57  int result = 0;
58  if (device_handle_ != NULL)
59  {
60  /*
61  * Release the interface
62  */
63  result = libusb_release_interface(device_handle_, 0);
64  if (result != 0)
65  printf("LIBUSB - Cannot Release Interface!\n");
66  else
67  printf("LIBUSB - Released Interface.\n");
68 
69  /*
70  * Close the device handle.
71  */
72  libusb_close(device_handle_);
73  }
74 
75  /*
76  * Free the list of the USB devices.
77  */
79 
80  /*
81  * Close the LIBUSB session.
82  */
83  libusb_exit(ctx_);
84  return result;
85 }
86 
90 ssize_t SickTimCommonUsb::getSOPASDeviceList(libusb_context *ctx, uint16_t vendorID, uint16_t productID,
91  libusb_device ***list)
92 {
93  libusb_device **resultDevices = NULL;
94  ssize_t numberOfResultDevices = 0;
95  libusb_device **devices;
96 
97  /*
98  * Get a list of all USB devices connected.
99  */
100  ssize_t numberOfDevices = libusb_get_device_list(ctx, &devices);
101 
102  /*
103  * Iterate through the list of the connected USB devices and search for devices with the given vendorID and productID.
104  */
105  for (ssize_t i = 0; i < numberOfDevices; i++)
106  {
107  struct libusb_device_descriptor desc;
108  int result = libusb_get_device_descriptor(devices[i], &desc);
109  if (result < 0)
110  {
111  ROS_ERROR("LIBUSB - Failed to get device descriptor");
112  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "LIBUSB - Failed to get device descriptor.");
113  continue;
114  }
115 
116  if (desc.idVendor == vendorID && desc.idProduct == 0x5001)
117  {
118  /*
119  * Add the matching device to the function result list and increase the device reference count.
120  */
121  resultDevices = (libusb_device **)realloc(resultDevices, sizeof(libusb_device *) * (numberOfResultDevices + 2));
122  if (resultDevices == NULL)
123  {
124  ROS_ERROR("LIBUSB - Failed to allocate memory for the device result list.");
125  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "LIBUSB - Failed to allocate memory for the device result list.");
126  }
127  else
128  {
129  resultDevices[numberOfResultDevices] = devices[i];
130  resultDevices[numberOfResultDevices + 1] = NULL;
131  libusb_ref_device(devices[i]);
132  numberOfResultDevices++;
133  }
134  }
135  }
136 
137  /*
138  * Free the list of the connected USB devices and decrease the device reference count.
139  */
140  libusb_free_device_list(devices, 1);
141 
142  /*
143  * Prepare the return values of the function.
144  */
145  *list = resultDevices;
146  return numberOfResultDevices;
147 }
148 
149 /*
150  * Free the list of devices obtained from the function 'getSOPASDeviceList'.
151  */
152 void SickTimCommonUsb::freeSOPASDeviceList(libusb_device **list)
153 {
154  if (!list)
155  return;
156 
157  int i = 0;
158  struct libusb_device *dev;
159  while ((dev = list[i++]) != NULL)
160  libusb_unref_device(dev);
161 
162  free(list);
163 }
164 
165 /*
166  * Print the device details such as USB device class, vendor id and product id to the console.
167  */
168 void SickTimCommonUsb::printUSBDeviceDetails(struct libusb_device_descriptor desc)
169 {
170  ROS_INFO("Device Class: 0x%x", desc.bDeviceClass);
171  ROS_INFO("VendorID: 0x%x", desc.idVendor);
172  ROS_INFO("ProductID: 0x%x", desc.idProduct);
173 }
174 
175 /*
176  * Iterate through the the interfaces of the USB device and print out the interface details to the console.
177  */
179 {
180  struct libusb_config_descriptor *config;
181 
182  /*
183  * Get a USB configuration descriptor based on its index.
184  */
185  libusb_get_config_descriptor(device, 0, &config);
186 
187  ROS_INFO("Interfaces: %i", (int)config->bNumInterfaces);
188  ROS_INFO("----------------------------------------");
189 
190  const struct libusb_interface *interface;
191  const struct libusb_interface_descriptor *interface_descriptor;
192  const struct libusb_endpoint_descriptor *endpoint_descriptor;
193 
194  int i, j, k;
195  for (i = 0; i < config->bNumInterfaces; i++)
196  {
197  interface = &config->interface[i];
198  ROS_INFO("Number of alternate settings: %i", interface->num_altsetting);
199 
200  for (j = 0; j < interface->num_altsetting; j++)
201  {
202  interface_descriptor = &interface->altsetting[j];
203 
204  ROS_INFO("Interface number: %i", (int)interface_descriptor->bInterfaceNumber);
205  ROS_INFO("Number of endpoints: %i", (int)interface_descriptor->bNumEndpoints);
206 
207  for (k = 0; k < interface_descriptor->bNumEndpoints; k++)
208  {
209  endpoint_descriptor = &interface_descriptor->endpoint[k];
210  ROS_INFO("Descriptor Type: %i", endpoint_descriptor->bDescriptorType);
211  ROS_INFO("EP Address: %i", endpoint_descriptor->bEndpointAddress);
212  }
213  }
214 
215  if (i < config->bNumInterfaces - 1)
216  {
217  ROS_INFO("----------------------------------------");
218  }
219  }
220 
221  /*
222  * Free the configuration descriptor obtained from 'libusb_get_config_descriptor'
223  */
224  libusb_free_config_descriptor(config);
225 }
226 
230 void SickTimCommonUsb::printSOPASDeviceInformation(ssize_t numberOfDevices, libusb_device** devices)
231 {
232  ssize_t i;
233  for (i = 0; i < numberOfDevices; i++)
234  {
235  struct libusb_device_descriptor desc;
236  int result = libusb_get_device_descriptor(devices[i], &desc);
237  if (result < 0)
238  {
239  ROS_ERROR("LIBUSB - Failed to get device descriptor");
240  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "LIBUSB - Failed to get device descriptor.");
241  continue;
242  }
243  if (result == 0)
244  {
245  ROS_INFO("SICK AG - TIM3XX - [%zu]", (i + 1));
246  ROS_INFO("----------------------------------------");
247  printUSBDeviceDetails(desc);
248  ROS_INFO("----------------------------------------");
249  printUSBInterfaceDetails(devices[i]);
250  ROS_INFO("----------------------------------------");
251  }
252  }
253 
254  if (numberOfDevices == 0)
255  {
256  ROS_INFO("LIBUSB - No SICK TIM device connected.");
257  }
258 }
259 
263 int SickTimCommonUsb::sendSOPASCommand(const char* request, std::vector<unsigned char> * reply)
264 {
265  if (device_handle_ == NULL) {
266  ROS_ERROR("LIBUSB - device not open");
267  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "LIBUSB - device not open.");
268  return ExitError;
269  }
270 
271  int result = 0;
272  unsigned char receiveBuffer[65536];
273 
274  /*
275  * Write a SOPAS variable read request to the device.
276  */
277  ROS_DEBUG("LIBUSB - Write data... %s", request);
278 
279  int actual_length = 0;
280  int requestLength = strlen(request);
281  result = libusb_bulk_transfer(device_handle_, (2 | LIBUSB_ENDPOINT_OUT), (unsigned char*)request, requestLength,
282  &actual_length, 0);
283  if (result != 0 || actual_length != requestLength)
284  {
285  ROS_ERROR("LIBUSB - Write Error: %i.", result);
286  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "LIBUSB - Write Error.");
287  return result;
288  }
289 
290  /*
291  * Read the SOPAS device response with the given timeout.
292  */
293  result = libusb_bulk_transfer(device_handle_, (1 | LIBUSB_ENDPOINT_IN), receiveBuffer, 65535, &actual_length, USB_TIMEOUT);
294  if (result != 0)
295  {
296  ROS_ERROR("LIBUSB - Read Error: %i.", result);
297  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "LIBUSB - Read Error.");
298  return result;
299  }
300 
301  receiveBuffer[actual_length] = 0;
302  ROS_DEBUG("LIBUSB - Read data... %s", receiveBuffer);
303  if(reply) {
304  reply->clear();
305  for(int i = 0; i < actual_length; i++) {
306  reply->push_back(receiveBuffer[i]);
307  }
308  }
309 
310  return result;
311 }
312 
313 /*
314  * provided as a separate method (not inside constructor) so we can return error codes
315  */
317 {
318  /*
319  * Create and initialize a new LIBUSB session.
320  */
321  int result = libusb_init(&ctx_);
322  if (result != 0)
323  {
324  ROS_ERROR("LIBUSB - Initialization failed with the following error code: %i.", result);
325  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "LIBUSB - Initialization failed.");
326  return ExitError;
327  }
328 
329  /*
330  * Set the verbosity level to 3 as suggested in the documentation.
331  */
332  libusb_set_debug(ctx_, 3);
333 
334  /*
335  * Get a list of all SICK TIM3xx devices connected to the USB bus.
336  *
337  * As a shortcut, you can also use the LIBUSB function:
338  * libusb_open_device_with_vid_pid(ctx, 0x19A2, 0x5001).
339  */
340  int vendorID = 0x19A2; // SICK AG
341  int deviceID = 0x5001; // TIM3XX
342  numberOfDevices_ = getSOPASDeviceList(ctx_, vendorID, deviceID, &devices_);
343 
344  /*
345  * If available, open the first SICK TIM3xx device.
346  */
347  if (numberOfDevices_ == 0)
348  {
349  ROS_ERROR("No SICK TiM devices connected!");
350  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "No SICK TiM devices connected!");
351  return ExitError;
352  }
353  else if (numberOfDevices_ <= device_number_)
354  {
355  ROS_ERROR("Device number %d too high, only %zu SICK TiM scanners connected", device_number_, numberOfDevices_);
356  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "Chosen SICK TiM scanner not connected");
357  return ExitError;
358  }
359 
360  /*
361  * Print out the SOPAS device information to the console.
362  */
364 
365  /*
366  * Open the device handle and detach all kernel drivers.
367  */
368  libusb_open(devices_[device_number_], &device_handle_);
369  if (device_handle_ == NULL)
370  {
371  ROS_ERROR("LIBUSB - Cannot open device (permission denied?); please read sick_tim/README.md");
372  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "LIBUSB - Cannot open device (permission denied?); please read sick_tim/README.md");
373  return ExitError;
374  }
375  else
376  {
377  ROS_DEBUG("LIBUSB - Device opened");
378  }
379 
380  if (libusb_kernel_driver_active(device_handle_, 0) == 1)
381  {
382  ROS_DEBUG("LIBUSB - Kernel driver active");
383  if (libusb_detach_kernel_driver(device_handle_, 0) == 0)
384  {
385  ROS_DEBUG("LIBUSB - Kernel driver detached!");
386  }
387  }
388 
389  /*
390  * Claim the interface 0
391  */
392  result = libusb_claim_interface(device_handle_, 0);
393  if (result < 0)
394  {
395  ROS_ERROR("LIBUSB - Cannot claim interface");
396  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "LIBUSB - Cannot claim interface.");
397  return ExitError;
398  }
399  else
400  {
401  ROS_INFO("LIBUSB - Claimed interface");
402  }
403 
404  return ExitSuccess;
405 }
406 
407 int SickTimCommonUsb::get_datagram(unsigned char* receiveBuffer, int bufferSize, int* actual_length)
408 {
409  int result = libusb_bulk_transfer(device_handle_, (1 | LIBUSB_ENDPOINT_IN), receiveBuffer, bufferSize - 1, actual_length,
410  USB_TIMEOUT); // read up to bufferSize - 1 to leave space for \0
411  if (result != 0)
412  {
413  if (result == LIBUSB_ERROR_TIMEOUT)
414  {
415  ROS_WARN("LIBUSB - Read Error: LIBUSB_ERROR_TIMEOUT.");
416  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "LIBUSB - Read Error: LIBUSB_ERROR_TIMEOUT.");
417  *actual_length = 0;
418  return ExitSuccess; // return success with size 0 to continue looping
419  }
420  else
421  {
422  ROS_ERROR("LIBUSB - Read Error: %i.", result);
423  diagnostics_.broadcast(diagnostic_msgs::DiagnosticStatus::ERROR, "LIBUSB - Read Error.");
424  return result; // return failure to exit node
425  }
426  }
427 
428  receiveBuffer[*actual_length] = 0;
429  return ExitSuccess;
430 }
431 
432 } /* namespace sick_tim */
void printSOPASDeviceInformation(ssize_t numberOfDevices, libusb_device **devices)
void printUSBDeviceDetails(struct libusb_device_descriptor desc)
#define ROS_WARN(...)
virtual int get_datagram(unsigned char *receiveBuffer, int bufferSize, int *actual_length)
Read a datagram from the device.
#define ROS_INFO(...)
virtual int sendSOPASCommand(const char *request, std::vector< unsigned char > *reply)
Send a SOPAS command to the device and print out the response to the console.
libusb_device_handle * device_handle_
ssize_t getSOPASDeviceList(libusb_context *ctx, uint16_t vendorID, uint16_t productID, libusb_device ***list)
diagnostic_updater::Updater diagnostics_
void printUSBInterfaceDetails(libusb_device *device)
SickTimCommonUsb(AbstractParser *parser, int device_number)
void broadcast(int lvl, const std::string msg)
static const unsigned int USB_TIMEOUT
void freeSOPASDeviceList(libusb_device **list)
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


sick_tim
Author(s): Jochen Sprickerhof , Martin Günther , Sebastian Pütz
autogenerated on Tue May 7 2019 03:13:47