$search

sick_tim3xx::SickTim3xx Class Reference

List of all members.

Public Member Functions

void check_angle_range (SickTim3xxConfig &conf)
int init_usb ()
int loopOnce ()
 SickTim3xx ()
void update_config (sick_tim3xx::SickTim3xxConfig &new_config, uint32_t level=0)
virtual ~SickTim3xx ()

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)
int sendSOPASCommand (libusb_device_handle *device_handle, const char *request, unsigned int timeout)

Private Attributes

SickTim3xxConfig config_
libusb_context * ctx_
libusb_device_handle * device_handle_
libusb_device ** devices_
dynamic_reconfigure::Server
< sick_tim3xx::SickTim3xxConfig > 
dynamic_reconfigure_server_
ros::NodeHandle nh_
ssize_t numberOfDevices_
ros::Publisher pub_

Static Private Attributes

static const unsigned int USB_TIMEOUT = 500

Detailed Description

Definition at line 53 of file sick_tim3xx.cpp.


Constructor & Destructor Documentation

sick_tim3xx::SickTim3xx::SickTim3xx (  ) 

Definition at line 90 of file sick_tim3xx.cpp.

sick_tim3xx::SickTim3xx::~SickTim3xx (  )  [virtual]

Definition at line 100 of file sick_tim3xx.cpp.


Member Function Documentation

void sick_tim3xx::SickTim3xx::check_angle_range ( SickTim3xxConfig &  conf  ) 

Definition at line 680 of file sick_tim3xx.cpp.

void sick_tim3xx::SickTim3xx::freeSOPASDeviceList ( libusb_device **  list  )  [private]

Definition at line 206 of file sick_tim3xx.cpp.

ssize_t sick_tim3xx::SickTim3xx::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 146 of file sick_tim3xx.cpp.

int sick_tim3xx::SickTim3xx::init_usb (  ) 

Definition at line 355 of file sick_tim3xx.cpp.

int sick_tim3xx::SickTim3xx::loopOnce (  ) 

Definition at line 481 of file sick_tim3xx.cpp.

void sick_tim3xx::SickTim3xx::printSOPASDeviceInformation ( ssize_t  numberOfDevices,
libusb_device **  devices 
) [private]

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

Definition at line 284 of file sick_tim3xx.cpp.

void sick_tim3xx::SickTim3xx::printUSBDeviceDetails ( struct libusb_device_descriptor  desc  )  [private]

Definition at line 222 of file sick_tim3xx.cpp.

void sick_tim3xx::SickTim3xx::printUSBInterfaceDetails ( libusb_device *  device  )  [private]

Definition at line 232 of file sick_tim3xx.cpp.

int sick_tim3xx::SickTim3xx::sendSOPASCommand ( libusb_device_handle *  device_handle,
const char *  request,
unsigned int  timeout 
) [private]

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

Definition at line 316 of file sick_tim3xx.cpp.

void sick_tim3xx::SickTim3xx::update_config ( sick_tim3xx::SickTim3xxConfig &  new_config,
uint32_t  level = 0 
)

Definition at line 689 of file sick_tim3xx.cpp.


Member Data Documentation

SickTim3xxConfig sick_tim3xx::SickTim3xx::config_ [private]

Definition at line 80 of file sick_tim3xx.cpp.

libusb_context* sick_tim3xx::SickTim3xx::ctx_ [private]

Definition at line 84 of file sick_tim3xx.cpp.

libusb_device_handle* sick_tim3xx::SickTim3xx::device_handle_ [private]

Definition at line 87 of file sick_tim3xx.cpp.

libusb_device** sick_tim3xx::SickTim3xx::devices_ [private]

Definition at line 86 of file sick_tim3xx.cpp.

dynamic_reconfigure::Server<sick_tim3xx::SickTim3xxConfig> sick_tim3xx::SickTim3xx::dynamic_reconfigure_server_ [private]

Definition at line 81 of file sick_tim3xx.cpp.

Definition at line 76 of file sick_tim3xx.cpp.

Definition at line 85 of file sick_tim3xx.cpp.

Definition at line 77 of file sick_tim3xx.cpp.

const unsigned int sick_tim3xx::SickTim3xx::USB_TIMEOUT = 500 [static, private]

Definition at line 64 of file sick_tim3xx.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


sick_tim3xx
Author(s): Jochen Sprickerhof, Martin Günther
autogenerated on Tue Mar 5 12:32:52 2013