40 #define __FILE_ID__ "ypkt_lin" 45 #include <sys/types.h> 50 #define yLinSetErr(intro, err,errmsg) yLinSetErrEx(__LINE__,intro, err,errmsg) 52 static int yLinSetErrEx(u32 line,
char *intro,
int err,
char *errmsg)
58 case LIBUSB_SUCCESS: msg=
"Success (no error)";
break;
59 case LIBUSB_ERROR_IO: msg=
"Input/output error";
break;
60 case LIBUSB_ERROR_INVALID_PARAM:msg=
"Invalid parameter";
break;
61 case LIBUSB_ERROR_ACCESS: msg=
"Access denied (insufficient permissions)";
break;
62 case LIBUSB_ERROR_NO_DEVICE: msg=
"No such device (it may have been disconnected)";
break;
63 case LIBUSB_ERROR_NOT_FOUND: msg=
"Entity not found";
break;
64 case LIBUSB_ERROR_BUSY: msg=
"Resource busy";
break;
65 case LIBUSB_ERROR_TIMEOUT: msg=
"Operation timed out";
break;
66 case LIBUSB_ERROR_OVERFLOW: msg=
"Overflow";
break;
67 case LIBUSB_ERROR_PIPE: msg=
"Pipe error";
break;
68 case LIBUSB_ERROR_INTERRUPTED: msg=
"System call interrupted (perhaps due to signal)";
break;
69 case LIBUSB_ERROR_NO_MEM: msg=
"Insufficient memory";
break;
70 case LIBUSB_ERROR_NOT_SUPPORTED:msg=
"Operation not supported or unimplemented on this platform";
break;
72 case LIBUSB_ERROR_OTHER: msg=
"Other error";
break;
79 HALLOG(
"LIN(%d):%s\n",line,msg);
89 #define YOCTO_LOCK_PIPE "/tmp/.yoctolock" 96 static int yReserveGlobalAccess(
yContextSt *ctx,
char *errmsg)
99 int chk_val, mypid, usedpid = 0;
102 mode_t oldmode = umask(0000);
105 HALLOG(
"old mode (%#o)\n",oldmode);
106 HALLOG(
"create fifo with (%#o)\n",mode);
107 if(mkfifo(YOCTO_LOCK_PIPE,mode)<0) {
108 HALLOG(
"unable to create lock fifo (%d:%s)\n",errno,strerror(errno));
111 fd = open(YOCTO_LOCK_PIPE,O_RDWR|O_NONBLOCK);
113 HALLOG(
"unable to open lock fifo (%d)\n",errno);
124 mypid = (int) getpid();
125 res = read(fd, &chk_val,
sizeof(chk_val));
126 if (res ==
sizeof(chk_val)) {
133 res = write(fd, &chk_val,
sizeof(chk_val));
134 if(res !=
sizeof(chk_val)) {
157 static void yReleaseGlobalAccess(
yContextSt *ctx)
161 dropwarning = read(pid_lock_fd,&chk_val,
sizeof(chk_val));
175 #define STRING_CACHE_SIZE 16 176 #define STRING_CACHE_EXPIRATION 60000 //1 minutes 177 static stringCacheSt stringCache[STRING_CACHE_SIZE];
181 static int getUsbStringASCII(
yContextSt *ctx, libusb_device_handle *hdl, libusb_device *dev, u8 desc_index,
char *data, u32 length)
186 stringCacheSt *c = stringCache;
187 stringCacheSt *
f = NULL;
192 for (i = 0; i < STRING_CACHE_SIZE; i++, c++) {
193 if (c->expiration > now) {
194 if(c->dev == dev && c->desc_index == desc_index) {
195 if (c->len > 0 && c->string) {
197 if (c->len >= length)
199 memcpy(data, c->string, len);
201 HALENUMLOG(
"return string from cache (%p:%d->%s)\n",dev,desc_index,c->string);
220 res=libusb_control_transfer(hdl, LIBUSB_ENDPOINT_IN,
221 LIBUSB_REQUEST_GET_DESCRIPTOR, (LIBUSB_DT_STRING << 8) | desc_index,
222 0, buffer, 512, 10000);
233 for (l = 0; l < len; l++){
234 data[l] = (char) buffer[2+(l*2)];
240 f->desc_index = desc_index;
242 memcpy(f->string, data, len+1);
245 HALENUMLOG(
"add string to cache (%p:%d->%s)\n",dev,desc_index,f->string);
253 int process_libusb_events(
yContextSt *ctx,
int ms,
char * errmsg)
257 memset(&tv, 0,
sizeof(tv));
258 tv.tv_sec = ms / 1000;
259 tv.tv_usec = (ms % 1000) * 1000;
260 res = libusb_handle_events_timeout(ctx->libusb, &tv);
262 yLinSetErr(
"libusb_handle_events_timeout", res, errmsg);
268 static void *event_thread(
void *
param)
274 HALLOG(
"Start event_thread run loop\n");
276 int res = process_libusb_events(ctx, 1000, errmsg);
278 yLinSetErr(
"libusb_handle_events_timeout", res,errmsg);
282 HALLOG(
"event_thread run loop stoped\n");
292 YPROPERR(yReserveGlobalAccess(ctx, errmsg));
293 memset(stringCache, 0,
sizeof(stringCache));
295 res = libusb_init(&ctx->libusb);
297 return yLinSetErr(
"Unable to start lib USB", res,errmsg);
301 const struct libusb_version *libusb_v;
302 libusb_v = libusb_get_version();
303 dbglog(
"Use libUSB v%d.%d.%d.%d\n", libusb_v->major, libusb_v->minor, libusb_v->micro, libusb_v->nano);
307 pthread_create(&ctx->usb_thread, NULL, event_thread, ctx);
320 stringCacheSt *c = stringCache;
324 pthread_join(ctx->usb_thread,NULL);
328 libusb_exit(ctx->libusb);
329 yReleaseGlobalAccess(ctx);
330 for (i = 0; i < STRING_CACHE_SIZE; i++, c++) {
342 static int getDevConfig(libusb_device *dev,
struct libusb_config_descriptor **config)
345 int res = libusb_get_active_config_descriptor(dev, config);
346 if(res==LIBUSB_ERROR_NOT_FOUND){
347 HALLOG(
"not yet configured\n");
348 if(libusb_get_config_descriptor(dev, 0, config)!=0){
352 HALLOG(
"unable to get active configuration %d\n",res);
362 libusb_device **list;
369 nbdev = libusb_get_device_list(
yContext->libusb,&list);
371 return yLinSetErr(
"Unable to get device list", nbdev, errmsg);
378 memset(*ifaces, 0, alloc_size);
380 for (i = 0; i < nbdev; i++) {
382 struct libusb_device_descriptor desc;
383 struct libusb_config_descriptor *config;
384 libusb_device_handle *hdl;
386 libusb_device *dev = list[i];
387 if ((res = libusb_get_device_descriptor(dev,&desc)) != 0){
388 returnval = yLinSetErr(
"Unable to get device descriptor",res,errmsg);
394 HALENUMLOG(
"open device %x:%x\n", desc.idVendor, desc.idProduct);
396 if(getDevConfig(dev, &config) < 0) {
399 iface = (*ifaces) + (*nbifaceDetect);
400 iface->
vendorid = (u16)desc.idVendor;
401 iface->
deviceid = (u16)desc.idProduct;
403 iface->devref = libusb_ref_device(dev);
404 res = libusb_open(dev, &hdl);
405 if (res == LIBUSB_ERROR_ACCESS) {
406 returnval =
YERRMSG(
YAPI_IO_ERROR,
"the user has insufficient permissions to access USB devices");
410 HALENUMLOG(
"unable to access device %x:%x\n", desc.idVendor, desc.idProduct);
413 HALENUMLOG(
"try to get serial for %x:%x:%x (%p)\n", desc.idVendor, desc.idProduct, desc.iSerialNumber, dev);
416 HALENUMLOG(
"unable to get serial for device %x:%x\n", desc.idVendor, desc.idProduct);
421 libusb_free_config_descriptor(config);
425 libusb_free_device_list(list,1);
440 if(dev->
iface.devref != newiface->devref){
448 static void rd_callback(
struct libusb_transfer *transfer);
449 static void wr_callback(
struct libusb_transfer *transfer);
452 static int sendNextPkt(
yInterfaceSt *iface,
char *errmsg)
456 if (pktitem != NULL) {
458 memcpy(&iface->wrTr->tmppkt, &pktitem->
pkt,
sizeof(
USB_Packet));
459 libusb_fill_interrupt_transfer( iface->wrTr->tr,
462 (u8*)&iface->wrTr->tmppkt,
467 res = libusb_submit_transfer(iface->wrTr->tr);
469 return yLinSetErr(
"libusb_submit_transfer(WR) failed", res, errmsg);
476 static int submitReadPkt(
yInterfaceSt *iface,
char *errmsg)
479 libusb_fill_interrupt_transfer( iface->rdTr->tr,
482 (u8*)&iface->rdTr->tmppkt,
487 res = libusb_submit_transfer(iface->rdTr->tr);
489 return yLinSetErr(
"libusb_submit_transfer(RD) failed", res, errmsg);
495 static void rd_callback(
struct libusb_transfer *transfer)
498 linRdTr *lintr = (linRdTr*)transfer->user_data;
503 HALLOG(
"CBrd:drop invalid ypkt rd_callback (lintr is null)\n");
507 HALLOG(
"CBrd:drop invalid ypkt rd_callback (iface is null)\n");
511 switch(transfer->status){
512 case LIBUSB_TRANSFER_COMPLETED:
516 case LIBUSB_TRANSFER_ERROR:
518 HALLOG(
"CBrd:%s pkt error (len=%d nbError:%d)\n",iface->
serial, transfer->actual_length, iface->ioError);
520 case LIBUSB_TRANSFER_TIMED_OUT :
523 case LIBUSB_TRANSFER_CANCELLED:
524 HALLOG(
"CBrd:%s pkt_cancelled (len=%d) \n",iface->
serial, transfer->actual_length);
529 case LIBUSB_TRANSFER_STALL:
531 res = libusb_cancel_transfer(lintr->tr);
532 HALLOG(
"CBrd:%s libusb_cancel_transfer returned %d\n",iface->
serial, res);
533 res = libusb_clear_halt(iface->hdl, iface->rdendp);
534 HALLOG(
"CBrd:%s libusb_clear_hal returned %d\n",iface->
serial, res);
536 case LIBUSB_TRANSFER_NO_DEVICE:
537 HALLOG(
"CBrd:%s no_device (len=%d)\n",iface->
serial, transfer->actual_length);
539 case LIBUSB_TRANSFER_OVERFLOW:
540 HALLOG(
"CBrd:%s pkt_overflow (len=%d)\n",iface->
serial, transfer->actual_length);
543 HALLOG(
"CBrd:%s unknown state %X\n",iface->
serial, transfer->status);
548 res = submitReadPkt(iface, errmsg);
550 HALLOG(
"CBrd:%s libusb_submit_transfer errror %X\n", iface->
serial, res);
556 static void wr_callback(
struct libusb_transfer *transfer)
558 linRdTr *lintr = (linRdTr*)transfer->user_data;
565 HALLOG(
"CBwr:drop invalid ypkt wr_callback (lintr is null)\n");
570 HALLOG(
"CBwr:drop invalid ypkt wr_callback (iface is null)\n");
573 YASSERT(transfer == lintr->tr);
575 switch(transfer->status) {
576 case LIBUSB_TRANSFER_COMPLETED:
581 res = sendNextPkt(iface, errmsg);
583 HALLOG(
"send of next pkt item failed:%d:%s\n", res, errmsg);
586 case LIBUSB_TRANSFER_ERROR:
588 HALLOG(
"CBwr:%s pkt error (len=%d nbError:%d)\n",iface->
serial, transfer->actual_length, iface->ioError);
590 case LIBUSB_TRANSFER_TIMED_OUT :
592 res = sendNextPkt(iface, errmsg);
594 HALLOG(
"retry of next pkt item failed:%d:%s\n", res, errmsg);
597 case LIBUSB_TRANSFER_CANCELLED:
598 HALLOG(
"CBwr:%s pkt_cancelled (len=%d) \n",iface->
serial, transfer->actual_length);
600 case LIBUSB_TRANSFER_STALL:
603 case LIBUSB_TRANSFER_NO_DEVICE:
604 HALLOG(
"CBwr:%s pkt_cancelled (len=%d)\n",iface->
serial, transfer->actual_length);
606 case LIBUSB_TRANSFER_OVERFLOW:
607 HALLOG(
"CBwr:%s pkt_overflow (len=%d)\n",iface->
serial, transfer->actual_length);
610 HALLOG(
"CBwr:%s unknown state %X\n",iface->
serial, transfer->status);
620 struct libusb_config_descriptor *config;
621 const struct libusb_interface_descriptor* ifd;
626 if(iface->devref==NULL){
633 if((res=libusb_open(iface->devref,&iface->hdl))!=0){
634 return yLinSetErr(
"libusb_open", res,errmsg);
636 libusb_reset_device(iface->hdl);
637 libusb_close(iface->hdl);
641 if((res=libusb_open(iface->devref,&iface->hdl))!=0){
642 return yLinSetErr(
"libusb_open", res,errmsg);
645 if((res=libusb_kernel_driver_active(iface->hdl,iface->
ifaceno))<0){
646 error= yLinSetErr(
"libusb_kernel_driver_active",res,errmsg);
650 HALLOG(
"%s need to detach kernel driver\n",iface->
serial);
651 if((res = libusb_detach_kernel_driver(iface->hdl,iface->
ifaceno))<0){
652 error= yLinSetErr(
"libusb_detach_kernel_driver",res,errmsg);
658 if((res = libusb_claim_interface(iface->hdl,iface->
ifaceno))<0){
659 error= yLinSetErr(
"libusb_claim_interface", res,errmsg);
664 res=getDevConfig(iface->devref,&config);
671 ifd = &config->interface[iface->
ifaceno].altsetting[0];
672 for (j = 0; j < ifd->bNumEndpoints; j++) {
674 if((ifd->endpoint[j].bEndpointAddress & LIBUSB_ENDPOINT_DIR_MASK) == LIBUSB_ENDPOINT_IN){
675 iface->rdendp = ifd->endpoint[j].bEndpointAddress;
677 iface->wrendp = ifd->endpoint[j].bEndpointAddress;
680 HALLOG(
"ednpoints are rd=%d wr=%d\n", iface->rdendp,iface->wrendp);
684 iface->rdTr =
yMalloc(
sizeof(linRdTr));
685 iface->wrTr =
yMalloc(
sizeof(linRdTr));
686 HALLOG(
"allocate linRdTr=%p linWrTr\n", iface->rdTr, iface->wrTr);
687 iface->wrTr->iface = iface;
688 iface->wrTr->tr = libusb_alloc_transfer(0);
689 iface->rdTr->iface = iface;
690 iface->rdTr->tr = libusb_alloc_transfer(0);
692 HALLOG(
"%s both libusbTR allocated (%p /%p)\n",iface->
serial, iface->rdTr->tr, iface->wrTr->tr);
693 res = submitReadPkt(iface, errmsg);
701 libusb_close(iface->hdl);
710 return sendNextPkt(iface, errmsg);
717 if (iface && iface->hdl) {
721 if (iface->rdTr->tr) {
723 int res =libusb_cancel_transfer(iface->rdTr->tr);
725 while(count && iface->rdTr->tr->status != LIBUSB_TRANSFER_CANCELLED){
732 res = libusb_release_interface(iface->hdl,iface->
ifaceno);
733 if(res != 0 && res!=LIBUSB_ERROR_NOT_FOUND && res!=LIBUSB_ERROR_NO_DEVICE){
737 res = libusb_attach_kernel_driver(iface->hdl,iface->
ifaceno);
738 if(res<0 && res!=LIBUSB_ERROR_NO_DEVICE){
741 libusb_close(iface->hdl);
744 if (iface->rdTr->tr) {
746 libusb_free_transfer(iface->rdTr->tr);
747 iface->rdTr->tr = NULL;
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
#define YERRMSG(code, message)
void yInitializeCriticalSection(yCRITICAL_SECTION *cs)
int yyySetup(yInterfaceSt *iface, char *errmsg)
int yyyUSBGetInterfaces(yInterfaceSt **ifaces, int *nbifaceDetect, char *errmsg)
void yLeaveCriticalSection(yCRITICAL_SECTION *cs)
YRETCODE yPktQueuePopH2D(yInterfaceSt *iface, pktItem **pkt)
int yyyUSB_init(yContextSt *ctx, char *errmsg)
#define HALENUMLOG(fmt, args...)
int yyySignalOutPkt(yInterfaceSt *iface, char *errmsg)
int yyyUSB_stop(yContextSt *ctx, char *errmsg)
YRETCODE yPktQueuePeekH2D(yInterfaceSt *iface, pktItem **pkt)
#define HALLOG(fmt, args...)
void yEnterCriticalSection(yCRITICAL_SECTION *cs)
char serial[YOCTO_SERIAL_LEN *2]
YRETCODE yPktQueuePushD2H(yInterfaceSt *iface, const USB_Packet *pkt, char *errmsg)
void yDeleteCriticalSection(yCRITICAL_SECTION *cs)
void yPktQueueFree(pktQueue *q)
u64 YAPI_FUNCTION_EXPORT yapiGetTickCount(void)
void yyyPacketShutdown(yInterfaceSt *iface)
struct _yInterfaceSt::@69 flags
char serial[YOCTO_SERIAL_LEN]
int yyyOShdlCompare(yPrivDeviceSt *dev, yInterfaceSt *newiface)
void yPktQueueInit(pktQueue *q)