You are viewing a plain text version of this content. The canonical link for it is here.
Posted to commits@nuttx.apache.org by GitBox <gi...@apache.org> on 2021/03/05 14:10:19 UTC

[GitHub] [incubator-nuttx] davids5 opened a new pull request #2985: stm32 Ethernet hardening

davids5 opened a new pull request #2985:
URL: https://github.com/apache/incubator-nuttx/pull/2985


   ## Summary
   
   Discussion on mailing list https://lists.apache.org/thread.html/r667771dc2901734e826d5478097589ba35f00e61ea7e34ed07e144e8%40%3Cdev.nuttx.apache.org%3E
   
   ```
   The problem is the following. (The value of numbers do not matter, but help express the nature of the problem.)
   
   If CONFIG_NET_ETH_PKTSIZE is the default 490 and a 1518 frame on the network is received by the F7.
   
   The DMA HW will store the frame as n buffer sizes segments and one or 0 remainder sizes buffer.
   
   The following will happen:
   
   490 becomes 608 after the sizing and alignment.
   
   DMA populates the buffers from the descriptors
   
   +>D0->B0(608) the FL is 1518 the d_len is set to 1514. FL from (FL bits in RDES0[29:16]) - 4
   |    |
   |    V
   |    D1->B1(608)
   |    |
   |   V
   |   D2->B2(298)
   |   ....
   |   |
   |   V
   <+Dn->Bn[]
   ....
   
   From RM410: To compute the amount of valid data in this final buffer, the driver must read the frame length (FL bits in RDES0[29:16])  and subtract the sum of the buffer sizes of the preceding buffers in this frame. 
   
   But the code is invalidating from &B0[0] to &B0[1513]. If the buffers were contiguous in memory this would be ok. But the buffers that are used in RX are replaced (in the descriptors) from the free pool using the g_txbuffer memory.
   
   While at boot B0 to Bn are contiguous, they become scattered as a process of receiving (the nature of the ring and replacement from the free pool)
   
   The ring:
   
   /* Scan descriptors owned by the CPU.  Scan until:
      *
      *   1) We find a descriptor still owned by the DMA,
      *   2) We have examined all of the RX descriptors, or
      *   3) All of the TX descriptors are in flight.
      *
   
   The replacement:
   
                 buffer = stm32_allocbuffer(priv);
                 /* Take the buffer from the RX descriptor of the first free
                  * segment, put it into the network device structure, then
                  * replace the buffer in the RX descriptor with the newly
                  * allocated buffer.
                  */
                 dev->d_buf    = (uint8_t *)rxcurr->rdes2;
                 rxcurr->rdes2 = (uint32_t)buffer;
   
   
   Eventually, B0 is allocated from one of the buffers in the g_txbuffer array. 
   
   
   Given this layout of memory low-high  
   
   	/* Descriptor allocations */
   
   	g_rxtable[RXTABLE_SIZE]
   	g_txtable[TXTABLE_SIZE]
   
   	/* Buffer allocations */
   
   	g_rxbuffer[RXBUFFER_ALLOC]
   	g_txbuffer[TXBUFFER_ALLOC]
   
   	/* These are the pre-allocated Ethernet device structures */
   
   	stm32_ethmac_s g_stm32ethmac[STM32F7_NETHERNET];
   
   The dev->d_buf is an address in g_txbuffer. dev->d_len is the Frame Length 1514 NOT the buffer length!
   
   The up_invalidate_dcache then corrupts the g_stm32ethmac. The result is dev->d_buf and + dev->d_len are both 0.
   
   Context before the call to up_invalidate_dcache
   
   	dev->d_buf = &g_txbuffer[n * (RXBUFFER_ALLOC/608)]
   	dev->d_len = 1514
   
               	  up_invalidate_dcache((uintptr_t)dev->d_buf,
                           	           (uintptr_t)dev->d_buf + dev->d_len);
   
   Context after the call to up_invalidate_dcache
   	dev->d_buf =0
   	dev->d_len = 0
   
   
   This then returns OK and stm32_receive dereferences a null pointer and places the null into the free pool.
   The hard fault then happens. 
   
   When the CONFIG_NET_ETH_PKTSIZE is 1514, the corruption does to happen because sizeof FRAME  == sizeof BUFFER
   
   (The system will still crash if the hardware can receive a bigger frame the numbers are relaitve)
   
   The driver is not quite right, the code manages the segments but does not coalesce them back in to a frame. (memcpy with such a DMA is gross thought) So the data RX data is useless to the network layer.
   
   If the network layers used IOB and could deal with on the fly assembly the system would be most efficient. But that is a major undertaking.
   
   The goal now is to harden the driver.
   
   1) Discard frames (all segments) grater then the size of one buffer. 
   2) Fix the invalidation.
   
   ```
   ## Impact
   
   Critical on master on STM32F7 and STM32H7 - 
   
   STM32F4 - will probably not fault, but will process bad data.
   ```
   NuttShell (NSH) NuttX-9.1.1
   nsh> arm_hardfault: Hard Fault:
   arm_hardfault:   IRQ: 3 regs: 0x2007e3ac
   arm_hardfault:   BASEPRI: 000000f0 PRIMASK: 00000000 IPSR: 00000003 CONTROL: 00000000
   arm_hardfault:   CFAULTS: 00008200 HFAULTS: 40000000 DFAULTS: 00000000 BFAULTADDR: 0000000c AFAULTS: 00000000
   arm_hardfault: PANIC!!! Hard fault: 40000000
   up_assert: Assertion failed at file:armv7-m/arm_hardfault.c line: 134 task: lpwork
   up_registerdump: R0: 200295c0 200295aa 00000000 00000000 20029320 20029240 4002901c 40029014
   up_registerdump: R8: 00010040 20029300 2002937c 200293e4 00000001 2007e480 0801760d 08017512
   up_registerdump: xPSR: 81000000 BASEPRI: 000000f0 CONTROL: 00000000
   up_registerdump: EXC_RETURN: ffffffe9
   up_dumpstate: sp:     200214f0
   up_dumpstate: IRQ stack:
   up_dumpstate:   base: 20021580
   up_dumpstate:   size: 00000200
   up_dumpstate:   used: 00000188
   up_stackdump: 200214e0: 200214f0 20021580 2007e508 08015131 000000f0 00000000 200293e4 00000001
   up_stackdump: 20021500: 2007e480 0801760d 08017512 e000ed2c 0000000c e000ed2c 0000000c 00000000
   up_stackdump: 20021520: 00000000 00010040 20029300 2002937c 200293e4 08009d07 0800aaa9 080097df
   up_stackdump: 20021540: 40000000 00000000 0000000c 00000000 20021580 00000003 00000003 0800b3a7
   up_stackdump: 20021560: 000000f0 08008371 000000f0 2007e3ac 20029240 4002901c 40029014 08008237
   up_dumpstate: sp:     2007e480
   up_dumpstate: User stack:
   up_dumpstate:   base: 2007e508
   up_dumpstate:   size: 00000654
   up_dumpstate:   used: 00000234
   up_stackdump: 2007e480: 00000000 20029250 00000000 20029250 00000000 2002934c 00000000 000000f0
   up_stackdump: 2007e4a0: 00000000 20026934 00000080 ffffffff 20026d10 0800d245 00000000 00001a4e
   up_stackdump: 2007e4c0: 00000000 00000010 00000000 20026d10 0800c539 00000000 00000000 00000000
   up_stackdump: 2007e4e0: 00000000 00000000 00000000 0800c545 2007d6c0 0800c3c1 00000000 00000000
   up_stackdump: 2007e500: 00000000 00000000 2007e510 00000000 6f77706c de006b72 00000060 80000680
   up_taskdump: Idle Task: PID=0 Stack Used=332 of 724
   up_taskdump: hpwork: PID=1 Stack Used=332 of 1268
   up_taskdump: lpwork: PID=2 Stack Used=564 of 1620
   up_taskdump: init: PID=3 Stack Used=2300 of 2932
   up_taskdump: wq:manager: PID=4 Stack Used=428 of 1260
   up_taskdump: Telnet daemon: PID=5 Stack Used=548 of 2012
   up_taskdump: mavlink_if0: PID=266 Stack Used=1700 of 2780
   up_taskdump: navigator: PID=467 Stack Used=1044 of 1772
   up_taskdump: gps: PID=340 Stack Used=924 of 1684
   up_taskdump: wq:hp_default: PID=21 Stack Used=1124 of 1900
   up_taskdump: mavlink_if1: PID=406 Stack Used=1588 of 2692
   up_taskdump: mavlink_rcv_if1: PID=407 Stack Used=4180 of 6108
   up_taskdump: dataman: PID=26 Stack Used=796 of 1204
   up_taskdump: wq:lp_default: PID=28 Stack Used=972 of 1700
   up_taskdump: wq:nav_and_controllers: PID=231 Stack Used=1316 of 2164
   up_taskdump: wq:rate_ctrl: PID=232 Stack Used=1416 of 1892
   up_taskdump: wq:I2C1: PID=169 Stack Used=864 of 2340
   up_taskdump: wq:INS0: PID=234 Stack Used=1348 of 6004
   up_taskdump: wq:I2C2: PID=171 Stack Used=852 of 2340
   up_taskdump: wq:SPI3: PID=174 Stack Used=1436 of 2340
   up_taskdump: wq:INS1: PID=239 Stack Used=1348 of 6004
   up_taskdump: wq:SPI2: PID=177 Stack Used=1780 of 2340
   up_taskdump: wq:INS2: PID=242 Stack Used=1348 of 6004
   up_taskdump: wq:SPI1: PID=179 Stack Used=1596 of 2340
   up_taskdump: commander: PID=244 Stack Used=1268 of 3220
   up_taskdump: wq:I2C4: PID=181 Stack Used=1084 of 2340
   up_taskdump: px4io: PID=438 Stack Used=1008 of 1484
   up_taskdump: logger: PID=503 Stack Used=2436 of 3644
   up_taskdump: log_writer_file: PID=506 Stack Used=388 of 1172
   up_taskdump: wq:uavcan: PID=251 Stack Used=1852 of 2580
   up_taskdump: netinit: PID=509 Stack Used=644 of 2052
   up_taskdump: uavcan fw srv: PID=254 Stack Used=1564 of 6004
   up_taskdump: mavlink_rcv_if0: PID=511 Stack Used=4188 of 6108
   reset done, 10 ms
   [boot] Rev 0x0 : Ver 0x0 V5X00
   [boot] Fault Log info File No 4 Length 3177 flags:0x01 state:0
   [boot] Fault Logged on 2000-01-02-20:16:46 - Valid
   [boot] There is a hard fault logged. Hold down the SPACE BAR, while booting to review!
   sercon: Registering CDC/ACM serial driver
   serco[hardfault_log] Fault Log info File No 4 Length 3177 flags:0x01 state:0
   [hardfault_log] Fault Logged on 2000-01-02-20:16:46 - Valid
   n: Successfully registered the CDC/ACM serial driver
   HW arch: PX4_FMU_V5X
   HW type: V5X0[hardfault_log] Saving Fault Log file /fs/microsd/fault_2000_01_02_20_16_46.log
   ```
   ![image](https://user-images.githubusercontent.com/1945821/110126421-4362df00-7d79-11eb-80fd-2a5c2bb6ed24.png)
   
   ## Testing
   
   telnet, ping and flood withj scapy
   px4_fmuv-5x (stm32 F7)
   
   ```
   from scapy.all import *
   send(fragment(IP(dst="192.168.0.123")/ICMP()/("X"*60000)) )
   ```
   
   


----------------------------------------------------------------
This is an automated message from the Apache Git Service.
To respond to the message, please log on to GitHub and use the
URL above to go to the specific comment.

For queries about this service, please contact Infrastructure at:
users@infra.apache.org



[GitHub] [incubator-nuttx] rippetoej commented on pull request #2985: stm32 Ethernet hardening

Posted by GitBox <gi...@apache.org>.
rippetoej commented on pull request #2985:
URL: https://github.com/apache/incubator-nuttx/pull/2985#issuecomment-791547653


   @davids5 Glad I could help in some way. I've left it running and it has been going strong for over an hour at this point. 


----------------------------------------------------------------
This is an automated message from the Apache Git Service.
To respond to the message, please log on to GitHub and use the
URL above to go to the specific comment.

For queries about this service, please contact Infrastructure at:
users@infra.apache.org



[GitHub] [incubator-nuttx] davids5 commented on pull request #2985: stm32 Ethernet hardening

Posted by GitBox <gi...@apache.org>.
davids5 commented on pull request #2985:
URL: https://github.com/apache/incubator-nuttx/pull/2985#issuecomment-791541587


   @acassis - can you test the Ethernet on the STM32F4?


----------------------------------------------------------------
This is an automated message from the Apache Git Service.
To respond to the message, please log on to GitHub and use the
URL above to go to the specific comment.

For queries about this service, please contact Infrastructure at:
users@infra.apache.org



[GitHub] [incubator-nuttx] rippetoej commented on pull request #2985: stm32 Ethernet hardening

Posted by GitBox <gi...@apache.org>.
rippetoej commented on pull request #2985:
URL: https://github.com/apache/incubator-nuttx/pull/2985#issuecomment-791512546


   @davids5 I tested your changes on my board and have had no issues for the last 20 minutes using the default packet size of 590. Previous, all it took was plugging the board into my network, which would lead to a hard fault in less than 15 seconds. Network debug output shows it is receiving large packets that are being broken up into segments. I have TCP, UDP, and ICMP all enabled. Looks like your fix did the trick!
   
   stm32_recvframe: ERROR: Dropped, RX descriptor Too big: 1476 in 3 segments
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   stm32_receive: WARNING: DROPPED Unknown type: 94ab
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   stm32_recvframe: ERROR: Dropped, RX descriptor Too big: 1344 in 3 segments
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   stm32_recvframe: ERROR: Dropped, RX descriptor Too big: 1086 in 2 segments
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   stm32_recvframe: ERROR: Dropped, RX descriptor Too big: 1362 in 3 segments
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   stm32_recvframe: ERROR: Dropped, RX descriptor Too big: 1362 in 3 segments
   udp_input: WARNING: No listener on UDP port
   stm32_recvframe: ERROR: Dropped, RX descriptor Too big: 810 in 2 segments
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   stm32_recvframe: ERROR: Dropped, RX descriptor Too big: 1318 in 3 segments
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   stm32_recvframe: ERROR: Dropped, RX descriptor Too big: 1276 in 3 segments
   udp_input: WARNING: No listener on UDP port
   stm32_recvframe: ERROR: Dropped, RX descriptor Too big: 696 in 2 segments
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   stm32_recvframe: ERROR: Dropped, RX descriptor Too big: 798 in 2 segments
   stm32_recvframe: ERROR: Dropped, RX descriptor Too big: 793 in 2 segments
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   udp_input: WARNING: No listener on UDP port
   


----------------------------------------------------------------
This is an automated message from the Apache Git Service.
To respond to the message, please log on to GitHub and use the
URL above to go to the specific comment.

For queries about this service, please contact Infrastructure at:
users@infra.apache.org



[GitHub] [incubator-nuttx] davids5 commented on pull request #2985: stm32 Ethernet hardening

Posted by GitBox <gi...@apache.org>.
davids5 commented on pull request #2985:
URL: https://github.com/apache/incubator-nuttx/pull/2985#issuecomment-791541992


   @rippetoej - Thank you for testing!


----------------------------------------------------------------
This is an automated message from the Apache Git Service.
To respond to the message, please log on to GitHub and use the
URL above to go to the specific comment.

For queries about this service, please contact Infrastructure at:
users@infra.apache.org



[GitHub] [incubator-nuttx] xiaoxiang781216 merged pull request #2985: stm32 Ethernet hardening

Posted by GitBox <gi...@apache.org>.
xiaoxiang781216 merged pull request #2985:
URL: https://github.com/apache/incubator-nuttx/pull/2985


   


----------------------------------------------------------------
This is an automated message from the Apache Git Service.
To respond to the message, please log on to GitHub and use the
URL above to go to the specific comment.

For queries about this service, please contact Infrastructure at:
users@infra.apache.org