4 #include <IOKit/hid/IOHIDManager.h> 5 #include <IOKit/hid/IOHIDKeys.h> 6 #include <IOKit/IOKitLib.h> 7 #include <CoreFoundation/CoreFoundation.h> 36 if(pthread_mutex_init(&barrier->
mutex, 0) < 0) {
39 if(pthread_cond_init(&barrier->
cond, 0) < 0) {
40 pthread_mutex_destroy(&barrier->
mutex);
51 pthread_cond_destroy(&barrier->
cond);
52 pthread_mutex_destroy(&barrier->
mutex);
58 pthread_mutex_lock(&barrier->
mutex);
63 pthread_cond_broadcast(&barrier->
cond);
64 pthread_mutex_unlock(&barrier->
mutex);
69 pthread_cond_wait(&barrier->
cond, &(barrier->
mutex));
70 pthread_mutex_unlock(&barrier->
mutex);
154 pthread_mutex_destroy(&dev->
mutex);
164 static void register_error(hid_device *
device,
const char *op)
176 ref = IOHIDDeviceGetProperty(device, key);
178 if (CFGetTypeID(ref) == CFNumberGetTypeID()) {
179 CFNumberGetValue((CFNumberRef) ref, kCFNumberSInt32Type, &value);
208 str = (CFStringRef) IOHIDDeviceGetProperty(device, prop);
213 CFIndex str_len = CFStringGetLength(str);
215 CFIndex used_buf_len;
216 CFIndex chars_copied;
221 range.length = ((
size_t)str_len > len)? len: (
size_t)str_len;
222 chars_copied = CFStringGetBytes(str,
224 kCFStringEncodingUTF32LE,
228 len *
sizeof(
wchar_t),
231 if (chars_copied == len)
234 buf[chars_copied] = 0;
262 size_t len = wcslen(s);
263 wchar_t *ret = (
wchar_t *)malloc((len+1)*
sizeof(wchar_t));
277 static void *iokit_framework =
NULL;
278 static io_service_t (*dynamic_IOHIDDeviceGetService)(IOHIDDeviceRef) =
NULL;
284 if (iokit_framework ==
NULL) {
285 iokit_framework = dlopen(
"/System/Library/IOKit.framework/IOKit", RTLD_LAZY);
287 if (iokit_framework !=
NULL)
288 dynamic_IOHIDDeviceGetService = (io_service_t (*)(IOHIDDeviceRef))dlsym(iokit_framework,
"IOHIDDeviceGetService");
291 if (dynamic_IOHIDDeviceGetService !=
NULL) {
293 return dynamic_IOHIDDeviceGetService(device);
304 struct IOHIDDevice_internal {
318 io_service_t service;
320 struct IOHIDDevice_internal *
tmp = (
struct IOHIDDevice_internal *)device;
330 hid_mgr = IOHIDManagerCreate(kCFAllocatorDefault, kIOHIDOptionsTypeNone);
333 IOHIDManagerScheduleWithRunLoop(
hid_mgr, CFRunLoopGetCurrent(), kCFRunLoopDefaultMode);
357 IOHIDManagerClose(
hid_mgr, kIOHIDOptionsTypeNone);
368 res = CFRunLoopRunInMode(kCFRunLoopDefaultMode, 0.001,
FALSE);
369 }
while(res != kCFRunLoopRunFinished && res != kCFRunLoopRunTimedOut);
388 CFSetRef device_set = IOHIDManagerCopyDevices(
hid_mgr);
391 num_devices = CFSetGetCount(device_set);
392 IOHIDDeviceRef *device_array =
reinterpret_cast<IOHIDDeviceRef *
>(calloc(num_devices,
sizeof(IOHIDDeviceRef)));
393 CFSetGetValues(device_set, (
const void **) device_array);
396 for (i = 0; i < num_devices; i++) {
397 unsigned short dev_vid;
398 unsigned short dev_pid;
402 IOHIDDeviceRef dev = device_array[
i];
411 if ((vendor_id == 0
x0 || vendor_id == dev_vid) &&
412 (product_id == 0
x0 || product_id == dev_pid)) {
414 io_object_t iokit_dev;
437 res = IORegistryEntryGetPath(iokit_dev, kIOServicePlane, path);
438 if (res == KERN_SUCCESS)
439 cur_dev->
path = strdup(path);
441 cur_dev->
path = strdup(
"");
466 CFRelease(device_set);
490 const char *path_to_open =
NULL;
500 path_to_open = cur_dev->
path;
505 path_to_open = cur_dev->
path;
509 cur_dev = cur_dev->
next;
536 IOHIDReportType report_type,
uint32_t report_id,
537 uint8_t *report, CFIndex report_length)
544 rpt->
data =
reinterpret_cast<uint8_t*
> (calloc(1, report_length));
545 memcpy(rpt->
data, report, report_length);
546 rpt->
len = report_length;
550 pthread_mutex_lock(&dev->
mutex);
570 if (num_queued > 30) {
579 pthread_mutex_unlock(&dev->
mutex);
601 CFRunLoopSourceContext
ctx;
602 memset(&ctx, 0,
sizeof(ctx));
606 dev->
source = CFRunLoopSourceCreate(kCFAllocatorDefault, 0, &ctx);
611 dev->
run_loop = CFRunLoopGetCurrent();
621 if (code == kCFRunLoopRunFinished) {
628 if (code != kCFRunLoopRunTimedOut &&
629 code != kCFRunLoopRunHandledSource) {
643 pthread_mutex_lock(&dev->
mutex);
645 pthread_mutex_unlock(&dev->
mutex);
663 io_registry_entry_t
entry = MACH_PORT_NULL;
671 bool return_error =
false;
674 entry = IORegistryEntryFromPath(kIOMasterPortDefault, path);
675 if (entry == MACH_PORT_NULL) {
681 dev->
device_handle = IOHIDDeviceCreate(kCFAllocatorDefault, entry);
688 IOReturn ret = IOHIDDeviceOpen(dev->
device_handle, kIOHIDOptionsTypeSeizeDevice);
689 if (ret == kIOReturnSuccess) {
700 CFStringCreateWithCString(
NULL, str, kCFStringEncodingASCII);
703 IOHIDDeviceRegisterInputReportCallback(
714 IOObjectRelease(entry);
718 return_error =
true;;
726 if (entry != MACH_PORT_NULL)
727 IOObjectRelease(entry);
736 const unsigned char *data_to_send;
737 size_t length_to_send;
744 if (data[0] == 0
x0) {
747 data_to_send = data+1;
748 length_to_send = length-1;
761 data_to_send, length_to_send);
763 if (res == kIOReturnSuccess) {
775 return set_report(dev, kIOHIDReportTypeOutput, data, length);
784 size_t len = (length < rpt->
len)? length: rpt->
len;
785 memcpy(data, rpt->
data, len);
795 int res = pthread_cond_wait(cond, mutex);
815 int res = pthread_cond_timedwait(cond, mutex, abstime);
838 pthread_mutex_lock(&dev->
mutex);
863 if (milliseconds == -1) {
874 else if (milliseconds > 0) {
879 gettimeofday(&tv,
NULL);
880 TIMEVAL_TO_TIMESPEC(&tv, &ts);
881 ts.tv_sec += milliseconds / 1000;
882 ts.tv_nsec += (milliseconds % 1000) * 1000000;
883 if (ts.tv_nsec >= 1000000000L) {
885 ts.tv_nsec -= 1000000000L;
891 else if (res == ETIMEDOUT)
903 pthread_mutex_unlock(&dev->
mutex);
922 return set_report(dev, kIOHIDReportTypeFeature, data, length);
935 kIOHIDReportTypeFeature,
938 if (res == kIOReturnSuccess)
952 IOHIDDeviceRegisterInputReportCallback(
957 IOHIDDeviceScheduleWithRunLoop(dev->
device_handle, CFRunLoopGetMain(), kCFRunLoopDefaultMode);
964 CFRunLoopSourceSignal(dev->
source);
977 IOHIDDeviceClose(dev->
device_handle, kIOHIDOptionsTypeSeizeDevice);
981 pthread_mutex_lock(&dev->
mutex);
985 pthread_mutex_unlock(&dev->
mutex);
int pthread_barrierattr_t
void HID_API_EXPORT hid_free_enumeration(struct hidapi_device_info *devs)
Free an enumeration Linked List.
GLboolean GLboolean GLboolean b
static int32_t get_usage_page(IOHIDDeviceRef device)
static IOHIDManagerRef hid_mgr
static unsigned short get_product_id(IOHIDDeviceRef device)
struct hidapi_device_info * next
int HID_API_EXPORT_CALL hid_get_serial_number_string(hidapi_device *dev, wchar_t *string, size_t maxlen)
Get The Serial Number String from a HID device.
CFRunLoopSourceRef source
int HID_API_EXPORT hid_write(hidapi_device *dev, const unsigned char *data, size_t length)
Write an Output report to a HID device.
static int get_transport(IOHIDDeviceRef device, wchar_t *buf, size_t len)
static int32_t get_usage(IOHIDDeviceRef device)
GLuint64 GLenum void * handle
GLsizei const GLchar *const * path
static int return_data(hidapi_device *dev, unsigned char *data, size_t length)
static int get_serial_number(IOHIDDeviceRef device, wchar_t *buf, size_t len)
static int32_t get_max_report_length(IOHIDDeviceRef device)
static unsigned short get_vendor_id(IOHIDDeviceRef device)
int HID_API_EXPORT hid_read_timeout(hidapi_device *dev, unsigned char *data, size_t length, int milliseconds)
Read an Input report from a HID device with timeout.
struct input_report * input_reports
void HID_API_EXPORT hid_close(hidapi_device *dev)
Close a HID device.
IOHIDDeviceRef device_handle
unsigned short product_id
static wchar_t * dup_wcs(const wchar_t *s)
static int pthread_barrier_init(pthread_barrier_t *barrier, const pthread_barrierattr_t *attr, unsigned int count)
int HID_API_EXPORT_CALL hid_get_manufacturer_string(hidapi_device *dev, wchar_t *string, size_t maxlen)
Get The Manufacturer String from a HID device.
pthread_barrier_t shutdown_barrier
CFIndex max_input_report_len
static int get_string_property(IOHIDDeviceRef device, CFStringRef prop, wchar_t *buf, size_t len)
GLboolean GLboolean GLboolean GLboolean a
GLenum GLuint GLenum GLsizei const GLchar * buf
int HID_API_EXPORT_CALL hid_get_indexed_string(hidapi_device *dev, int string_index, wchar_t *string, size_t maxlen)
Get a string from a HID device, based on its string index.
static io_service_t hidapi_IOHIDDeviceGetService(IOHIDDeviceRef device)
int HID_API_EXPORT hid_exit(void)
Finalize the HIDAPI library.
static int pthread_barrier_wait(pthread_barrier_t *barrier)
static void hid_report_callback(void *context, IOReturn result, void *sender, IOHIDReportType report_type, uint32_t report_id, uint8_t *report, CFIndex report_length)
int uses_numbered_reports
_W64 unsigned int uintptr_t
static int cond_wait(const hidapi_device *dev, pthread_cond_t *cond, pthread_mutex_t *mutex)
pthread_barrier_t barrier
int HID_API_EXPORT hid_set_nonblocking(hidapi_device *dev, int nonblock)
Set the device handle to be non-blocking.
unsigned short release_number
static int get_product_string(IOHIDDeviceRef device, wchar_t *buf, size_t len)
static int cond_timedwait(const hidapi_device *dev, pthread_cond_t *cond, pthread_mutex_t *mutex, const struct timespec *abstime)
static int32_t get_int_property(IOHIDDeviceRef device, CFStringRef key)
int HID_API_EXPORT hid_read(hidapi_device *dev, unsigned char *data, size_t length)
Read an Input report from a HID device.
int HID_API_EXPORT hid_init(void)
Initialize the HIDAPI library.
static void process_pending_events(void)
static int32_t get_location_id(IOHIDDeviceRef device)
static hidapi_device * new_hid_device(void)
hidapi_device *HID_API_EXPORT hid_open(unsigned short vendor_id, unsigned short product_id, const wchar_t *serial_number)
Open a HID device using a Vendor ID (VID), Product ID (PID) and optionally a serial number...
#define HID_API_EXPORT_CALL
void next(auto_any_t cur, type2type< T, C > *)
unsigned short usage_page
CFStringRef run_loop_mode
static int get_manufacturer_string(IOHIDDeviceRef device, wchar_t *buf, size_t len)
uint8_t * input_report_buf
static void hid_device_removal_callback(void *context, IOReturn result, void *sender)
static int init_hid_manager(void)
int HID_API_EXPORT_CALL hid_get_product_string(hidapi_device *dev, wchar_t *string, size_t maxlen)
Get The Product String from a HID device.
GLenum GLuint GLenum GLsizei length
static int set_report(hidapi_device *dev, IOHIDReportType type, const unsigned char *data, size_t length)
static int pthread_barrier_destroy(pthread_barrier_t *barrier)
HID_API_EXPORT const wchar_t *HID_API_CALL hid_error(hidapi_device *dev)
Get a string describing the last error which occurred.
::std_msgs::UInt8_< std::allocator< void > > UInt8
struct hidapi_device_info HID_API_EXPORT * hid_enumerate(unsigned short vendor_id, unsigned short product_id)
Enumerate the HID Devices.
static void * read_thread(void *param)
int HID_API_EXPORT hid_get_feature_report(hidapi_device *dev, unsigned char *data, size_t length)
Get a feature report from a HID device.
static void free_hid_device(hidapi_device *dev)
int HID_API_EXPORT hid_send_feature_report(hidapi_device *dev, const unsigned char *data, size_t length)
Send a Feature report to the device.
hidapi_device *HID_API_EXPORT hid_open_path(const char *path)
Open a HID device by its path name.
struct pthread_barrier pthread_barrier_t
wchar_t * manufacturer_string
static void perform_signal_callback(void *context)