before merging master
[inav.git] / lib / main / AT32F43x / Drivers / AT32F43x_StdPeriph_Driver / src / at32f435_437_usb.c
blob8c7afcbaa5a488493163a45a83f07cf7465d3c52
1 /**
2 **************************************************************************
3 * @file at32f435_437_usb.c
4 * @version v2.1.0
5 * @date 2022-08-16
6 * @brief contains all the functions for the usb firmware library
7 **************************************************************************
8 * Copyright notice & Disclaimer
10 * The software Board Support Package (BSP) that is made available to
11 * download from Artery official website is the copyrighted work of Artery.
12 * Artery authorizes customers to use, copy, and distribute the BSP
13 * software and its related documentation for the purpose of design and
14 * development in conjunction with Artery microcontrollers. Use of the
15 * software is governed by this copyright notice and the following disclaimer.
17 * THIS SOFTWARE IS PROVIDED ON "AS IS" BASIS WITHOUT WARRANTIES,
18 * GUARANTEES OR REPRESENTATIONS OF ANY KIND. ARTERY EXPRESSLY DISCLAIMS,
19 * TO THE FULLEST EXTENT PERMITTED BY LAW, ALL EXPRESS, IMPLIED OR
20 * STATUTORY OR OTHER WARRANTIES, GUARANTEES OR REPRESENTATIONS,
21 * INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
22 * FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
24 **************************************************************************
27 #include "at32f435_437_conf.h"
29 /** @addtogroup AT32F435_437_periph_driver
30 * @{
33 /** @defgroup USB
34 * @brief USB driver modules
35 * @{
38 #ifdef USB_MODULE_ENABLED
40 /** @defgroup USB_private_functions
41 * @{
44 #ifdef OTGFS_USB_GLOBAL
45 /**
46 * @brief usb global core soft reset
47 * @param usbx: to select the otgfs peripheral.
48 * this parameter can be one of the following values:
49 * - OTG1_GLOBAL
50 * - OTG2_GLOBAL
51 * @retval error status
53 error_status usb_global_reset(otg_global_type *usbx)
55 uint32_t timeout = 0;
56 while(usbx->grstctl_bit.ahbidle == RESET)
58 if(timeout ++ > 200000)
60 break;
63 timeout = 0;
64 usbx->grstctl_bit.csftrst = TRUE;
65 while(usbx->grstctl_bit.csftrst == SET)
67 if(timeout ++ > 200000)
69 break;
72 return SUCCESS;
75 /**
76 * @brief usb global initialization
77 * @param usbx: to select the otgfs peripheral.
78 * this parameter can be one of the following values:
79 * - OTG1_GLOBAL
80 * - OTG2_GLOBAL
81 * @retval none
83 void usb_global_init(otg_global_type *usbx)
85 /* reset otg moudle */
86 usb_global_reset(usbx);
88 /* exit power down mode */
89 usbx->gccfg_bit.pwrdown = TRUE;
92 /**
93 * @brief usb global select usb core (otg1 or otg2).
94 * @param usb_id: select otg1 or otg2
95 * this parameter can be one of the following values:
96 * - USB_OTG1_ID
97 * - USB_OTG2_ID
98 * @retval usb global register type pointer
100 otg_global_type *usb_global_select_core(uint8_t usb_id)
102 if(usb_id == USB_OTG1_ID)
104 /* use otg1 */
105 return OTG1_GLOBAL;
107 else
109 /* use otg2 */
110 return OTG2_GLOBAL;
115 * @brief flush tx fifo
116 * @param usbx: to select the otgfs peripheral.
117 * this parameter can be one of the following values:
118 * - OTG1_GLOBAL
119 * - OTG2_GLOBAL
120 * @param fifo_num: tx fifo num,when fifo_num=16,flush all tx fifo
121 * parameter as following values: 0-16
122 * @retval none
124 void usb_flush_tx_fifo(otg_global_type *usbx, uint32_t fifo_num)
126 uint32_t timeout = 0;
127 /* set flush fifo number */
128 usbx->grstctl_bit.txfnum = fifo_num;
130 /* start flush fifo */
131 usbx->grstctl_bit.txfflsh = TRUE;
133 while(usbx->grstctl_bit.txfflsh == TRUE)
135 if(timeout ++ > 200000)
137 break;
143 * @brief flush rx fifo
144 * @param usbx: to select the otgfs peripheral.
145 * this parameter can be one of the following values:
146 * - OTG1_GLOBAL
147 * - OTG2_GLOBAL
148 * @retval none
150 void usb_flush_rx_fifo(otg_global_type *usbx)
152 uint32_t timeout = 0;
153 usbx->grstctl_bit.rxfflsh = TRUE;
154 while(usbx->grstctl_bit.rxfflsh == TRUE)
156 if(timeout ++ > 200000)
158 break;
164 * @brief usb interrupt mask enable
165 * @param usbx: to select the otgfs peripheral.
166 * this parameter can be one of the following values:
167 * - OTG1_GLOBAL
168 * - OTG2_GLOBAL
169 * @param interrupt:
170 * this parameter can be any combination of the following values:
171 * - USB_OTG_MODEMIS_INT
172 * - USB_OTG_OTGINT_INT
173 * - USB_OTG_SOF_INT
174 * - USB_OTG_RXFLVL_INT
175 * - USB_OTG_NPTXFEMP_INT
176 * - USB_OTG_GINNAKEFF_INT
177 * - USB_OTG_GOUTNAKEFF_INT
178 * - USB_OTG_ERLYSUSP_INT
179 * - USB_OTG_USBSUSP_INT
180 * - USB_OTG_USBRST_INT
181 * - USB_OTG_ENUMDONE_INT
182 * - USB_OTG_ISOOUTDROP_INT
183 * - USB_OTG_IEPT_INT
184 * - USB_OTG_OEPT_INT
185 * - USB_OTG_INCOMISOIN_INT
186 * - USB_OTG_INCOMPIP_INCOMPISOOUT_INT
187 * - USB_OTG_PRT_INT
188 * - USB_OTG_HCH_INT
189 * - USB_OTG_PTXFEMP_INT
190 * - USB_OTG_CONIDSCHG_INT
191 * - USB_OTG_DISCON_INT
192 * - USB_OTG_WKUP_INT
193 * @param new_state: TRUE or FALSE
194 * @retval none
196 void usb_global_interrupt_enable(otg_global_type *usbx, uint16_t interrupt, confirm_state new_state)
198 if(new_state == TRUE)
200 usbx->gintmsk |= interrupt;
202 else
204 usbx->gintmsk &= ~interrupt;
209 * @brief get all global core interrupt flag
210 * @param usbx: to select the otgfs peripheral.
211 * this parameter can be one of the following values:
212 * - OTG1_GLOBAL
213 * - OTG2_GLOBAL
214 * @retval intterupt flag
216 uint32_t usb_global_get_all_interrupt(otg_global_type *usbx)
218 uint32_t intsts = usbx->gintsts;
219 return intsts & usbx->gintmsk;
223 * @brief clear the global interrupt flag
224 * @param usbx: to select the otgfs peripheral.
225 * this parameter can be one of the following values:
226 * - OTG1_GLOBAL
227 * - OTG2_GLOBAL
228 * @param flag: interrupt flag
229 * this parameter can be any combination of the following values:
230 * - USB_OTG_MODEMIS_FLAG
231 * - USB_OTG_OTGINT_FLAG
232 * - USB_OTG_SOF_FLAG
233 * - USB_OTG_RXFLVL_FLAG
234 * - USB_OTG_NPTXFEMP_FLAG
235 * - USB_OTG_GINNAKEFF_FLAG
236 * - USB_OTG_GOUTNAKEFF_FLAG
237 * - USB_OTG_ERLYSUSP_FLAG
238 * - USB_OTG_USBSUSP_FLAG
239 * - USB_OTG_USBRST_FLAG
240 * - USB_OTG_ENUMDONE_FLAG
241 * - USB_OTG_ISOOUTDROP_FLAG
242 * - USB_OTG_EOPF_FLAG
243 * - USB_OTG_IEPT_FLAG
244 * - USB_OTG_OEPT_FLAG
245 * - USB_OTG_INCOMISOIN_FLAG
246 * - USB_OTG_INCOMPIP_INCOMPISOOUT_FLAG
247 * - USB_OTG_PRT_FLAG
248 * - USB_OTG_HCH_FLAG
249 * - USB_OTG_PTXFEMP_FLAG
250 * - USB_OTG_CONIDSCHG_FLAG
251 * - USB_OTG_DISCON_FLAG
252 * - USB_OTG_WKUP_FLAG
253 * @retval none
255 void usb_global_clear_interrupt(otg_global_type *usbx, uint32_t flag)
257 usbx->gintsts = flag;
261 * @brief usb global interrupt enable
262 * @param usbx: to select the otgfs peripheral.
263 * this parameter can be one of the following values:
264 * OTG1_GLOBAL , OTG2_GLOBAL
265 * @retval none
267 void usb_interrupt_enable(otg_global_type *usbx)
269 usbx->gahbcfg_bit.glbintmsk = TRUE;
273 * @brief usb global interrupt disable
274 * @param usbx: to select the otgfs peripheral.
275 * this parameter can be one of the following values:
276 * - OTG1_GLOBAL
277 * - OTG2_GLOBAL
278 * @retval none
280 void usb_interrupt_disable(otg_global_type *usbx)
282 usbx->gahbcfg_bit.glbintmsk = FALSE;
286 * @brief usb set rx fifo size
287 * @param usbx: to select the otgfs peripheral.
288 * this parameter can be one of the following values:
289 * - OTG1_GLOBAL
290 * - OTG2_GLOBAL
291 * @param size: rx fifo size
292 * @retval none
294 void usb_set_rx_fifo(otg_global_type *usbx, uint16_t size)
296 usbx->grxfsiz = size;
300 * @brief usb set tx fifo size
301 * @param usbx: to select the otgfs peripheral.
302 * this parameter can be one of the following values:
303 * - OTG1_GLOBAL
304 * - OTG2_GLOBAL
305 * @param txfifo: the fifo number
306 * @param size: tx fifo size
307 * @retval none
309 void usb_set_tx_fifo(otg_global_type *usbx, uint8_t txfifo, uint16_t size)
311 uint8_t i_index = 0;
312 uint32_t offset = 0;
314 offset = usbx->grxfsiz;
315 if(txfifo == 0)
317 usbx->gnptxfsiz_ept0tx = offset | (size << 16);
319 else
321 offset += usbx->gnptxfsiz_ept0tx_bit.nptxfdep;
322 for(i_index = 0; i_index < (txfifo - 1); i_index ++)
324 offset += usbx->dieptxfn_bit[i_index].ineptxfdep;
326 usbx->dieptxfn[txfifo - 1] = offset | (size << 16);
332 * @brief set otg mode(device or host mode)
333 * @param usbx: to select the otgfs peripheral.
334 * this parameter can be one of the following values:
335 * - OTG1_GLOBAL
336 * - OTG2_GLOBAL
337 * @param mode:
338 this parameter can be one of the following values:
339 * - OTG_DEVICE_MODE
340 * - OTG_HOST_MODE
341 * - OTG_DRD_MODE
342 * @retval none
344 void usb_global_set_mode(otg_global_type *usbx, uint32_t mode)
346 /* set otg to device mode */
347 if(mode == OTG_DEVICE_MODE)
349 usbx->gusbcfg_bit.fhstmode = FALSE;
350 usbx->gusbcfg_bit.fdevmode = TRUE;
353 /* set otg to host mode */
354 if(mode == OTG_HOST_MODE)
356 usbx->gusbcfg_bit.fdevmode = FALSE;
357 usbx->gusbcfg_bit.fhstmode = TRUE;
360 /* set otg to default mode */
361 if(mode == OTG_DRD_MODE)
363 usbx->gusbcfg_bit.fdevmode = FALSE;
364 usbx->gusbcfg_bit.fhstmode = FALSE;
370 * @brief disable the transceiver power down mode
371 * @param usbx: to select the otgfs peripheral.
372 * this parameter can be one of the following values:
373 * - OTG1_GLOBAL
374 * - OTG2_GLOBAL
375 * @retval none
377 void usb_global_power_on(otg_global_type *usbx)
379 /* core soft reset */
380 usbx->grstctl_bit.csftrst = TRUE;
381 while(usbx->grstctl_bit.csftrst);
383 /* disable power down mode */
384 usbx->gccfg_bit.pwrdown = TRUE;
389 * @brief usb stop phy clock
390 * @param usbx: to select the otgfs peripheral.
391 * this parameter can be one of the following values:
392 * - OTG1_GLOBAL
393 * - OTG2_GLOBAL
394 * @retval none
396 void usb_stop_phy_clk(otg_global_type *usbx)
398 OTG_PCGCCTL(usbx)->pcgcctl_bit.stoppclk = TRUE;
402 * @brief usb open phy clock
403 * @param usbx: to select the otgfs peripheral.
404 * this parameter can be one of the following values:
405 * - OTG1_GLOBAL
406 * - OTG2_GLOBAL
407 * @retval none
409 void usb_open_phy_clk(otg_global_type *usbx)
411 OTG_PCGCCTL(usbx)->pcgcctl_bit.stoppclk = FALSE;
416 * @brief write data from user memory to usb buffer
417 * @param pusr_buf: point to user buffer
418 * @param offset_addr: endpoint tx offset address
419 * @param nbytes: number of bytes data write to usb buffer
420 * @retval none
422 void usb_write_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, uint16_t nbytes)
424 uint32_t n_index;
425 uint32_t nhbytes = (nbytes + 3) / 4;
426 uint32_t *pbuf = (uint32_t *)pusr_buf;
427 for(n_index = 0; n_index < nhbytes; n_index ++)
429 #if defined (__ICCARM__) && (__VER__ < 7000000)
430 USB_FIFO(usbx, num) = *(__packed uint32_t *)pbuf;
431 #else
432 USB_FIFO(usbx, num) = __UNALIGNED_UINT32_READ(pbuf);
433 #endif
434 pbuf ++;
439 * @brief read data from usb buffer to user buffer
440 * @param pusr_buf: point to user buffer
441 * @param offset_addr: endpoint rx offset address
442 * @param nbytes: number of bytes data write to usb buffer
443 * @retval none
445 void usb_read_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, uint16_t nbytes)
447 UNUSED(num);
448 uint32_t n_index;
449 uint32_t nhbytes = (nbytes + 3) / 4;
450 uint32_t *pbuf = (uint32_t *)pusr_buf;
451 for(n_index = 0; n_index < nhbytes; n_index ++)
453 #if defined (__ICCARM__) && (__VER__ < 7000000)
454 *(__packed uint32_t *)pbuf = USB_FIFO(usbx, 0);
455 #else
456 __UNALIGNED_UINT32_WRITE(pbuf, (USB_FIFO(usbx, 0)));
457 #endif
458 pbuf ++;
461 #endif
464 #ifdef OTGFS_USB_DEVICE
466 * @brief open usb endpoint
467 * @param usbx: to select the otgfs peripheral.
468 * this parameter can be one of the following values:
469 * - OTG1_GLOBAL
470 * - OTG2_GLOBAL
471 * @param ept_info: endpoint information structure
472 * @retval none
474 void usb_ept_open(otg_global_type *usbx, usb_ept_info *ept_info)
476 uint8_t mps = USB_EPT0_MPS_64;
477 if(ept_info->eptn == USB_EPT0)
479 if(ept_info->maxpacket == 0x40)
481 mps = USB_EPT0_MPS_64;
483 else if(ept_info->maxpacket == 0x20)
485 mps = USB_EPT0_MPS_32;
487 else if(ept_info->maxpacket == 0x10)
489 mps = USB_EPT0_MPS_16;
491 else if(ept_info->maxpacket == 0x08)
493 mps = USB_EPT0_MPS_8;
496 /* endpoint direction is in */
497 if(ept_info->inout == EPT_DIR_IN)
499 OTG_DEVICE(usbx)->daintmsk |= 1 << ept_info->eptn;
500 if(ept_info->eptn == USB_EPT0)
502 USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.mps = mps;
504 else
506 USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.mps = ept_info->maxpacket;
508 USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.eptype = ept_info->trans_type;
509 USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.txfnum = ept_info->eptn;
510 USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.setd0pid = TRUE;
511 USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.usbacept = TRUE;
513 /* endpoint direction is out */
514 else
516 OTG_DEVICE(usbx)->daintmsk |= (1 << ept_info->eptn) << 16;
517 if(ept_info->eptn == USB_EPT0)
519 USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.mps = mps;
521 else
523 USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.mps = ept_info->maxpacket;
525 USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.eptype = ept_info->trans_type;
526 USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.setd0pid = TRUE;
527 USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.usbacept = TRUE;
532 * @brief close usb endpoint
533 * @param usbx: to select the otgfs peripheral.
534 * this parameter can be one of the following values:
535 * - OTG1_GLOBAL
536 * - OTG2_GLOBAL
537 * @param ept_info: endpoint information structure
538 * @retval none
540 void usb_ept_close(otg_global_type *usbx, usb_ept_info *ept_info)
542 if(ept_info->inout == EPT_DIR_IN)
544 OTG_DEVICE(usbx)->daintmsk &= ~(1 << ept_info->eptn);
545 USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.usbacept = FALSE;
547 else
549 OTG_DEVICE(usbx)->daintmsk &= ~((1 << ept_info->eptn) << 16);
550 USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.usbacept = FALSE;
556 * @brief set endpoint tx or rx status to stall
557 * @param usbx: to select the otgfs peripheral.
558 * this parameter can be one of the following values:
559 * - OTG1_GLOBAL
560 * - OTG2_GLOBAL
561 * @param ept_info: endpoint information structure
562 * @retval none
564 void usb_ept_stall(otg_global_type *usbx, usb_ept_info *ept_info)
566 if(ept_info->inout == EPT_DIR_IN)
568 if(USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.eptena == RESET)
570 USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.eptdis = FALSE;
572 USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.stall = SET;
574 else
576 if(USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.eptena == RESET)
578 USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.eptdis = FALSE;
580 USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.stall = TRUE;
585 * @brief clear endpoint tx or rx status to stall
586 * @param usbx: to select the otgfs peripheral.
587 * this parameter can be one of the following values:
588 * - OTG1_GLOBAL
589 * - OTG2_GLOBAL
590 * @param ept_info: endpoint information structure
591 * @retval none
593 void usb_ept_clear_stall(otg_global_type *usbx, usb_ept_info *ept_info)
595 if(ept_info->inout == EPT_DIR_IN)
597 USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.stall = FALSE;
598 if(ept_info->trans_type == EPT_INT_TYPE || ept_info->trans_type == EPT_BULK_TYPE)
600 USB_INEPT(usbx, ept_info->eptn)->diepctl_bit.setd0pid = TRUE;
603 else
605 USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.stall = FALSE;
606 if(ept_info->trans_type == EPT_INT_TYPE || ept_info->trans_type == EPT_BULK_TYPE)
608 USB_OUTEPT(usbx, ept_info->eptn)->doepctl_bit.setd0pid = TRUE;
614 * @brief get all out endpoint interrupt bits
615 * @param usbx: to select the otgfs peripheral.
616 * this parameter can be one of the following values:
617 * - OTG1_GLOBAL
618 * - OTG2_GLOBAL
619 * @retval out endpoint interrupt bits
621 uint32_t usb_get_all_out_interrupt(otg_global_type *usbx)
623 uint32_t intsts = OTG_DEVICE(usbx)->daint;
624 return ((intsts & (OTG_DEVICE(usbx)->daintmsk)) >> 16);
628 * @brief get all in endpoint interrupt bits
629 * @param usbx: to select the otgfs peripheral.
630 * this parameter can be one of the following values:
631 * - OTG1_GLOBAL
632 * - OTG2_GLOBAL
633 * @retval in endpoint interrupt bits
635 uint32_t usb_get_all_in_interrupt(otg_global_type *usbx)
637 uint32_t intsts = OTG_DEVICE(usbx)->daint;
638 return ((intsts & (OTG_DEVICE(usbx)->daintmsk)) & 0xFFFF);
643 * @brief get out endpoint interrupt flag
644 * @param usbx: to select the otgfs peripheral.
645 * this parameter can be one of the following values:
646 * - OTG1_GLOBAL
647 * - OTG2_GLOBAL
648 * @param eptn: endpoint number
649 * @retval out endpoint interrupt flags
651 uint32_t usb_ept_out_interrupt(otg_global_type *usbx, uint32_t eptn)
653 uint32_t intsts = USB_OUTEPT(usbx, eptn)->doepint;
654 return (intsts & (OTG_DEVICE(usbx)->doepmsk));
658 * @brief get in endpoint interrupt flag
659 * @param usbx: to select the otgfs peripheral.
660 * this parameter can be one of the following values:
661 * - OTG1_GLOBAL
662 * - OTG2_GLOBAL
663 * @param eptn: endpoint number
664 * @retval in endpoint intterupt flags
666 uint32_t usb_ept_in_interrupt(otg_global_type *usbx, uint32_t eptn)
668 uint32_t intsts, mask1, mask2;
669 mask1 = OTG_DEVICE(usbx)->diepmsk;
670 mask2 = OTG_DEVICE(usbx)->diepempmsk;
671 mask1 |= ((mask2 >> eptn) & 0x1) << 7;
672 intsts = USB_INEPT(usbx, eptn)->diepint & mask1;
673 return intsts;
677 * @brief clear out endpoint interrupt flag
678 * @param usbx: to select the otgfs peripheral.
679 * this parameter can be one of the following values:
680 * - OTG1_GLOBAL
681 * - OTG2_GLOBAL
682 * @param eptn: endpoint number
683 * @retval flag: interrupt flag
684 * this parameter can be any combination of the following values:
685 * - USB_OTG_DOEPINT_XFERC_FLAG
686 * - USB_OTG_DOEPINT_EPTDISD_FLAG
687 * - USB_OTG_DOEPINT_SETUP_FLAG
688 * - USB_OTG_DOEPINT_OTEPDIS_FLAG
689 * - USB_OTG_DOEPINT_B2BSTUP_FLAG
691 void usb_ept_out_clear(otg_global_type *usbx, uint32_t eptn, uint32_t flag)
693 USB_OUTEPT(usbx, eptn)->doepint = flag;
697 * @brief clear in endpoint interrupt flag
698 * @param usbx: to select the otgfs peripheral.
699 * this parameter can be one of the following values:
700 * - OTG1_GLOBAL
701 * - OTG2_GLOBAL
702 * @param eptn: endpoint number
703 * @retval flag: interrupt flag
704 * this parameter can be any combination of the following values:
705 * - USB_OTG_DIEPINT_XFERC_FLAG
706 * - USB_OTG_DIEPINT_EPTDISD_FLAG
707 * - USB_OTG_DIEPINT_TMROC_FLAG
708 * - USB_OTG_DIEPINT_INTTXFE_FLAG
709 * - USB_OTG_DIEPINT_INEPNE_FLAG
710 * - USB_OTG_DIEPINT_TXFE_FLAG
712 void usb_ept_in_clear(otg_global_type *usbx, uint32_t eptn, uint32_t flag)
714 USB_INEPT(usbx, eptn)->diepint = flag;
719 * @brief set the host assignment address
720 * @param usbx: to select the otgfs peripheral.
721 * this parameter can be one of the following values:
722 * - OTG1_GLOBAL
723 * - OTG2_GLOBAL
724 * @param address: host assignment address
725 * @retval none
727 void usb_set_address(otg_global_type *usbx, uint8_t address)
729 OTG_DEVICE(usbx)->dcfg_bit.devaddr = address;
733 * @brief enable endpoint 0 out
734 * @param usbx: to select the otgfs peripheral.
735 * this parameter can be one of the following values:
736 * - OTG1_GLOBAL
737 * - OTG2_GLOBAL
738 * @retval none
740 void usb_ept0_start(otg_global_type *usbx)
742 otg_eptout_type *usb_outept = USB_OUTEPT(usbx, 0);
743 usb_outept->doeptsiz = 0;
744 usb_outept->doeptsiz_bit.pktcnt = 1;
745 usb_outept->doeptsiz_bit.xfersize = 24;
746 usb_outept->doeptsiz_bit.rxdpid_setupcnt = 3;
751 * @brief endpoint 0 start setup
752 * @param usbx: to select the otgfs peripheral.
753 * this parameter can be one of the following values:
754 * - OTG1_GLOBAL
755 * - OTG2_GLOBAL
756 * @retval none
758 void usb_ept0_setup(otg_global_type *usbx)
760 USB_INEPT(usbx, 0)->diepctl_bit.mps = 0;
761 OTG_DEVICE(usbx)->dctl_bit.cgnpinak = FALSE;
765 * @brief connect usb device by enable pull-up
766 * @param usbx: to select the otgfs peripheral.
767 * this parameter can be one of the following values:
768 * - OTG1_GLOBAL
769 * - OTG2_GLOBAL
770 * @retval none
772 void usb_connect(otg_global_type *usbx)
774 /* D+ 1.5k pull-up enable */
775 OTG_DEVICE(usbx)->dctl_bit.sftdiscon = FALSE;
779 * @brief disconnect usb device by disable pull-up
780 * @param usbx: to select the otgfs peripheral.
781 * this parameter can be one of the following values:
782 * - OTG1_GLOBAL
783 * - OTG2_GLOBAL
784 * @retval none
786 void usb_disconnect(otg_global_type *usbx)
788 /* D+ 1.5k pull-up disable */
789 OTG_DEVICE(usbx)->dctl_bit.sftdiscon = TRUE;
794 * @brief usb remote wakeup set
795 * @param usbx: to select the otgfs peripheral.
796 * this parameter can be one of the following values:
797 * - OTG1_GLOBAL
798 * - OTG2_GLOBAL
799 * @retval none
801 void usb_remote_wkup_set(otg_global_type *usbx)
803 OTG_DEVICE(usbx)->dctl_bit.rwkupsig = TRUE;
807 * @brief usb remote wakeup clear
808 * @param usbx: to select the otgfs peripheral.
809 * this parameter can be one of the following values:
810 * - OTG1_GLOBAL
811 * - OTG2_GLOBAL
812 * @retval none
814 void usb_remote_wkup_clear(otg_global_type *usbx)
816 OTG_DEVICE(usbx)->dctl_bit.rwkupsig = FALSE;
820 * @brief usb suspend status get
821 * @param usbx: to select the otgfs peripheral.
822 * this parameter can be one of the following values:
823 * - OTG1_GLOBAL
824 * - OTG2_GLOBAL
825 * @retval usb suspend status
827 uint8_t usb_suspend_status_get(otg_global_type *usbx)
829 return OTG_DEVICE(usbx)->dsts_bit.suspsts;
831 #endif
833 #ifdef OTGFS_USB_HOST
835 * @brief usb port power on
836 * @param usbx: to select the otgfs peripheral.
837 * this parameter can be one of the following values:
838 * - OTG1_GLOBAL
839 * - OTG2_GLOBAL
840 * @param state: state (TRUE or FALSE)
841 * @retval none
843 void usb_port_power_on(otg_global_type *usbx, confirm_state state)
845 otg_host_type *usb_host = OTG_HOST(usbx);
846 uint32_t hprt_val = usb_host->hprt;
848 hprt_val &= ~(USB_OTG_HPRT_PRTENA | USB_OTG_HPRT_PRTENCHNG |
849 USB_OTG_HPRT_PRTOVRCACT | USB_OTG_HPRT_PRTCONDET);
851 if(state == TRUE)
853 usb_host->hprt = hprt_val | USB_OTG_HPRT_PRTPWR;
855 else
857 usb_host->hprt = hprt_val & (~USB_OTG_HPRT_PRTPWR);
862 * @brief get current frame number
863 * @param usbx: to select the otgfs peripheral.
864 * this parameter can be one of the following values:
865 * - OTG1_GLOBAL
866 * - OTG2_GLOBAL
867 * @retval none
869 uint32_t usbh_get_frame(otg_global_type *usbx)
871 otg_host_type *usb_host = OTG_HOST(usbx);
872 return usb_host->hfnum & 0xFFFF;
876 * @brief enable one host channel
877 * @param usbx: to select the otgfs peripheral.
878 * this parameter can be one of the following values:
879 * - OTG1_GLOBAL
880 * - OTG2_GLOBAL
881 * @param chn: host channel number
882 * @param ept_num: devvice endpoint number
883 * @param dev_address: device address
884 * @param type: channel transfer type
885 * this parameter can be one of the following values:
886 * - EPT_CONTROL_TYPE
887 * - EPT_BULK_TYPE
888 * - EPT_INT_TYPE
889 * - EPT_ISO_TYPE
890 * @param maxpacket: support max packe size for this channel
891 * @param speed: device speed
892 * this parameter can be one of the following values:
893 * - USB_PRTSPD_FULL_SPEED
894 * - USB_PRTSPD_LOW_SPEED
895 * @retval none
897 void usb_hc_enable(otg_global_type *usbx,
898 uint8_t chn,
899 uint8_t ept_num,
900 uint8_t dev_address,
901 uint8_t type,
902 uint16_t maxpacket,
903 uint8_t speed)
905 otg_hchannel_type *hch = USB_CHL(usbx, chn);
906 otg_host_type *usb_host = OTG_HOST(usbx);
908 switch(type)
910 case EPT_CONTROL_TYPE:
911 case EPT_BULK_TYPE:
912 hch->hcintmsk |= USB_OTG_HC_XFERCM_INT | USB_OTG_HC_STALLM_INT |
913 USB_OTG_HC_XACTERRM_INT | USB_OTG_HC_NAKM_INT |
914 USB_OTG_HC_DTGLERRM_INT;
915 if(ept_num & 0x80)
917 hch->hcintmsk_bit.bblerrmsk = TRUE;
919 break;
920 case EPT_INT_TYPE:
921 hch->hcintmsk |= USB_OTG_HC_XFERCM_INT | USB_OTG_HC_STALLM_INT |
922 USB_OTG_HC_XACTERRM_INT | USB_OTG_HC_NAKM_INT |
923 USB_OTG_HC_DTGLERRM_INT | USB_OTG_HC_FRMOVRRUN_INT;
924 break;
925 case EPT_ISO_TYPE:
927 hch->hcintmsk |= USB_OTG_HC_XFERCM_INT | USB_OTG_HC_ACKM_INT |
928 USB_OTG_HC_FRMOVRRUN_INT;
929 break;
931 usb_host->haintmsk |= 1 << chn;
932 usbx->gintmsk_bit.hchintmsk = TRUE;
934 hch->hcchar_bit.devaddr = dev_address;
935 hch->hcchar_bit.eptnum = ept_num & 0x7F;
936 hch->hcchar_bit.eptdir = (ept_num & 0x80)?1:0;
937 hch->hcchar_bit.lspddev = (speed == USB_PRTSPD_LOW_SPEED)?1:0;
938 hch->hcchar_bit.eptype = type;
939 hch->hcchar_bit.mps = maxpacket;
941 if(type == EPT_INT_TYPE)
943 hch->hcchar_bit.oddfrm = TRUE;
948 * @brief host read channel interrupt
949 * @param usbx: to select the otgfs peripheral.
950 * this parameter can be one of the following values:
951 * - OTG1_GLOBAL
952 * - OTG2_GLOBAL
953 * @retval interrupt flag
955 uint32_t usb_hch_read_interrupt(otg_global_type *usbx)
957 otg_host_type *usb_host = OTG_HOST(usbx);
958 return usb_host->haint & 0xFFFF;
962 * @brief disable host
963 * @param usbx: to select the otgfs peripheral.
964 * this parameter can be one of the following values:
965 * - OTG1_GLOBAL
966 * - OTG2_GLOBAL
967 * @retval none
969 void usb_host_disable(otg_global_type *usbx)
971 uint32_t i_index = 0, count = 0;
972 otg_hchannel_type *hch;
973 otg_host_type *usb_host = OTG_HOST(usbx);
975 usbx->gahbcfg_bit.glbintmsk = FALSE;
976 usb_flush_rx_fifo(usbx);
977 usb_flush_tx_fifo(usbx, 0x10);
979 for(i_index = 0; i_index < 16; i_index ++)
981 hch = USB_CHL(usbx, i_index);
982 hch->hcchar_bit.chdis = TRUE;
983 hch->hcchar_bit.chena = FALSE;
984 hch->hcchar_bit.eptdir = 0;
987 for(i_index = 0; i_index < 16; i_index ++)
989 hch = USB_CHL(usbx, i_index);
990 hch->hcchar_bit.chdis = TRUE;
991 hch->hcchar_bit.chena = TRUE;
992 hch->hcchar_bit.eptdir = 0;
995 if(count ++ > 1000)
996 break;
997 }while(hch->hcchar_bit.chena);
999 usb_host->haint = 0xFFFFFFFF;
1000 usbx->gintsts = 0xFFFFFFFF;
1001 usbx->gahbcfg_bit.glbintmsk = TRUE;
1005 * @brief halt channel
1006 * @param usbx: to select the otgfs peripheral.
1007 * this parameter can be one of the following values:
1008 * - OTG1_GLOBAL
1009 * - OTG2_GLOBAL
1010 * @param chn: channel number
1011 * @retval none
1013 void usb_hch_halt(otg_global_type *usbx, uint8_t chn)
1015 uint32_t count = 0;
1016 otg_hchannel_type *usb_chh = USB_CHL(usbx, chn);
1017 otg_host_type *usb_host = OTG_HOST(usbx);
1019 /* endpoint type is control or bulk */
1020 if(usb_chh->hcchar_bit.eptype == EPT_CONTROL_TYPE ||
1021 usb_chh->hcchar_bit.eptype == EPT_BULK_TYPE)
1023 usb_chh->hcchar_bit.chdis = TRUE;
1024 if((usbx->gnptxsts_bit.nptxqspcavail) == 0)
1026 usb_chh->hcchar_bit.chena = FALSE;
1027 usb_chh->hcchar_bit.chena = TRUE;
1030 if(count ++ > 1000)
1031 break;
1032 }while(usb_chh->hcchar_bit.chena == SET);
1034 else
1036 usb_chh->hcchar_bit.chena = TRUE;
1039 else
1041 usb_chh->hcchar_bit.chdis = TRUE;
1042 if((usb_host->hptxsts_bit.ptxqspcavil) == 0)
1044 usb_chh->hcchar_bit.chena = FALSE;
1045 usb_chh->hcchar_bit.chena = TRUE;
1048 if(count ++ > 1000)
1049 break;
1050 }while(usb_chh->hcchar_bit.chena == SET);
1052 else
1054 usb_chh->hcchar_bit.chena = TRUE;
1059 * @brief select full or low speed clock
1060 * @param usbx: to select the otgfs peripheral.
1061 * this parameter can be one of the following values:
1062 * - OTG1_GLOBAL
1063 * - OTG2_GLOBAL
1064 * @param clk: clock frequency
1065 * @retval none
1067 void usbh_fsls_clksel(otg_global_type *usbx, uint8_t clk)
1069 otg_host_type *usb_host = OTG_HOST(usbx);
1071 usb_host->hcfg_bit.fslspclksel = clk;
1072 if(clk == USB_HCFG_CLK_6M)
1074 usb_host->hfir = 6000;
1076 else
1078 usb_host->hfir = 48000;
1081 #endif
1085 * @}
1088 #endif
1091 * @}
1095 * @}