00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "lusb/UsbDevice.h"
00036 #include <libusb-1.0/libusb.h>
00037
00038 using namespace std;
00039
00040 namespace lusb
00041 {
00042
00043 static inline UsbDevice::Location locationFromLibUsbDevice(libusb_device *dev, const libusb_device_descriptor desc) {
00044 return UsbDevice::Location(libusb_get_bus_number(dev),
00045 libusb_get_port_number(dev),
00046 libusb_get_device_address(dev),
00047 desc.idVendor,
00048 desc.idProduct);
00049 }
00050
00051 bool UsbDevice::handleError(int err)
00052 {
00053 bool success;
00054 switch ((libusb_error)err) {
00055 case LIBUSB_SUCCESS:
00056 success = true;
00057 break;
00058 case LIBUSB_ERROR_TIMEOUT:
00059 success = false;
00060 break;
00061 case LIBUSB_ERROR_BUSY:
00062 case LIBUSB_ERROR_OVERFLOW:
00063 case LIBUSB_ERROR_INVALID_PARAM:
00064 case LIBUSB_ERROR_INTERRUPTED:
00065 case LIBUSB_ERROR_NO_MEM:
00066 case LIBUSB_ERROR_PIPE:
00067 throwError(err);
00068 success = false;
00069 break;
00070 case LIBUSB_ERROR_IO:
00071 case LIBUSB_ERROR_ACCESS:
00072 case LIBUSB_ERROR_NO_DEVICE:
00073 case LIBUSB_ERROR_NOT_FOUND:
00074 case LIBUSB_ERROR_NOT_SUPPORTED:
00075 case LIBUSB_ERROR_OTHER:
00076 default:
00077 closeDevice();
00078 throwError(err);
00079 success = false;
00080 break;
00081 }
00082 return success;
00083 }
00084 void UsbDevice::throwError(int err)
00085 {
00086 error_code_ = (libusb_error)err;
00087 error_str_ = libusb_error_name(err);
00088 if (throw_errors_) {
00089 throw lusb::UsbDeviceException((libusb_error)err, error_str_.c_str());
00090 }
00091 }
00092 int UsbDevice::getLastError(std::string &str) const
00093 {
00094 str = error_str_;
00095 return error_code_;
00096 }
00097 void UsbDevice::setDebugLevel(uint8_t level)
00098 {
00099 if (level > LIBUSB_LOG_LEVEL_DEBUG) {
00100 level = LIBUSB_LOG_LEVEL_DEBUG;
00101 }
00102 libusb_set_debug(ctx_, level);
00103 }
00104
00105 void UsbDevice::init()
00106 {
00107 open_ = false;
00108 location_ = Location();
00109 libusb_handle_ = NULL;
00110 throw_errors_ = false;
00111 memset(bulk_threads_enable_, 0x00, sizeof(bulk_threads_enable_));
00112 memset(interrupt_threads_enable_, 0x00, sizeof(interrupt_threads_enable_));
00113 ctx_ = NULL;
00114 libusb_init(&ctx_);
00115 libusb_set_debug(ctx_, LIBUSB_LOG_LEVEL_NONE);
00116 }
00117
00118 UsbDevice::UsbDevice(uint16_t vid, uint16_t pid, uint8_t mi)
00119 {
00120 init();
00121 setDevceIds(vid, pid, mi);
00122 }
00123 UsbDevice::UsbDevice(uint16_t vid, uint16_t pid)
00124 {
00125 init();
00126 setDevceIds(vid, pid, 0x00);
00127 }
00128 UsbDevice::UsbDevice()
00129 {
00130 init();
00131 setDevceIds(0x0000, 0x0000, 0x00);
00132 }
00133 UsbDevice::~UsbDevice()
00134 {
00135 close();
00136 if (ctx_) {
00137 libusb_exit(ctx_);
00138 ctx_ = NULL;
00139 }
00140 }
00141
00142 void UsbDevice::setDevceIds(uint16_t vid, uint16_t pid, uint8_t mi)
00143 {
00144 pid_ = pid;
00145 vid_ = vid;
00146 mi_ = mi;
00147 }
00148
00149 void UsbDevice::listDevices(uint16_t vid, uint16_t pid, std::vector<Location> &vec)
00150 {
00151 const std::vector<UsbIds> ids(1, UsbIds(vid, pid));
00152 listDevices(ids, vec);
00153 }
00154
00155 void UsbDevice::listDevices(const std::vector<UsbIds> &ids, std::vector<Location> &vec)
00156 {
00157 vec.clear();
00158
00159 libusb_context *ctx = NULL;
00160 libusb_init(&ctx);
00161 libusb_set_debug(ctx, LIBUSB_LOG_LEVEL_NONE);
00162
00163 libusb_device **list;
00164 ssize_t cnt = libusb_get_device_list(ctx, &list);
00165 if (cnt > 0) {
00166 for (ssize_t i = 0; i < cnt; i++) {
00167 libusb_device *device = list[i];
00168 struct libusb_device_descriptor desc;
00169 if (libusb_get_device_descriptor(device, &desc) == LIBUSB_SUCCESS) {
00170 for (size_t i = 0; i < ids.size(); i++) {
00171 if ((!ids[i].vid || ids[i].vid == desc.idVendor) && (!ids[i].pid || ids[i].pid == desc.idProduct)) {
00172 vec.push_back(locationFromLibUsbDevice(device, desc));
00173 break;
00174 }
00175 }
00176 }
00177 }
00178 }
00179 libusb_free_device_list(list, 1);
00180
00181 libusb_exit(ctx);
00182 }
00183
00184 void UsbDevice::listDevices(std::vector<Location> &vec) const
00185 {
00186 listDevices(vid_, pid_, vec);
00187 }
00188
00189 bool UsbDevice::open(const Location &location)
00190 {
00191 closeDevice();
00192
00193 libusb_device **list;
00194 ssize_t cnt = libusb_get_device_list(ctx_, &list);
00195 ssize_t i = 0;
00196 if (cnt > 0) {
00197 for (i = 0; i < cnt; i++) {
00198 libusb_device *device = list[i];
00199 struct libusb_device_descriptor desc;
00200 if (libusb_get_device_descriptor(device, &desc) == LIBUSB_SUCCESS) {
00201 if ((!vid_ || vid_ == desc.idVendor) && (!pid_ || pid_ == desc.idProduct)) {
00202 Location loc = locationFromLibUsbDevice(device, desc);
00203 if (location.match(loc)) {
00204 libusb_device_handle *handle;
00205 if (libusb_open(device, &handle) == LIBUSB_SUCCESS) {
00206 if (libusb_kernel_driver_active(handle, mi_) == 1) {
00207 libusb_detach_kernel_driver(handle, mi_);
00208 }
00209 if (libusb_claim_interface(handle, mi_) == LIBUSB_SUCCESS) {
00210 location_ = loc;
00211 libusb_handle_ = handle;
00212 open_ = true;
00213 break;
00214 }
00215 libusb_close(handle);
00216 }
00217 }
00218 }
00219 }
00220 }
00221 }
00222
00223 libusb_free_device_list(list, 1);
00224 return open_;
00225 }
00226
00227 void UsbDevice::close()
00228 {
00229 for (int i = 0; i < 128; i++) {
00230 bulk_threads_enable_[i] = false;
00231 interrupt_threads_enable_[i] = false;
00232 }
00233 closeDevice();
00234 }
00235
00236 void UsbDevice::closeDevice()
00237 {
00238 if (open_) {
00239 open_ = false;
00240 if (libusb_handle_) {
00241 libusb_release_interface(libusb_handle_, 0);
00242 libusb_close(libusb_handle_);
00243 }
00244 }
00245 libusb_handle_ = NULL;
00246 }
00247
00248 bool UsbDevice::bulkWrite(const void * data, int size, unsigned char endpoint, int timeout)
00249 {
00250 if ((libusb_handle_ == NULL) || !open_) {
00251 return false;
00252 }
00253 int actual = 0;
00254 int err = libusb_bulk_transfer(libusb_handle_, endpoint & ~LIBUSB_ENDPOINT_IN, (unsigned char *)data, size, &actual,
00255 timeout);
00256 bool success;
00257 success = handleError(err);
00258 success &= size == actual;
00259 return success;
00260 }
00261 int UsbDevice::bulkRead(void * data, int size, unsigned char endpoint, int timeout)
00262 {
00263 if ((libusb_handle_ == NULL) || !open_) {
00264 return -1;
00265 }
00266 int actual = 0;
00267 int err = libusb_bulk_transfer(libusb_handle_, endpoint | LIBUSB_ENDPOINT_IN, (unsigned char *)data, size, &actual,
00268 timeout);
00269 return handleError(err) ? actual : -1;
00270 }
00271 bool UsbDevice::interruptWrite(const void * data, int size, unsigned char endpoint, int timeout)
00272 {
00273 if ((libusb_handle_ == NULL) || !open_) {
00274 return false;
00275 }
00276 int actual = 0;
00277 int err = libusb_interrupt_transfer(libusb_handle_, endpoint & ~LIBUSB_ENDPOINT_IN, (unsigned char *)data, size,
00278 &actual, timeout);
00279 bool success;
00280 success = handleError(err);
00281 success &= size == actual;
00282 return success;
00283 }
00284 int UsbDevice::interruptRead(void * data, int size, unsigned char endpoint, int timeout)
00285 {
00286 if ((libusb_handle_ == NULL) || !open_) {
00287 return -1;
00288 }
00289 int actual = 0;
00290 int err = libusb_interrupt_transfer(libusb_handle_, endpoint | LIBUSB_ENDPOINT_IN, (unsigned char *)data, size,
00291 &actual, timeout);
00292 return handleError(err) ? actual : -1;
00293 }
00294
00295 void UsbDevice::bulkReadThread(Callback callback, unsigned char endpoint)
00296 {
00297 endpoint &= 0x7F;
00298 int size;
00299 char data[1024];
00300 while (bulk_threads_enable_[endpoint]) {
00301 if (open_) {
00302 size = bulkRead(data, sizeof(data), endpoint, 100);
00303 if (size > 0) {
00304 callback(data, size);
00305 }
00306 } else {
00307 bulk_threads_enable_[endpoint] = 0;
00308 return;
00309 }
00310 }
00311 }
00312 void UsbDevice::interruptReadThread(Callback callback, unsigned char endpoint)
00313 {
00314 endpoint &= 0x7F;
00315 int size;
00316 char data[1024];
00317 while (interrupt_threads_enable_[endpoint]) {
00318 if (open_) {
00319 size = interruptRead(data, sizeof(data), endpoint, 100);
00320 if (size > 0) {
00321 callback(data, size);
00322 }
00323 } else {
00324 interrupt_threads_enable_[endpoint] = false;
00325 return;
00326 }
00327 }
00328 }
00329
00330 void UsbDevice::stopBulkReadThread(unsigned char endpoint)
00331 {
00332 endpoint &= 0x7F;
00333 bulk_threads_enable_[endpoint] = false;
00334 if (bulk_threads_[endpoint].joinable()) {
00335 bulk_threads_[endpoint].join();
00336 }
00337 }
00338 void UsbDevice::startBulkReadThread(Callback callback, unsigned char endpoint)
00339 {
00340 endpoint &= 0x7F;
00341 stopBulkReadThread(endpoint);
00342 bulk_threads_enable_[endpoint] = true;
00343 bulk_threads_[endpoint] = boost::thread(&UsbDevice::bulkReadThread, this, callback, endpoint);
00344 }
00345 void UsbDevice::stopInterruptReadThread(unsigned char endpoint)
00346 {
00347
00348 endpoint &= 0x7F;
00349 interrupt_threads_enable_[endpoint] = false;
00350 if (interrupt_threads_[endpoint].joinable()) {
00351 interrupt_threads_[endpoint].join();
00352 }
00353 }
00354 void UsbDevice::startinterruptReadThread(Callback callback, unsigned char endpoint)
00355 {
00356 endpoint &= 0x7F;
00357 stopBulkReadThread(endpoint);
00358 interrupt_threads_enable_[endpoint] = true;
00359 interrupt_threads_[endpoint] = boost::thread(&UsbDevice::interruptReadThread, this, callback, endpoint);
00360 }
00361
00362 }