Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | Static Private Attributes
sick_tim::SickTimCommonUsb Class Reference

#include <sick_tim_common_usb.h>

Inheritance diagram for sick_tim::SickTimCommonUsb:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 SickTimCommonUsb (AbstractParser *parser)
virtual ~SickTimCommonUsb ()

Protected Member Functions

virtual int close_device ()
virtual int get_datagram (unsigned char *receiveBuffer, int bufferSize, int *actual_length)
 Read a datagram from the device.
virtual int init_device ()
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.

Private Member Functions

void freeSOPASDeviceList (libusb_device **list)
ssize_t getSOPASDeviceList (libusb_context *ctx, uint16_t vendorID, uint16_t productID, libusb_device ***list)
void printSOPASDeviceInformation (ssize_t numberOfDevices, libusb_device **devices)
void printUSBDeviceDetails (struct libusb_device_descriptor desc)
void printUSBInterfaceDetails (libusb_device *device)

Private Attributes

libusb_context * ctx_
libusb_device_handle * device_handle_
libusb_device ** devices_
ssize_t numberOfDevices_

Static Private Attributes

static const unsigned int USB_TIMEOUT = 1000

Detailed Description

Definition at line 52 of file sick_tim_common_usb.h.


Constructor & Destructor Documentation

Definition at line 44 of file sick_tim_common_usb.cpp.

Definition at line 49 of file sick_tim_common_usb.cpp.


Member Function Documentation

int sick_tim::SickTimCommonUsb::close_device ( ) [protected, virtual]

Implements sick_tim::SickTimCommon.

Definition at line 55 of file sick_tim_common_usb.cpp.

void sick_tim::SickTimCommonUsb::freeSOPASDeviceList ( libusb_device **  list) [private]

Definition at line 152 of file sick_tim_common_usb.cpp.

int sick_tim::SickTimCommonUsb::get_datagram ( unsigned char *  receiveBuffer,
int  bufferSize,
int *  actual_length 
) [protected, virtual]

Read a datagram from the device.

Parameters:
[in]receiveBufferdata buffer to fill
[in]bufferSizemax data size to write to buffer (result should be 0 terminated)
[out]actual_lengththe actual amount of data written

Implements sick_tim::SickTimCommon.

Definition at line 406 of file sick_tim_common_usb.cpp.

ssize_t sick_tim::SickTimCommonUsb::getSOPASDeviceList ( libusb_context *  ctx,
uint16_t  vendorID,
uint16_t  productID,
libusb_device ***  list 
) [private]

Returns a list of USB devices currently attached to the system and matching the given vendorID and productID.

Definition at line 90 of file sick_tim_common_usb.cpp.

int sick_tim::SickTimCommonUsb::init_device ( ) [protected, virtual]

Implements sick_tim::SickTimCommon.

Definition at line 316 of file sick_tim_common_usb.cpp.

void sick_tim::SickTimCommonUsb::printSOPASDeviceInformation ( ssize_t  numberOfDevices,
libusb_device **  devices 
) [private]

Print the USB device information of the connected TIM3xx devices to the console.

Definition at line 230 of file sick_tim_common_usb.cpp.

void sick_tim::SickTimCommonUsb::printUSBDeviceDetails ( struct libusb_device_descriptor  desc) [private]

Definition at line 168 of file sick_tim_common_usb.cpp.

void sick_tim::SickTimCommonUsb::printUSBInterfaceDetails ( libusb_device *  device) [private]

Definition at line 178 of file sick_tim_common_usb.cpp.

int sick_tim::SickTimCommonUsb::sendSOPASCommand ( const char *  request,
std::vector< unsigned char > *  reply 
) [protected, virtual]

Send a SOPAS command to the device and print out the response to the console.

Implements sick_tim::SickTimCommon.

Definition at line 263 of file sick_tim_common_usb.cpp.


Member Data Documentation

libusb_context* sick_tim::SickTimCommonUsb::ctx_ [private]

Definition at line 84 of file sick_tim_common_usb.h.

libusb_device_handle* sick_tim::SickTimCommonUsb::device_handle_ [private]

Definition at line 87 of file sick_tim_common_usb.h.

libusb_device** sick_tim::SickTimCommonUsb::devices_ [private]

Definition at line 86 of file sick_tim_common_usb.h.

Definition at line 85 of file sick_tim_common_usb.h.

const unsigned int sick_tim::SickTimCommonUsb::USB_TIMEOUT = 1000 [static, private]

Definition at line 74 of file sick_tim_common_usb.h.


The documentation for this class was generated from the following files:


sick_tim
Author(s): Jochen Sprickerhof , Martin Günther
autogenerated on Thu Aug 27 2015 15:14:34