before merging master
[inav.git] / lib / main / AT32F43x / Drivers / AT32F43x_StdPeriph_Driver / src / at32f435_437_emac.c
blobc1dbe1ef5e5c78ea2185a72614b9fb14a1207398
1 /**
2 **************************************************************************
3 * @file at32f435_437_emac.c
4 * @version v2.1.0
5 * @date 2022-08-16
6 * @brief contains all the functions for the emac 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 EMAC
34 * @brief EMAC driver modules
35 * @{
38 #ifdef EMAC_MODULE_ENABLED
40 /** @defgroup EMAC_private_functions
41 * @{
44 #if defined (EMAC_BASE)
45 /**
46 * @brief global pointers on tx and rx descriptor used to track transmit and receive descriptors
48 emac_dma_desc_type *dma_tx_desc_to_set;
49 emac_dma_desc_type *dma_rx_desc_to_get;
51 /* emac private function */
52 static void emac_delay(uint32_t delay);
54 /**
55 * @brief deinitialize the emac peripheral registers to their default reset values.
56 * @param none
57 * @retval none
59 void emac_reset(void)
61 crm_periph_reset(CRM_EMAC_PERIPH_RESET, TRUE);
62 crm_periph_reset(CRM_EMAC_PERIPH_RESET, FALSE);
65 /**
66 * @brief initialize emac control structure
67 * @param emac_control_config_type
68 * @retval none
70 void emac_control_para_init(emac_control_config_type *control_para)
72 control_para->auto_nego = EMAC_AUTO_NEGOTIATION_OFF;
73 control_para->auto_pad_crc_strip = FALSE;
74 control_para->back_off_limit = EMAC_BACKOFF_LIMIT_0;
75 control_para->carrier_sense_disable = FALSE;
76 control_para->deferral_check = FALSE;
77 control_para->duplex_mode = EMAC_HALF_DUPLEX;
78 control_para->fast_ethernet_speed = EMAC_SPEED_10MBPS;
79 control_para->interframe_gap = EMAC_INTERFRAME_GAP_96BIT;
80 control_para->ipv4_checksum_offload = FALSE;
81 control_para->jabber_disable = FALSE;
82 control_para->loopback_mode = FALSE;
83 control_para->receive_own_disable = FALSE;
84 control_para->retry_disable = FALSE;
85 control_para->watchdog_disable = FALSE;
88 /**
89 * @brief according to hclk to set mdc clock frequency.
90 * @param none
91 * @retval none
93 void emac_clock_range_set(void)
95 uint8_t bits_value = 0;
96 crm_clocks_freq_type clocks_freq = {0};
98 /* clear clock range bits */
99 EMAC->miiaddr_bit.cr = bits_value;
101 crm_clocks_freq_get(&clocks_freq);
103 if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_20MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_35MHZ))
105 bits_value = EMAC_CLOCK_RANGE_20_TO_35;
107 else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_35MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_60MHZ))
109 bits_value = EMAC_CLOCK_RANGE_35_TO_60;
111 else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_60MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_100MHZ))
113 bits_value = EMAC_CLOCK_RANGE_60_TO_100;
115 else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_100MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_150MHZ))
117 bits_value = EMAC_CLOCK_RANGE_100_TO_150;
119 else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_150MHZ) && (clocks_freq.ahb_freq < EMAC_HCLK_BORDER_250MHZ))
121 bits_value = EMAC_CLOCK_RANGE_150_TO_250;
123 else if((clocks_freq.ahb_freq >= EMAC_HCLK_BORDER_250MHZ) && (clocks_freq.ahb_freq <= EMAC_HCLK_BORDER_288MHZ))
125 bits_value = EMAC_CLOCK_RANGE_250_TO_288;
128 EMAC->miiaddr_bit.cr = bits_value;
132 * @brief configure emac control setting.
133 * @param control_struct: control setting of mac control register.
134 * @retval none
136 void emac_control_config(emac_control_config_type *control_struct)
138 emac_deferral_check_set(control_struct->deferral_check);
139 emac_backoff_limit_set(control_struct->back_off_limit);
140 emac_auto_pad_crc_stripping_set(control_struct->auto_pad_crc_strip);
141 emac_retry_disable(control_struct->retry_disable);
142 emac_ipv4_checksum_offload_set(control_struct->ipv4_checksum_offload);
143 emac_loopback_mode_enable(control_struct->loopback_mode);
144 emac_receive_own_disable(control_struct->receive_own_disable);
145 emac_carrier_sense_disable(control_struct->carrier_sense_disable);
146 emac_interframe_gap_set(control_struct->interframe_gap);
147 emac_jabber_disable(control_struct->jabber_disable);
148 emac_watchdog_disable(control_struct->watchdog_disable);
152 * @brief reset emac dma
153 * @param none
154 * @retval none
156 void emac_dma_software_reset_set(void)
158 EMAC_DMA->bm_bit.swr = 1;
162 * @brief get emac dma reset status
163 * @param none
164 * @retval TRUE of FALSE
166 flag_status emac_dma_software_reset_get(void)
168 if(EMAC_DMA->bm_bit.swr)
170 return SET;
172 else
174 return RESET;
179 * @brief enable emac and dma reception/transmission
180 * @param none
181 * @retval none
183 void emac_start(void)
185 /* enable transmit state machine of the mac for transmission on the mii */
186 emac_trasmitter_enable(TRUE);
188 /* flush transmit fifo */
189 emac_dma_operations_set(EMAC_DMA_OPS_FLUSH_TRANSMIT_FIFO, TRUE);
191 /* enable receive state machine of the mac for reception from the mii */
192 emac_receiver_enable(TRUE);
194 /* start dma transmission */
195 emac_dma_operations_set(EMAC_DMA_OPS_START_STOP_TRANSMIT, TRUE);
197 /* start dma reception */
198 emac_dma_operations_set(EMAC_DMA_OPS_START_STOP_RECEIVE, TRUE);
202 * @brief stop emac and dma reception/transmission
203 * @param none
204 * @retval none
206 void emac_stop(void)
208 /* stop dma transmission */
209 emac_dma_operations_set(EMAC_DMA_OPS_START_STOP_TRANSMIT, FALSE);
211 /* stop dma reception */
212 emac_dma_operations_set(EMAC_DMA_OPS_START_STOP_RECEIVE, FALSE);
214 /* stop receive state machine of the mac for reception from the mii */
215 emac_receiver_enable(FALSE);
217 /* flush transmit fifo */
218 emac_dma_operations_set(EMAC_DMA_OPS_FLUSH_TRANSMIT_FIFO, TRUE);
220 /* stop transmit state machine of the mac for transmission on the mii */
221 emac_trasmitter_enable(FALSE);
226 * @brief write phy data.
227 * @param address: phy address.
228 * @param reg: register of phy.
229 * @param data: value that wants to write to phy.
230 * @retval SUCCESS or ERROR
232 error_status emac_phy_register_write(uint8_t address, uint8_t reg, uint16_t data)
234 uint32_t timeout = 0;
236 EMAC->miidt_bit.md = data;
238 EMAC->miiaddr_bit.pa = address;
239 EMAC->miiaddr_bit.mii = reg;
240 EMAC->miiaddr_bit.mw = 1;
241 EMAC->miiaddr_bit.mb = 1;
245 timeout++;
246 } while((EMAC->miiaddr_bit.mb) && (timeout < PHY_TIMEOUT));
248 if(timeout == PHY_TIMEOUT)
250 return ERROR;
252 return SUCCESS;
256 * @brief read phy data
257 * @param address: phy address.
258 * @param reg: register of phy.
259 * @param data: value that is read from phy.
260 * @retval SUCCESS or ERROR
262 error_status emac_phy_register_read(uint8_t address, uint8_t reg, uint16_t *data)
264 uint32_t timeout = 0;
266 EMAC->miiaddr_bit.pa = address;
267 EMAC->miiaddr_bit.mii = reg;
268 EMAC->miiaddr_bit.mw = 0;
269 EMAC->miiaddr_bit.mb = 1;
273 timeout++;
274 *data = EMAC->miidt_bit.md;
275 } while((EMAC->miiaddr_bit.mb) && (timeout < PHY_TIMEOUT));
277 if(timeout == PHY_TIMEOUT)
279 return ERROR;
282 *data = EMAC->miidt_bit.md;
283 return SUCCESS;
287 * @brief emac receiver enable.
288 * @param new_state: TRUE or FALSE.
289 * @retval none
291 void emac_receiver_enable(confirm_state new_state)
293 __IO uint32_t temp = 0;
295 EMAC->ctrl_bit.re = new_state;
297 temp = EMAC->ctrl;
298 emac_delay(1);
299 EMAC->ctrl = temp;
303 * @brief emac transmitter enable.
304 * @param new_state: TRUE or FALSE.
305 * @retval none
307 void emac_trasmitter_enable(confirm_state new_state)
309 __IO uint32_t temp = 0;
311 EMAC->ctrl_bit.te = new_state;
313 temp = EMAC->ctrl;
314 emac_delay(1);
315 EMAC->ctrl = temp;
319 * @brief emac defferal check enable, only avalible in half-duplex mode.
320 * @param new_state: TRUE or FALSE.
321 * @retval none
323 void emac_deferral_check_set(confirm_state new_state)
325 EMAC->ctrl_bit.dc = new_state;
329 * @brief emac back-off limit, only avalible in half-duplex mode.
330 * @param slot_time: waiting time of retransmission after collision
331 * this parameter can be one of the following values:
332 * - EMAC_BACKOFF_LIMIT_0
333 * - EMAC_BACKOFF_LIMIT_1
334 * - EMAC_BACKOFF_LIMIT_2
335 * - EMAC_BACKOFF_LIMIT_3
336 * @retval none
338 void emac_backoff_limit_set(emac_bol_type slot_time)
340 EMAC->ctrl_bit.bl = slot_time;
344 * @brief set mac automatic pad/CRC stripping.
345 * @param new_state: TRUE or FALSE.
346 * @retval none
348 void emac_auto_pad_crc_stripping_set(confirm_state new_state)
350 EMAC->ctrl_bit.acs = new_state;
354 * @brief transmittion retry disable.
355 * @param new_state: TRUE or FALSE.
356 * @retval none
358 void emac_retry_disable(confirm_state new_state)
360 EMAC->ctrl_bit.dr = new_state;
364 * @brief set ipv4 checksum offload.
365 * @param new_state: TRUE or FALSE.
366 * @retval none
368 void emac_ipv4_checksum_offload_set(confirm_state new_state)
370 EMAC->ctrl_bit.ipc = new_state;
374 * @brief enable loopback mode.
375 * @param new_state: TRUE or FALSE.
376 * @retval none
378 void emac_loopback_mode_enable(confirm_state new_state)
380 EMAC->ctrl_bit.lm = new_state;
384 * @brief receive own disable.
385 * @param new_state: TRUE or FALSE.
386 * @retval none
388 void emac_receive_own_disable(confirm_state new_state)
390 EMAC->ctrl_bit.dro = new_state;
394 * @brief carrier sense disbale.
395 * @param new_state: TRUE or FALSE.
396 * @retval none
398 void emac_carrier_sense_disable(confirm_state new_state)
400 EMAC->ctrl_bit.dcs = new_state;
404 * @brief set minimum interframe gap between frames during transmission.
405 * @param number: interframe gap number.
406 * this parameter can be one of the following values:
407 * - EMAC_FRAME_GAP_96BIT
408 * - EMAC_FRAME_GAP_88BIT
409 * - EMAC_FRAME_GAP_80BIT
410 * - EMAC_FRAME_GAP_72BIT
411 * - EMAC_FRAME_GAP_64BIT
412 * - EMAC_FRAME_GAP_56BIT
413 * - EMAC_FRAME_GAP_48BIT
414 * - EMAC_FRAME_GAP_40BIT
415 * @retval none
417 void emac_interframe_gap_set(emac_intergrame_gap_type number)
419 EMAC->ctrl_bit.ifg = number;
423 * @brief jabber disable.
424 * @param new_state: TRUE or FALSE.
425 * @retval none
427 void emac_jabber_disable(confirm_state new_state)
429 EMAC->ctrl_bit.jd = new_state;
433 * @brief watchdog disable.
434 * @param new_state: TRUE or FALSE.
435 * @retval none
437 void emac_watchdog_disable(confirm_state new_state)
439 EMAC->ctrl_bit.wd = new_state;
443 * @brief set mac fast emac speed.
444 * @param speed: mac bandwidth
445 * this parameter can be one of the following values:
446 * - EMAC_SPEED_10MBPS
447 * - EMAC_SPEED_100MBPS
448 * @retval none
450 void emac_fast_speed_set(emac_speed_type speed)
452 EMAC->ctrl_bit.fes = speed;
456 * @brief set duplex mode.
457 * @param duplex_mode: communication mode
458 * this parameter can be one of the following values:
459 * - EMAC_HALF_DUPLEX
460 * - EMAC_FULL_DUPLEX
461 * @retval none
463 void emac_duplex_mode_set(emac_duplex_type duplex_mode)
465 EMAC->ctrl_bit.dm = duplex_mode;
469 * @brief set mac promiscuous mode.
470 * @param new_state: TRUE or FALSE.
471 * @retval none
473 void emac_promiscuous_mode_set(confirm_state new_state)
475 EMAC->frmf_bit.pr = new_state;
479 * @brief hash unicast.
480 * @param new_state: TRUE or FALSE.
481 * @retval none
483 void emac_hash_unicast_set(confirm_state new_state)
485 EMAC->frmf_bit.huc = new_state;
489 * @brief hash multicast.
490 * @param new_state: TRUE or FALSE.
491 * @retval none
493 void emac_hash_multicast_set(confirm_state new_state)
495 EMAC->frmf_bit.hmc = new_state;
499 * @brief destination address inverse filtering.
500 * @param new_state: TRUE or FALSE.
501 * @retval none
503 void emac_dstaddr_inverse_filter_set(confirm_state new_state)
505 EMAC->frmf_bit.daif = new_state;
509 * @brief pass all multicasting frames.
510 * @param new_state: TRUE or FALSE.
511 * @retval none
513 void emac_pass_all_multicasting_set(confirm_state new_state)
515 EMAC->frmf_bit.pmc = new_state;
519 * @brief broadcast frames disable.
520 * @param new_state: TRUE or FALSE.
521 * @retval none
523 void emac_broadcast_frames_disable(confirm_state new_state)
525 EMAC->frmf_bit.dbf = new_state;
529 * @brief set mac how to pass control frames.
530 * @param condition: set what control frame can pass filter.
531 * this parameter can be one of the following values:
532 * - EMAC_CONTROL_FRAME_PASSING_NO
533 * - EMAC_CONTROL_FRAME_PASSING_ALL
534 * - EMAC_CONTROL_FRAME_PASSING_MATCH
535 * @retval none
537 void emac_pass_control_frames_set(emac_control_frames_filter_type condition)
539 EMAC->frmf_bit.pcf = condition;
543 * @brief source address inverse filtering.
544 * @param new_state: TRUE or FALSE.
545 * @retval none
547 void emac_srcaddr_inverse_filter_set(confirm_state new_state)
549 EMAC->frmf_bit.saif = new_state;
553 * @brief source address filtering.
554 * @param new_state: TRUE or FALSE.
555 * @retval none
557 void emac_srcaddr_filter_set(confirm_state new_state)
559 EMAC->frmf_bit.saf = new_state;
563 * @brief mac uses hash or perfect filter.
564 * @param new_state: TRUE or FALSE.
565 * @retval none
567 void emac_hash_perfect_filter_set(confirm_state new_state)
569 EMAC->frmf_bit.hpf = new_state;
573 * @brief mac receives all frames.
574 * @param new_state: TRUE or FALSE.
575 * @retval none
577 void emac_receive_all_set(confirm_state new_state)
579 EMAC->frmf_bit.ra = new_state;
583 * @brief hash table high 32-bit.
584 * @param high32bits: the highest 32-bit of hash table.
585 * @retval none
587 void emac_hash_table_high32bits_set(uint32_t high32bits)
589 EMAC->hth_bit.hth = high32bits;
593 * @brief hash table low 32-bit.
594 * @param low32bits: the lowest 32-bit of hash table.
595 * @retval none
597 void emac_hash_table_low32bits_set(uint32_t low32bits)
599 EMAC->htl_bit.htl = low32bits;
603 * @brief mii busy status.
604 * @param none
605 * @retval SET or RESET
607 flag_status emac_mii_busy_get(void)
609 if(EMAC->miiaddr_bit.mb) {
610 return SET;
612 else {
613 return RESET;
618 * @brief tell phy that will be written.
619 * @param new_state: TRUE or FALSE.
620 * @retval none
622 void emac_mii_write(confirm_state new_state)
624 EMAC->miiaddr_bit.mw = new_state;
628 * @brief set flow control busy in full-duplex mode, back pressure activate in half-duplex mode.
629 * @param new_state: TRUE or FALSE.
630 * @retval none
632 void emac_fcb_bpa_set(confirm_state new_state)
634 EMAC->fctrl_bit.fcbbpa = new_state;
638 * @brief set transmit flow control.
639 * @param new_state: TRUE or FALSE.
640 * @retval none
642 void emac_transmit_flow_control_enable(confirm_state new_state)
644 EMAC->fctrl_bit.etf = new_state;
648 * @brief set receive flow control.
649 * @param new_state: TRUE or FALSE.
650 * @retval none
652 void emac_receive_flow_control_enable(confirm_state new_state)
654 EMAC->fctrl_bit.erf = new_state;
658 * @brief set unicast pause frame detect.
659 * @param new_state: TRUE or FALSE.
660 * @retval none
662 void emac_unicast_pause_frame_detect(confirm_state new_state)
664 EMAC->fctrl_bit.dup = new_state;
668 * @brief set pause low threshold.
669 * @param pasue_threshold: pause slot time.
670 * this parameter can be one of the following values:
671 * - EMAC_PAUSE_4_SLOT_TIME
672 * - EMAC_PAUSE_28_SLOT_TIME
673 * - EMAC_PAUSE_144_SLOT_TIME
674 * - EMAC_PAUSE_256_SLOT_TIME
675 * @retval none
677 void emac_pause_low_threshold_set(emac_pause_slot_threshold_type pasue_threshold)
679 EMAC->fctrl_bit.plt = pasue_threshold;
683 * @brief set zero-quanta pause disable.
684 * @param new_state: TRUE or FALSE.
685 * @retval none
687 void emac_zero_quanta_pause_disable(confirm_state new_state)
689 EMAC->fctrl_bit.dzqp = new_state;
693 * @brief set pause time.
694 * @param pause_time: time slots to pause transmit frame.
695 * @retval none
697 void emac_pause_time_set(uint16_t pause_time)
699 EMAC->fctrl_bit.pt = pause_time;
703 * @brief identify coming vlan frame field with setting value.
704 * @param identifier: it will be compared with coming frame.
705 * @retval none
707 void emac_vlan_tag_identifier_set(uint16_t identifier)
709 EMAC->vlt_bit.vti = identifier;
713 * @brief set 12-bit vlan identifier.
714 * @param new_state: TRUE or FALSE.
715 * @retval none
717 void emac_vlan_tag_comparison_set(confirm_state new_state)
719 EMAC->vlt_bit.etv = new_state;
723 * @brief set wakeup frame.
724 * @param value: it will be written to eight non transparent registers.
725 * @retval none
727 void emac_wakeup_frame_set(uint32_t value)
729 EMAC->rwff = value;
733 * @brief get wakeup frame.
734 * @param none
735 * @retval get value from eight non transparent registers.
737 uint32_t emac_wakeup_frame_get(void)
739 return (EMAC->rwff);
743 * @brief all frame will be droppped except wakeup frame or magic packet.
744 * @param new_state: TRUE or FALSE.
745 * @retval none
747 void emac_power_down_set(confirm_state new_state)
749 EMAC->pmtctrlsts_bit.pd = new_state;
753 * @brief magic packet enable
754 * @param new_state: TRUE or FALSE.
755 * @retval none
757 void emac_magic_packet_enable(confirm_state new_state)
759 EMAC->pmtctrlsts_bit.emp = new_state;
763 * @brief wakeup frame enable
764 * @param new_state: TRUE or FALSE.
765 * @retval none
767 void emac_wakeup_frame_enable(confirm_state new_state)
769 EMAC->pmtctrlsts_bit.erwf = new_state;
773 * @brief received magic packet
774 * @param none
775 * @retval the new state of usart_flag (SET or RESET).
777 flag_status emac_received_magic_packet_get(void)
779 if(EMAC->pmtctrlsts_bit.rmp)
781 return SET;
783 else
785 return RESET;
790 * @brief received wakeup frame.
791 * @param none
792 * @retval the new state of usart_flag (SET or RESET).
794 flag_status emac_received_wakeup_frame_get(void)
796 if(EMAC->pmtctrlsts_bit.rrwf)
798 return SET;
800 else
802 return RESET;
807 * @brief set unicast frame that passes DAF as wakeup frame.
808 * @param new_state: TRUE or FALSE.
809 * @retval none
811 void emac_global_unicast_set(confirm_state new_state)
813 EMAC->pmtctrlsts_bit.guc = new_state;
817 * @brief reset wakeup frame filter resgister
818 * @param new_state: TRUE or FALSE.
819 * @retval none
821 void emac_wakeup_frame_filter_reset(confirm_state new_state)
823 EMAC->pmtctrlsts_bit.rwffpr = new_state;
827 * @brief read interrupt status
828 * @param flag: specifies the flag to check.
829 * this parameter can be one of the following values:
830 * - EMAC_PMT_FLAG
831 * - EMAC_MMC_FLAG
832 * - EMAC_MMCR_FLAG
833 * - EMAC_MMCT_FLAG
834 * - EMAC_TST_FLAG
835 * @retval the new state of usart_flag (SET or RESET).
837 flag_status emac_interrupt_status_read(uint32_t flag)
839 if(EMAC->ists & flag)
841 return SET;
843 else
845 return RESET;
850 * @brief set interrupt mask
851 * @param mask_type: mask the interrupt signal
852 * this parameter can be one of the following values:
853 * - EMAC_INTERRUPT_PMT_MASK
854 * - EMAC_INTERRUPT_TST_MASK
855 * @param new_state: TRUE or FALSE.
856 * @retval none
858 void emac_interrupt_mask_set(emac_interrupt_mask_type mask_type, confirm_state new_state)
860 switch(mask_type)
862 case EMAC_INTERRUPT_PMT_MASK:
864 EMAC->imr_bit.pim = new_state;
865 break;
867 case EMAC_INTERRUPT_TST_MASK:
869 EMAC->imr_bit.tim = new_state;
870 break;
876 * @brief set local mac address
877 * @param address: local address for mac0
878 * @retval none
880 void emac_local_address_set(uint8_t *address)
882 EMAC->a0h_bit.ma0h = (uint32_t)(address[5] << 8 | address[4]);
883 EMAC->a0l_bit.ma0l = (uint32_t)(address[3] << 24 | address[2] << 16 | address[1] << 8 | address[0]);
887 * @brief set mac filter address
888 * @param mac: select which mac you want to set
889 * this parameter can be one of the following values:
890 * - EMAC_ADDRESS_FILTER_1
891 * - EMAC_ADDRESS_FILTER_2
892 * - EMAC_ADDRESS_FILTER_3
893 * @retval none
895 void emac_address_filter_set(emac_address_type mac, emac_address_filter_type filter, emac_address_mask_type mask_bit, confirm_state new_state)
897 switch(mac)
899 case EMAC_ADDRESS_FILTER_1:
901 EMAC->a1h_bit.sa = filter;
902 EMAC->a1h_bit.mbc = mask_bit;
903 EMAC->a1h_bit.ae = new_state;
904 break;
906 case EMAC_ADDRESS_FILTER_2:
908 EMAC->a2h_bit.sa = filter;
909 EMAC->a2h_bit.mbc = mask_bit;
910 EMAC->a2h_bit.ae = new_state;
911 break;
913 case EMAC_ADDRESS_FILTER_3:
915 EMAC->a3h_bit.sa = filter;
916 EMAC->a3h_bit.mbc = mask_bit;
917 EMAC->a3h_bit.ae = new_state;
918 break;
924 * @brief set transmit/receive descriptor list address
925 * @param transfer_type: it will be transmit or receive
926 * this parameter can be one of the following values:
927 * - EMAC_DMA_TRANSMIT
928 * - EMAC_DMA_RECEIVE
929 * @param dma_desc_tab: pointer on the first tx desc list
930 * @param buff: pointer on the first tx/rx buffer list
931 * @param buffer_count: number of the used Tx desc in the list
932 * @retval none
934 void emac_dma_descriptor_list_address_set(emac_dma_tx_rx_type transfer_type, emac_dma_desc_type *dma_desc_tab, uint8_t *buff, uint32_t buffer_count)
936 uint32_t i = 0;
937 emac_dma_desc_type *dma_descriptor;
939 switch(transfer_type)
941 case EMAC_DMA_TRANSMIT:
943 dma_tx_desc_to_set = dma_desc_tab;
944 for(i = 0; i < buffer_count; i++)
946 dma_descriptor = dma_desc_tab + i;
948 dma_descriptor->status = EMAC_DMATXDESC_TCH;
950 dma_descriptor->buf1addr = (uint32_t)(&buff[i * EMAC_MAX_PACKET_LENGTH]);
952 if(i < (buffer_count - 1))
954 dma_descriptor->buf2nextdescaddr = (uint32_t)(dma_desc_tab + i + 1);
956 else
958 dma_descriptor->buf2nextdescaddr = (uint32_t) dma_desc_tab;
961 EMAC_DMA->tdladdr_bit.stl = (uint32_t) dma_desc_tab;
962 break;
964 case EMAC_DMA_RECEIVE:
966 dma_rx_desc_to_get = dma_desc_tab;
967 for(i = 0; i < buffer_count; i++)
969 dma_descriptor = dma_desc_tab + i;
971 dma_descriptor->status = EMAC_DMARXDESC_OWN;
973 dma_descriptor->controlsize = EMAC_DMARXDESC_RCH | (uint32_t)EMAC_MAX_PACKET_LENGTH;
975 dma_descriptor->buf1addr = (uint32_t)(&buff[i * EMAC_MAX_PACKET_LENGTH]);
977 if(i < (buffer_count - 1))
979 dma_descriptor->buf2nextdescaddr = (uint32_t)(dma_desc_tab + i + 1);
981 else
983 dma_descriptor->buf2nextdescaddr = (uint32_t) dma_desc_tab;
986 EMAC_DMA->rdladdr_bit.srl = (uint32_t) dma_desc_tab;
987 break;
993 * @brief enable or disable the specified dma rx descriptor receive interrupt
994 * @param dma_rx_desc: pointer on a rx desc.
995 * @param new_state: new state of the specified dma rx descriptor interrupt.
996 * this parameter can be one of the following values:
997 * - TRUE
998 * - FALSE.
999 * @retval none
1001 void emac_dma_rx_desc_interrupt_config(emac_dma_desc_type *dma_rx_desc, confirm_state new_state)
1003 if (new_state != FALSE)
1005 /* enable the dma rx desc receive interrupt */
1006 dma_rx_desc->controlsize &= (~(uint32_t)EMAC_DMARXDESC_DIC);
1008 else
1010 /* disable the dma rx desc receive interrupt */
1011 dma_rx_desc->controlsize |= EMAC_DMARXDESC_DIC;
1016 * @brief get transmit/receive descriptor list address
1017 * @param transfer_type: it will be transmit or receive
1018 * this parameter can be one of the following values:
1019 * - EMAC_DMA_TRANSMIT
1020 * - EMAC_DMA_RECEIVE
1021 * @retval transmit/receive descriptor list address
1023 uint32_t emac_dma_descriptor_list_address_get(emac_dma_tx_rx_type transfer_type)
1025 switch(transfer_type)
1027 case EMAC_DMA_TRANSMIT:
1029 return (EMAC_DMA->tdladdr_bit.stl);
1031 case EMAC_DMA_RECEIVE:
1033 return (EMAC_DMA->rdladdr_bit.srl);
1036 return 0;
1040 * @brief get the size of received the received packet.
1041 * @param none
1042 * @retval received packet size
1044 uint32_t emac_received_packet_size_get(void)
1046 uint32_t frame_length = 0;
1047 if(((dma_rx_desc_to_get->status & EMAC_DMARXDESC_OWN) == (uint32_t)RESET) &&
1048 ((dma_rx_desc_to_get->status & EMAC_DMATXDESC_ES) == (uint32_t)RESET) &&
1049 ((dma_rx_desc_to_get->status & EMAC_DMARXDESC_LS) != (uint32_t)RESET) &&
1050 ((dma_rx_desc_to_get->status & EMAC_DMARXDESC_FS) != (uint32_t)RESET))
1052 frame_length = emac_dmarxdesc_frame_length_get(dma_rx_desc_to_get);
1055 return frame_length;
1059 * @brief get the specified dma rx descsriptor frame length.
1060 * @param dma_rx_desc: pointer on a dma rx descriptor
1061 * @retval the rx descriptor received frame length.
1063 uint32_t emac_dmarxdesc_frame_length_get(emac_dma_desc_type *dma_rx_desc)
1065 return ((dma_rx_desc->status & EMAC_DMARXDESC_FL) >> EMAC_DMARXDESC_FRAME_LENGTHSHIFT);
1069 * @brief init emac dma parameters
1070 * @param emac_dma_config_type
1071 * @retval none
1073 void emac_dma_para_init(emac_dma_config_type *control_para)
1075 control_para->aab_enable = FALSE;
1076 control_para->da_enable = FALSE;
1077 control_para->desc_skip_length = 0;
1078 control_para->dt_disable = FALSE;
1079 control_para->fb_enable = FALSE;
1080 control_para->fef_enable = FALSE;
1081 control_para->flush_rx_disable = FALSE;
1082 control_para->fugf_enable = FALSE;
1083 control_para->osf_enable = FALSE;
1084 control_para->priority_ratio = EMAC_DMA_1_RX_1_TX;
1085 control_para->rsf_enable = FALSE;
1086 control_para->rx_dma_pal = EMAC_DMA_PBL_1;
1087 control_para->rx_threshold = EMAC_DMA_RX_THRESHOLD_64_BYTES;
1088 control_para->tsf_enable = FALSE;
1089 control_para->tx_dma_pal = EMAC_DMA_PBL_1;
1090 control_para->tx_threshold = EMAC_DMA_TX_THRESHOLD_64_BYTES;
1091 control_para->usp_enable = FALSE;
1095 * @brief configure emac dma
1096 * @param emac_dma_config_type
1097 * @retval none
1099 void emac_dma_config(emac_dma_config_type *control_para)
1101 EMAC_DMA->bm_bit.aab = control_para->aab_enable;
1102 EMAC_DMA->bm_bit.dsl = control_para->desc_skip_length;
1103 EMAC_DMA->bm_bit.rdp = control_para->rx_dma_pal;
1104 EMAC_DMA->bm_bit.pbl = control_para->tx_dma_pal;
1105 EMAC_DMA->bm_bit.fb = control_para->fb_enable;
1106 EMAC_DMA->bm_bit.usp = control_para->usp_enable;
1107 EMAC_DMA->bm_bit.da = control_para->da_enable;
1108 EMAC_DMA->bm_bit.pr = control_para->priority_ratio;
1110 EMAC_DMA->opm_bit.dt = control_para->dt_disable;
1111 EMAC_DMA->opm_bit.rsf = control_para->rsf_enable;
1112 EMAC_DMA->opm_bit.dfrf = control_para->flush_rx_disable;
1113 EMAC_DMA->opm_bit.tsf = control_para->tsf_enable;
1114 EMAC_DMA->opm_bit.ttc = control_para->tx_threshold;
1115 EMAC_DMA->opm_bit.fef = control_para->fef_enable;
1116 EMAC_DMA->opm_bit.fugf = control_para->fugf_enable;
1117 EMAC_DMA->opm_bit.rtc = control_para->rx_threshold;
1118 EMAC_DMA->opm_bit.osf = control_para->osf_enable;
1122 * @brief set rx tx priority
1123 * @param ratio: rx tx priority ratio
1124 * this parameter can be one of the following values:
1125 * - EMAC_DMA_1_RX_1_TX
1126 * - EMAC_DMA_2_RX_1_TX
1127 * - EMAC_DMA_3_RX_1_TX
1128 * - EMAC_DMA_4_RX_1_TX
1129 * @param new_state: TRUE or FALSE
1130 * @retval none
1132 void emac_dma_arbitation_set(emac_dma_rx_tx_ratio_type ratio, confirm_state new_state)
1134 EMAC_DMA->bm_bit.da = new_state;
1136 if(new_state)
1138 EMAC_DMA->bm_bit.pr = ratio;
1143 * @brief set descriptor skip mength
1144 * @param length: descriptor skip length
1145 * @retval none
1147 void emac_dma_descriptor_skip_length_set(uint8_t length)
1149 EMAC_DMA->bm_bit.dsl = length;
1153 * @brief set programmable burst length
1154 * @param tx_length: tx programmable burst length
1155 * this parameter can be one of the following values:
1156 * - EMAC_DMA_PBL_1
1157 * - EMAC_DMA_PBL_2
1158 * - EMAC_DMA_PBL_4
1159 * - EMAC_DMA_PBL_8
1160 * - EMAC_DMA_PBL_16
1161 * - EMAC_DMA_PBL_32
1162 * @param rx_length: rx programmable burst length
1163 * this parameter can be one of the following values:
1164 * - EMAC_DMA_PBL_1
1165 * - EMAC_DMA_PBL_2
1166 * - EMAC_DMA_PBL_4
1167 * - EMAC_DMA_PBL_8
1168 * - EMAC_DMA_PBL_16
1169 * - EMAC_DMA_PBL_32
1170 * @param new_state: TRUE or FALSE
1171 * @retval none
1173 void emac_dma_separate_pbl_set(emac_dma_pbl_type tx_length, emac_dma_pbl_type rx_length, confirm_state new_state)
1175 EMAC_DMA->bm_bit.usp = new_state;
1176 EMAC_DMA->bm_bit.pbl = tx_length;
1178 if(new_state)
1180 EMAC_DMA->bm_bit.pbl = rx_length;
1185 * @brief set 8 times programmable burst length
1186 * @param new_state: TRUE or FALSE
1187 * @retval none
1189 void emac_dma_eight_pbl_mode_set(confirm_state new_state)
1191 EMAC_DMA->bm_bit.pblx8 = new_state;
1195 * @brief set address-aligned beats
1196 * @param new_state: TRUE or FALSE
1197 * @retval none
1199 void emac_dma_address_aligned_beats_set(confirm_state new_state)
1201 EMAC_DMA->bm_bit.aab = new_state;
1205 * @brief set transmit/receive poll demand
1206 * @param transfer_type: it will be transmit or receive
1207 * this parameter can be one of the following values:
1208 * - EMAC_DMA_TRANSMIT
1209 * - EMAC_DMA_RECEIVE
1210 * @param value: it can be any number
1211 * @retval none
1213 void emac_dma_poll_demand_set(emac_dma_tx_rx_type transfer_type, uint32_t value)
1215 switch(transfer_type)
1217 case EMAC_DMA_TRANSMIT:
1219 EMAC_DMA->tpd_bit.tpd = value;
1220 break;
1222 case EMAC_DMA_RECEIVE:
1224 EMAC_DMA->rpd_bit.rpd = value;
1225 break;
1231 * @brief get transmit poll demand
1232 * @param transfer_type: it will be transmit or receive
1233 * this parameter can be one of the following values:
1234 * - EMAC_DMA_TRANSMIT
1235 * - EMAC_DMA_RECEIVE
1236 * @retval current transmit descriptor
1238 uint32_t emac_dma_poll_demand_get(emac_dma_tx_rx_type transfer_type)
1240 switch(transfer_type)
1242 case EMAC_DMA_TRANSMIT:
1244 return (EMAC_DMA->tpd_bit.tpd);
1246 case EMAC_DMA_RECEIVE:
1248 return (EMAC_DMA->rpd_bit.rpd);
1251 return 0;
1255 * @brief get receive dma process status
1256 * @param none
1257 * @retval every situation it describe in RM
1258 * this parameter can be one of the following values:
1259 * - EMAC_DMA_RX_RESET_STOP_COMMAND
1260 * - EMAC_DMA_RX_FETCH_DESCRIPTOR
1261 * - EMAC_DMA_RX_WAITING_PACKET
1262 * - EMAC_DMA_RX_DESCRIPTOR_UNAVAILABLE
1263 * - EMAC_DMA_RX_CLOSE_DESCRIPTOR
1264 * - EMAC_DMA_RX_FIFO_TO_HOST
1266 emac_dma_receive_process_status_type emac_dma_receive_status_get(void)
1268 switch(EMAC_DMA->sts_bit.rs)
1270 case EMAC_DMA_RX_RESET_STOP_COMMAND:
1272 return EMAC_DMA_RX_RESET_STOP_COMMAND;
1275 case EMAC_DMA_RX_FETCH_DESCRIPTOR:
1277 return EMAC_DMA_RX_FETCH_DESCRIPTOR;
1280 case EMAC_DMA_RX_WAITING_PACKET:
1282 return EMAC_DMA_RX_WAITING_PACKET;
1285 case EMAC_DMA_RX_DESCRIPTOR_UNAVAILABLE:
1287 return EMAC_DMA_RX_DESCRIPTOR_UNAVAILABLE;
1290 case EMAC_DMA_RX_CLOSE_DESCRIPTOR:
1292 return EMAC_DMA_RX_CLOSE_DESCRIPTOR;
1295 case EMAC_DMA_RX_FIFO_TO_HOST:
1297 return EMAC_DMA_RX_FIFO_TO_HOST;
1301 return EMAC_DMA_RX_RESET_STOP_COMMAND;
1305 * @brief get transmit dma process status
1306 * @param none
1307 * @retval every situation it describe in RM
1308 * this parameter can be one of the following values:
1309 * - EMAC_DMA_TX_RESET_STOP_COMMAND
1310 * - EMAC_DMA_TX_FETCH_DESCRIPTOR
1311 * - EMAC_DMA_TX_WAITING_FOR_STATUS
1312 * - EMAC_DMA_TX_HOST_TO_FIFO
1313 * - EMAC_DMA_TX_DESCRIPTOR_UNAVAILABLE
1314 * - EMAC_DMA_TX_CLOSE_DESCRIPTOR
1316 emac_dma_transmit_process_status_type emac_dma_transmit_status_get(void)
1318 switch(EMAC_DMA->sts_bit.ts)
1320 case EMAC_DMA_TX_RESET_STOP_COMMAND:
1322 return EMAC_DMA_TX_RESET_STOP_COMMAND;
1325 case EMAC_DMA_TX_FETCH_DESCRIPTOR:
1327 return EMAC_DMA_TX_FETCH_DESCRIPTOR;
1330 case EMAC_DMA_TX_WAITING_FOR_STATUS:
1332 return EMAC_DMA_TX_WAITING_FOR_STATUS;
1335 case EMAC_DMA_TX_HOST_TO_FIFO:
1337 return EMAC_DMA_TX_HOST_TO_FIFO;
1340 case EMAC_DMA_TX_DESCRIPTOR_UNAVAILABLE:
1342 return EMAC_DMA_TX_DESCRIPTOR_UNAVAILABLE;
1345 case EMAC_DMA_TX_CLOSE_DESCRIPTOR:
1347 return EMAC_DMA_TX_CLOSE_DESCRIPTOR;
1351 return EMAC_DMA_TX_RESET_STOP_COMMAND;
1355 * @brief set dma operations
1356 * @param ops: operations of dma
1357 * this parameter can be one of the following values:
1358 * - EMAC_DMA_OPS_START_STOP_RECEIVE
1359 * - EMAC_DMA_OPS_SECOND_FRAME
1360 * - EMAC_DMA_OPS_FORWARD_UNDERSIZED
1361 * - EMAC_DMA_OPS_FORWARD_ERROR
1362 * - EMAC_DMA_OPS_START_STOP_TRANSMIT
1363 * - EMAC_DMA_OPS_FLUSH_TRANSMIT_FIFO
1364 * - EMAC_DMA_OPS_TRANSMIT_STORE_FORWARD
1365 * - EMAC_DMA_OPS_RECEIVE_FLUSH_DISABLE
1366 * - EMAC_DMA_OPS_RECEIVE_STORE_FORWARD
1367 * - EMAC_DMA_OPS_DROP_ERROR_DISABLE
1368 * @param new_state: TRUE or FALSE
1369 * @retval none
1371 void emac_dma_operations_set(emac_dma_operations_type ops, confirm_state new_state)
1373 __IO uint32_t temp = 0;
1374 switch(ops)
1376 case EMAC_DMA_OPS_START_STOP_RECEIVE:
1378 EMAC_DMA->opm_bit.ssr = new_state;
1379 break;
1382 case EMAC_DMA_OPS_SECOND_FRAME:
1384 EMAC_DMA->opm_bit.osf = new_state;
1385 break;
1388 case EMAC_DMA_OPS_FORWARD_UNDERSIZED:
1390 EMAC_DMA->opm_bit.fugf = new_state;
1391 break;
1394 case EMAC_DMA_OPS_FORWARD_ERROR:
1396 EMAC_DMA->opm_bit.fef = new_state;
1397 break;
1400 case EMAC_DMA_OPS_START_STOP_TRANSMIT:
1402 EMAC_DMA->opm_bit.sstc = new_state;
1403 break;
1406 case EMAC_DMA_OPS_FLUSH_TRANSMIT_FIFO:
1408 EMAC_DMA->opm_bit.ftf = new_state;
1409 temp = EMAC_DMA->opm;
1410 emac_delay(1);
1411 EMAC_DMA->opm = temp;
1412 break;
1415 case EMAC_DMA_OPS_TRANSMIT_STORE_FORWARD:
1417 EMAC_DMA->opm_bit.tsf = new_state;
1418 break;
1421 case EMAC_DMA_OPS_RECEIVE_FLUSH_DISABLE:
1423 EMAC_DMA->opm_bit.dfrf = new_state;
1424 break;
1427 case EMAC_DMA_OPS_RECEIVE_STORE_FORWARD:
1429 EMAC_DMA->opm_bit.rsf = new_state;
1430 break;
1433 case EMAC_DMA_OPS_DROP_ERROR_DISABLE:
1435 EMAC_DMA->opm_bit.dt = new_state;
1436 break;
1442 * @brief set receive dma threshold
1443 * @param value: receive threshold
1444 * this parameter can be one of the following values:
1445 * - EMAC_DMA_RX_THRESHOLD_64_BYTES
1446 * - EMAC_DMA_RX_THRESHOLD_32_BYTES
1447 * - EMAC_DMA_RX_THRESHOLD_96_BYTES
1448 * - EMAC_DMA_RX_THRESHOLD_128_BYTES
1449 * @retval none
1451 void emac_dma_receive_threshold_set(emac_dma_receive_threshold_type value)
1453 EMAC_DMA->opm_bit.rtc = value;
1457 * @brief set transmit dma threshold
1458 * @param value: transmit threshold
1459 * this parameter can be one of the following values:
1460 * - EMAC_DMA_TX_THRESHOLD_64_BYTES
1461 * - EMAC_DMA_TX_THRESHOLD_128_BYTES
1462 * - EMAC_DMA_TX_THRESHOLD_192_BYTES
1463 * - EMAC_DMA_TX_THRESHOLD_256_BYTES
1464 * - EMAC_DMA_TX_THRESHOLD_40_BYTES
1465 * - EMAC_DMA_TX_THRESHOLD_32_BYTES
1466 * - EMAC_DMA_TX_THRESHOLD_24_BYTES
1467 * - EMAC_DMA_TX_THRESHOLD_16_BYTES
1468 * @retval none
1470 void emac_dma_transmit_threshold_set(emac_dma_transmit_threshold_type value)
1472 EMAC_DMA->opm_bit.ttc = value;
1476 * @brief enable dma interrupt
1477 * @param it: interrupt type
1478 * this parameter can be one of the following values:
1479 * - EMAC_DMA_INTERRUPT_TX
1480 * - EMAC_DMA_INTERRUPT_TX_STOP
1481 * - EMAC_DMA_INTERRUPT_TX_UNAVAILABLE
1482 * - EMAC_DMA_INTERRUPT_TX_JABBER
1483 * - EMAC_DMA_INTERRUPT_RX_OVERFLOW
1484 * - EMAC_DMA_INTERRUPT_TX_UNDERFLOW
1485 * - EMAC_DMA_INTERRUPT_RX
1486 * - EMAC_DMA_INTERRUPT_RX_UNAVAILABLE
1487 * - EMAC_DMA_INTERRUPT_RX_STOP
1488 * - EMAC_DMA_INTERRUPT_RX_TIMEOUT
1489 * - EMAC_DMA_INTERRUPT_TX_EARLY
1490 * - EMAC_DMA_INTERRUPT_FATAL_BUS_ERROR
1491 * - EMAC_DMA_INTERRUPT_RX_EARLY
1492 * - EMAC_DMA_INTERRUPT_ABNORMAL_SUMMARY
1493 * - EMAC_DMA_INTERRUPT_NORMAL_SUMMARY
1494 * @param new_state: TRUE or FALSE
1495 * @retval none
1497 void emac_dma_interrupt_enable(emac_dma_interrupt_type it, confirm_state new_state)
1499 switch(it)
1501 case EMAC_DMA_INTERRUPT_TX:
1503 EMAC_DMA->ie_bit.tie = new_state;
1504 break;
1506 case EMAC_DMA_INTERRUPT_TX_STOP:
1508 EMAC_DMA->ie_bit.tse = new_state;
1509 break;
1511 case EMAC_DMA_INTERRUPT_TX_UNAVAILABLE:
1513 EMAC_DMA->ie_bit.tue = new_state;
1514 break;
1516 case EMAC_DMA_INTERRUPT_TX_JABBER:
1518 EMAC_DMA->ie_bit.tje = new_state;
1519 break;
1521 case EMAC_DMA_INTERRUPT_RX_OVERFLOW:
1523 EMAC_DMA->ie_bit.ove = new_state;
1524 break;
1526 case EMAC_DMA_INTERRUPT_TX_UNDERFLOW:
1528 EMAC_DMA->ie_bit.une = new_state;
1529 break;
1531 case EMAC_DMA_INTERRUPT_RX:
1533 EMAC_DMA->ie_bit.rie = new_state;
1534 break;
1536 case EMAC_DMA_INTERRUPT_RX_UNAVAILABLE:
1538 EMAC_DMA->ie_bit.rbue = new_state;
1539 break;
1541 case EMAC_DMA_INTERRUPT_RX_STOP:
1543 EMAC_DMA->ie_bit.rse = new_state;
1544 break;
1546 case EMAC_DMA_INTERRUPT_RX_TIMEOUT:
1548 EMAC_DMA->ie_bit.rwte = new_state;
1549 break;
1551 case EMAC_DMA_INTERRUPT_TX_EARLY:
1553 EMAC_DMA->ie_bit.eie = new_state;
1554 break;
1556 case EMAC_DMA_INTERRUPT_FATAL_BUS_ERROR:
1558 EMAC_DMA->ie_bit.fbee = new_state;
1559 break;
1561 case EMAC_DMA_INTERRUPT_RX_EARLY:
1563 EMAC_DMA->ie_bit.ere = new_state;
1564 break;
1566 case EMAC_DMA_INTERRUPT_ABNORMAL_SUMMARY:
1568 EMAC_DMA->ie_bit.aie = new_state;
1569 break;
1571 case EMAC_DMA_INTERRUPT_NORMAL_SUMMARY:
1573 EMAC_DMA->ie_bit.nie = new_state;
1574 break;
1580 * @brief get missed frames by the controller
1581 * @param none
1582 * @retval missed frames by the controller
1584 uint16_t emac_dma_controller_missing_frame_get(void)
1586 uint16_t number = EMAC_DMA->mfbocnt_bit.mfc;
1587 return number;
1591 * @brief get overflow bit for missed frame counter
1592 * @param none
1593 * @retval overflow bit for missed frame counter
1595 uint8_t emac_dma_missing_overflow_bit_get(void)
1597 uint8_t number = EMAC_DMA->mfbocnt_bit.obmfc;
1598 return number;
1602 * @brief get missed frames by the application
1603 * @param none
1604 * @retval missed frames by the application
1606 uint16_t emac_dma_application_missing_frame_get(void)
1608 uint16_t number = EMAC_DMA->mfbocnt_bit.ofc;
1609 return number;
1613 * @brief get overflow bit for FIFO overflow counter
1614 * @param none
1615 * @retval overflow bit for FIFO overflow counter
1617 uint8_t emac_dma_fifo_overflow_bit_get(void)
1619 uint8_t number = EMAC_DMA->mfbocnt_bit.obfoc;
1620 return number;
1624 * @brief get overflow bit for FIFO overflow counter
1625 * @param transfer type: receive/transmit type
1626 * this parameter can be one of the following values:
1627 * - EMAC_DMA_TX_DESCRIPTOR
1628 * - EMAC_DMA_RX_DESCRIPTOR
1629 * - EMAC_DMA_TX_BUFFER
1630 * - EMAC_DMA_RX_BUFFER
1631 * @retval memory address
1633 uint32_t emac_dma_tansfer_address_get(emac_dma_transfer_address_type transfer_type)
1635 uint32_t address = 0;
1637 switch(transfer_type)
1639 case EMAC_DMA_TX_DESCRIPTOR:
1641 address = EMAC_DMA->ctd_bit.htdap;
1642 break;
1644 case EMAC_DMA_RX_DESCRIPTOR:
1646 address = EMAC_DMA->crd_bit.hrdap;
1647 break;
1649 case EMAC_DMA_TX_BUFFER:
1651 address = EMAC_DMA->ctbaddr_bit.htbap;
1652 break;
1654 case EMAC_DMA_RX_BUFFER:
1656 address = EMAC_DMA->crbaddr_bit.hrbap;
1657 break;
1660 return address;
1664 * @brief reset all counter
1665 * @param none
1666 * @retval none
1668 void emac_mmc_counter_reset(void)
1670 EMAC_MMC->ctrl_bit.rc = TRUE;
1674 * @brief counter stop counting from zero when it reaches maximum
1675 * @param new_state: TRUE or FALSE.
1676 * @retval none
1678 void emac_mmc_rollover_stop(confirm_state new_state)
1680 EMAC_MMC->ctrl_bit.scr = new_state;
1684 * @brief enable reset on read
1685 * @param new_state: TRUE or FALSE.
1686 * @retval none
1688 void emac_mmc_reset_on_read_enable(confirm_state new_state)
1690 EMAC_MMC->ctrl_bit.rr = new_state;
1694 * @brief freeze mmc counter
1695 * @param new_state: TRUE or FALSE.
1696 * @retval none
1698 void emac_mmc_counter_freeze(confirm_state new_state)
1700 EMAC_MMC->ctrl_bit.fmc = new_state;
1704 * @brief interupt status of received frames
1705 * @param flag: specifies the flag to check.
1706 * this parameter can be one of the following values:
1707 * - MMC_RX_CRC_ERROR
1708 * - MMC_RX_ALIGN_ERROR
1709 * - MMC_RX_GOOD_UNICAST
1710 * @retval the new state of usart_flag (SET or RESET).
1712 flag_status emac_mmc_received_status_get(uint32_t flag)
1714 if(EMAC_MMC->ri & flag)
1716 return SET;
1718 else
1720 return RESET;
1725 * @brief interupt status of transmit frames
1726 * @param transmit_type: transmit type.
1727 * this parameter can be one of the following values:
1728 * - MMC_TX_SINGLE_COL
1729 * - MMC_TX_MULTIPLE_COL
1730 * - MMC_TX_GOOD_FRAMES
1731 * @retval the new state of usart_flag (SET or RESET).
1733 flag_status emac_mmc_transmit_status_get(uint32_t flag)
1735 if(EMAC_MMC->ti & flag)
1737 return SET;
1739 else
1741 return RESET;
1746 * @brief mask received mmc interrupt
1747 * @param flag: specifies the flag to check.
1748 * this parameter can be one of the following values:
1749 * - MMC_RX_CRC_ERROR
1750 * - MMC_RX_ALIGN_ERROR
1751 * - MMC_RX_GOOD_UNICAST
1752 * @param new_state: TRUE or FALSE.
1753 * @retval none
1755 void emac_mmc_received_interrupt_mask_set(uint32_t flag, confirm_state new_state)
1757 switch(flag)
1759 case MMC_RX_CRC_ERROR:
1761 EMAC_MMC->rim_bit.rcefcim = new_state;
1762 break;
1764 case MMC_RX_ALIGN_ERROR:
1766 EMAC_MMC->rim_bit.raefacim = new_state;
1767 break;
1769 case MMC_RX_GOOD_UNICAST:
1771 EMAC_MMC->rim_bit.rugfcim = new_state;
1772 break;
1778 * @brief mask transmit mmc interrupt
1779 * @param transmit_type: transmit type.
1780 * this parameter can be one of the following values:
1781 * - MMC_TX_SINGLE_COL
1782 * - MMC_TX_MULTIPLE_COL
1783 * - MMC_TX_GOOD_FRAMES
1784 * @param new_state: TRUE or FALSE.
1785 * @retval none
1787 void emac_mmc_transmit_interrupt_mask_set(uint32_t flag, confirm_state new_state)
1789 switch(flag)
1791 case MMC_TX_SINGLE_COL:
1793 EMAC_MMC->tim_bit.tscgfcim = new_state;
1794 break;
1796 case MMC_TX_MULTIPLE_COL:
1798 EMAC_MMC->tim_bit.tmcgfcim = new_state;
1799 break;
1801 case MMC_TX_GOOD_FRAMES:
1803 EMAC_MMC->tim_bit.tgfcim = new_state;
1804 break;
1810 * @brief get good frame numbers as single collision occurs.
1811 * @param flag: specifies the flag to check.
1812 * this parameter can be one of the following values:
1813 * - MMC_TX_SINGLE_COL
1814 * - MMC_TX_MULTIPLE_COL
1815 * - MMC_TX_GOOD_FRAMES
1816 * @retval good frames
1818 uint32_t emac_mmc_transmit_good_frames_get(uint32_t flag)
1820 uint32_t good_frames = MMC_TX_GOOD_FRAMES;
1822 switch(flag)
1824 case MMC_TX_SINGLE_COL:
1826 good_frames = EMAC_MMC->tfscc_bit.tgfscc;
1827 break;
1829 case MMC_TX_MULTIPLE_COL:
1831 good_frames = EMAC_MMC->tfmscc_bit.tgfmscc;
1832 break;
1834 case MMC_TX_GOOD_FRAMES:
1836 good_frames = EMAC_MMC->tfcnt_bit.tgfc;
1837 break;
1840 return good_frames;
1844 * @brief get good frame numbers as single collision occurs.
1845 * @param flag: specifies the flag to check.
1846 * this parameter can be one of the following values:
1847 * - MMC_RX_CRC_ERROR
1848 * - MMC_RX_ALIGN_ERROR
1849 * - MMC_RX_GOOD_UNICAST
1850 * @retval good frames
1852 uint32_t emac_mmc_received_error_frames_get(uint32_t flag)
1854 uint32_t error_frames = MMC_RX_GOOD_UNICAST;
1856 switch(flag)
1858 case MMC_RX_CRC_ERROR:
1860 error_frames = EMAC_MMC->rfcecnt_bit.rfcec;
1861 break;
1863 case MMC_RX_ALIGN_ERROR:
1865 error_frames = EMAC_MMC->rfaecnt_bit.rfaec;
1866 break;
1868 case MMC_RX_GOOD_UNICAST:
1870 error_frames = EMAC_MMC->rgufcnt_bit.rgufc;
1871 break;
1874 return error_frames;
1878 * @brief enable timestamp.
1879 * @param new_state: TRUE or FALSE.
1880 * @retval none
1882 void emac_ptp_timestamp_enable(confirm_state new_state)
1884 EMAC_PTP->tsctrl_bit.te = new_state;
1888 * @brief enable timestamp fine update.
1889 * @param new_state: TRUE or FALSE.
1890 * @retval none
1892 void emac_ptp_timestamp_fine_update_enable(confirm_state new_state)
1894 EMAC_PTP->tsctrl_bit.tfcu = new_state;
1898 * @brief initialize timestamp time system.
1899 * @param new_state: TRUE or FALSE.
1900 * @retval none
1902 void emac_ptp_timestamp_system_time_init(confirm_state new_state)
1904 EMAC_PTP->tsctrl_bit.ti = new_state;
1908 * @brief update timestamp time system.
1909 * @param new_state: TRUE or FALSE.
1910 * @retval none
1912 void emac_ptp_timestamp_system_time_update(confirm_state new_state)
1914 EMAC_PTP->tsctrl_bit.tu = new_state;
1918 * @brief enable timestamp interrupt trigger.
1919 * @param new_state: TRUE or FALSE.
1920 * @retval none
1922 void emac_ptp_interrupt_trigger_enable(confirm_state new_state)
1924 EMAC_PTP->tsctrl_bit.tite = new_state;
1928 * @brief update timestamp addend register.
1929 * @param new_state: TRUE or FALSE.
1930 * @retval none
1932 void emac_ptp_addend_register_update(confirm_state new_state)
1934 EMAC_PTP->tsctrl_bit.aru = new_state;
1938 * @brief enable timestamp snapshot for all received frames.
1939 * @param new_state: TRUE or FALSE.
1940 * @retval none
1942 void emac_ptp_snapshot_received_frames_enable(confirm_state new_state)
1944 EMAC_PTP->tsctrl_bit.etaf = new_state;
1948 * @brief enable digital rollover.
1949 * @param new_state: TRUE or FALSE.
1950 * @retval none
1952 void emac_ptp_subsecond_rollover_enable(confirm_state new_state)
1954 EMAC_PTP->tsctrl_bit.tdbrc = new_state;
1958 * @brief enable packet snooping for version 2.
1959 * @param new_state: TRUE or FALSE.
1960 * @retval none
1962 void emac_ptp_psv2_enable(confirm_state new_state)
1964 EMAC_PTP->tsctrl_bit.eppv2f = new_state;
1968 * @brief enable snapshot over emac.
1969 * @param new_state: TRUE or FALSE.
1970 * @retval none
1972 void emac_ptp_snapshot_emac_frames_enable(confirm_state new_state)
1974 EMAC_PTP->tsctrl_bit.eppef = new_state;
1978 * @brief enable snapshot for ipv6 frames.
1979 * @param new_state: TRUE or FALSE.
1980 * @retval none
1982 void emac_ptp_snapshot_ipv6_frames_enable(confirm_state new_state)
1984 EMAC_PTP->tsctrl_bit.eppfsip6u = new_state;
1988 * @brief enable snapshot for ipv4 frames.
1989 * @param new_state: TRUE or FALSE.
1990 * @retval none
1992 void emac_ptp_snapshot_ipv4_frames_enable(confirm_state new_state)
1994 EMAC_PTP->tsctrl_bit.eppfsip4u = new_state;
1998 * @brief enable snapshot for event message.
1999 * @param new_state: TRUE or FALSE.
2000 * @retval none
2002 void emac_ptp_snapshot_event_message_enable(confirm_state new_state)
2004 EMAC_PTP->tsctrl_bit.etsfem = new_state;
2008 * @brief enable snapshot for message relevant to master
2009 * @param new_state: TRUE or FALSE.
2010 * @retval none
2012 void emac_ptp_snapshot_master_event_enable(confirm_state new_state)
2014 EMAC_PTP->tsctrl_bit.esfmrtm = new_state;
2018 * @brief set clock node type
2019 * @param node: select ptp packets for taking snapshot
2020 * this parameter can be one of the following values:
2021 * - EMAC_PTP_NORMAL_CLOCK
2022 * - EMAC_PTP_BOUNDARY_CLOCK
2023 * - EMAC_PTP_END_TO_END_CLOCK
2024 * - EMAC_PTP_PEER_TO_PEER_CLOCK
2025 * @retval none
2027 void emac_ptp_clock_node_set(emac_ptp_clock_node_type node)
2029 EMAC_PTP->tsctrl_bit.sppfts = node;
2033 * @brief enable ptp frame filtering mac address
2034 * @param new_state: TRUE or FALSE.
2035 * @retval none
2037 void emac_ptp_mac_address_filter_enable(confirm_state new_state)
2039 EMAC_PTP->tsctrl_bit.emafpff = new_state;
2043 * @brief set subsecond increment value
2044 * @param value: add to subsecond value for every update
2045 * @retval none
2047 void emac_ptp_subsecond_increment_set(uint8_t value)
2049 EMAC_PTP->ssinc_bit.ssiv = value;
2053 * @brief get system time second
2054 * @param none
2055 * @retval system time second
2057 uint32_t emac_ptp_system_second_get(void)
2059 uint32_t second = EMAC_PTP->tsh_bit.ts;
2060 return second;
2064 * @brief get system time subsecond
2065 * @param none
2066 * @retval system time subsecond
2068 uint32_t emac_ptp_system_subsecond_get(void)
2070 uint32_t subsecond = EMAC_PTP->tsl_bit.tss;
2071 return subsecond;
2075 * @brief get system time sign
2076 * @param none
2077 * @retval TRUE or FALSE
2079 confirm_state emac_ptp_system_time_sign_get(void)
2081 if(EMAC_PTP->tsl_bit.ast)
2083 return TRUE;
2085 else
2087 return FALSE;
2092 * @brief set system time second
2093 * @param second: system time second
2094 * @retval none
2096 void emac_ptp_system_second_set(uint32_t second)
2098 EMAC_PTP->tshud_bit.ts = second;
2102 * @brief set system time subsecond
2103 * @param subsecond: system time subsecond
2104 * @retval none
2106 void emac_ptp_system_subsecond_set(uint32_t subsecond)
2108 EMAC_PTP->tslud_bit.tss = subsecond;
2112 * @brief set system time sign
2113 * @param sign: TRUE or FALSE.
2114 * @retval none
2116 void emac_ptp_system_time_sign_set(confirm_state sign)
2118 if(sign)
2120 EMAC_PTP->tslud_bit.ast = 1;
2122 else
2124 EMAC_PTP->tslud_bit.ast = 0;
2129 * @brief set time stamp addend
2130 * @param value: to achieve time synchronization
2131 * @retval none
2133 void emac_ptp_timestamp_addend_set(uint32_t value)
2135 EMAC_PTP->tsad_bit.tar = value;
2139 * @brief set target time stamp high
2140 * @param value: to set target time second
2141 * @retval none
2143 void emac_ptp_target_second_set(uint32_t value)
2145 EMAC_PTP->tth_bit.ttsr = value;
2149 * @brief set target time stamp low
2150 * @param value: to set target time nanosecond
2151 * @retval none
2153 void emac_ptp_target_nanosecond_set(uint32_t value)
2155 EMAC_PTP->ttl_bit.ttlr = value;
2159 * @brief set target time stamp low
2160 * @param status: type of status
2161 * this parameter can be one of the following values:
2162 * - EMAC_PTP_SECOND_OVERFLOW
2163 * - EMAC_PTP_TARGET_TIME_REACH
2164 * @retval TRUE or FALSE
2166 confirm_state emac_ptp_timestamp_status_get(emac_ptp_timestamp_status_type status)
2168 switch(status)
2170 case EMAC_PTP_SECOND_OVERFLOW:
2172 if(EMAC_PTP->tssr_bit.tso)
2174 return TRUE;
2176 else
2178 return FALSE;
2181 case EMAC_PTP_TARGET_TIME_REACH:
2183 if(EMAC_PTP->tssr_bit.tttr)
2185 return TRUE;
2187 else
2189 return FALSE;
2193 return FALSE;
2197 * @brief set pps frequency
2198 * @param freq: pps frequency
2199 * this parameter can be one of the following values:
2200 * - EMAC_PTP_PPS_1HZ
2201 * - EMAC_PTP_PPS_2HZ
2202 * - EMAC_PTP_PPS_4HZ
2203 * - EMAC_PTP_PPS_8HZ
2204 * - EMAC_PTP_PPS_16HZ
2205 * - EMAC_PTP_PPS_32HZ
2206 * - EMAC_PTP_PPS_64HZ
2207 * - EMAC_PTP_PPS_128HZ
2208 * - EMAC_PTP_PPS_256HZ
2209 * - EMAC_PTP_PPS_512HZ
2210 * - EMAC_PTP_PPS_1024HZ
2211 * - EMAC_PTP_PPS_2048HZ
2212 * - EMAC_PTP_PPS_4096HZ
2213 * - EMAC_PTP_PPS_8192HZ
2214 * - EMAC_PTP_PPS_16384HZ
2215 * - EMAC_PTP_PPS_32768HZ
2216 * @retval none
2218 void emac_ptp_pps_frequency_set(emac_ptp_pps_control_type freq)
2220 EMAC_PTP->ppscr_bit.pofc = freq;
2224 * @brief this is delay function base on system clock.
2225 * @param delay: delay time
2226 * @retval none
2228 static void emac_delay(uint32_t delay)
2230 __IO uint32_t delay_time = delay * (system_core_clock / 8 / 1000);
2233 __NOP();
2235 while(delay_time --);
2239 * @brief check whether the specified emac dma flag is set or not.
2240 * @param dma_flag: specifies the emac dma flag to check.
2241 * this parameter can be one of emac dma flag status:
2242 * - EMAC_DMA_TI_FLAG
2243 * - EMAC_DMA_TPS_FLAG
2244 * - EMAC_DMA_TBU_FLAG
2245 * - EMAC_DMA_TJT_FLAG
2246 * - EMAC_DMA_OVF_FLAG
2247 * - EMAC_DMA_UNF_FLAG
2248 * - EMAC_DMA_RI_FLAG
2249 * - EMAC_DMA_RBU_FLAG
2250 * - EMAC_DMA_RPS_FLAG
2251 * - EMAC_DMA_RWT_FLAG
2252 * - EMAC_DMA_ETI_FLAG
2253 * - EMAC_DMA_FBEI_FLAG
2254 * - EMAC_DMA_ERI_FLAG
2255 * - EMAC_DMA_AIS_FLAG
2256 * - EMAC_DMA_NIS_FLAG
2257 * @retval the new state of dma_flag (SET or RESET).
2259 flag_status emac_dma_flag_get(uint32_t dma_flag)
2261 flag_status status = RESET;
2263 if(EMAC_DMA->sts & dma_flag)
2264 status = SET;
2265 /* return the new state (SET or RESET) */
2266 return status;
2270 * @brief clear the emac dma flag.
2271 * @param dma_flag: specifies the emac dma flags to clear.
2272 * this parameter can be any combination of the following values:
2273 * - EMAC_DMA_TI_FLAG
2274 * - EMAC_DMA_TPS_FLAG
2275 * - EMAC_DMA_TBU_FLAG
2276 * - EMAC_DMA_TJT_FLAG
2277 * - EMAC_DMA_OVF_FLAG
2278 * - EMAC_DMA_UNF_FLAG
2279 * - EMAC_DMA_RI_FLAG
2280 * - EMAC_DMA_RBU_FLAG
2281 * - EMAC_DMA_RPS_FLAG
2282 * - EMAC_DMA_RWT_FLAG
2283 * - EMAC_DMA_ETI_FLAG
2284 * - EMAC_DMA_FBEI_FLAG
2285 * - EMAC_DMA_ERI_FLAG
2286 * - EMAC_DMA_AIS_FLAG
2287 * - EMAC_DMA_NIS_FLAG
2288 * @retval none
2290 void emac_dma_flag_clear(uint32_t dma_flag)
2292 EMAC_DMA->sts = dma_flag;
2296 * @}
2299 #endif
2302 * @}
2305 #endif
2308 * @}