Go to the documentation of this file.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 #ifndef USB_DEVICE_H_
00036 #define USB_DEVICE_H_
00037
00038 #include <stdexcept>
00039 #include <string>
00040 #include <boost/function.hpp>
00041 #include <boost/thread.hpp>
00042
00043 struct libusb_device_handle;
00044 struct libusb_context;
00045
00046 namespace lusb
00047 {
00048
00049 struct UsbDeviceException : public std::runtime_error
00050 {
00051 int error_code_;
00052 UsbDeviceException(int code, const char* msg) :
00053 std::runtime_error(msg), error_code_(code)
00054 {
00055 }
00056 };
00057
00058 class UsbDevice
00059 {
00060 public:
00061 UsbDevice(uint16_t vid, uint16_t pid, uint8_t mi);
00062 UsbDevice(uint16_t vid, uint16_t pid);
00063 UsbDevice();
00064 ~UsbDevice();
00065
00066 struct UsbIds {
00067 UsbIds() : vid(0), pid(0) {}
00068 UsbIds(uint16_t _vid, uint16_t _pid) : vid(_vid), pid(_pid) {}
00069 uint16_t vid, pid;
00070 };
00071
00072 class Location {
00073 public:
00074 Location() : loc(0) {}
00075 Location(uint8_t _bus, uint8_t _port = 0, uint8_t _addr = 0, uint16_t _vid = 0, uint16_t _pid = 0) : loc(0) {
00076 bus = _bus;
00077 addr = _addr;
00078 port = _port;
00079 vid = _vid;
00080 pid = _pid;
00081 }
00082 static bool match(const Location& a, const Location& b) {
00083
00084 return !((a.bus && b.bus && (a.bus != b.bus )) ||
00085 (a.addr && b.addr && (a.addr != b.addr)) ||
00086 (a.port && b.port && (a.port != b.port)));
00087 }
00088 bool match(const Location& other) const {
00089 return match(*this, other);
00090 }
00091 bool operator==(const Location& other) const {
00092 return loc == other.loc;
00093 }
00094 bool operator!=(const Location& other) const {
00095 return loc != other.loc;
00096 }
00097 bool operator<(const Location& other) const {
00098 return loc < other.loc;
00099 }
00100 bool operator>(const Location& other) const {
00101 return loc > other.loc;
00102 }
00103 bool operator<=(const Location& other) const {
00104 return loc <= other.loc;
00105 }
00106 bool operator>=(const Location& other) const {
00107 return loc >= other.loc;
00108 }
00109 union {
00110 uint32_t loc;
00111 struct {
00112 uint8_t bus;
00113 uint8_t addr;
00114 uint8_t port;
00115 uint8_t :8;
00116 };
00117 };
00118 uint16_t vid;
00119 uint16_t pid;
00120 };
00121 static void listDevices(const std::vector<UsbIds> &ids, std::vector<Location> &list);
00122 static void listDevices(uint16_t vid, uint16_t pid, std::vector<Location> &list);
00123 void listDevices(std::vector<Location> &list) const;
00124
00125 void setDevceIds(uint16_t vid, uint16_t pid, uint8_t mi);
00126 bool open(const Location &location = Location());
00127 void close();
00128
00129 bool isOpen() const { return open_; }
00130 Location getLocation() const { return location_; }
00131
00132 bool bulkWrite(const void * data, int size, unsigned char endpoint, int timeout);
00133 int bulkRead(void * data, int size, unsigned char endpoint, int timeout);
00134 bool interruptWrite(const void * data, int size, unsigned char endpoint, int timeout);
00135 int interruptRead(void * data, int size, unsigned char endpoint, int timeout);
00136
00137 typedef boost::function<void(const void *data, int size)> Callback;
00138 void startBulkReadThread(Callback callback, unsigned char endpoint);
00139 void stopBulkReadThread(unsigned char endpoint);
00140 void startinterruptReadThread(Callback callback, unsigned char endpoint);
00141 void stopInterruptReadThread(unsigned char endpoint);
00142
00143 bool throw_errors_;
00144 int getLastError(std::string &str) const;
00145 void setDebugLevel(uint8_t level);
00146
00147 private:
00148 bool handleError(int err);
00149 void throwError(int err);
00150 void init();
00151 void closeDevice();
00152
00153 void bulkReadThread(Callback callback, unsigned char endpoint);
00154 void interruptReadThread(Callback callback, unsigned char endpoint);
00155
00156 int error_code_;
00157 std::string error_str_;
00158
00159 uint16_t vid_;
00160 uint16_t pid_;
00161 uint8_t mi_;
00162 bool open_;
00163 Location location_;
00164 libusb_device_handle *libusb_handle_;
00165 libusb_context *ctx_;
00166 boost::thread bulk_threads_[128];
00167 bool bulk_threads_enable_[128];
00168 boost::thread interrupt_threads_[128];
00169 bool interrupt_threads_enable_[128];
00170
00171 };
00172 }
00173
00174 #endif