ModalAI Forum
    • Categories
    • Recent
    • Tags
    • Popular
    • Users
    • Groups
    • Register
    • Login

    Buffering in UART return

    VOXL 2
    3
    4
    159
    Loading More Posts
    • Oldest to Newest
    • Newest to Oldest
    • Most Votes
    Reply
    • Reply as topic
    Log in to reply
    This topic has been deleted. Only users with topic management privileges can see it.
    • M
      MartinP
      last edited by

      Hi,

      I have an external sensor (a lidar) connected by UART to J3 on VOXL2 via a M0125 breakout. I am reading successfully on "/dev/ttyHS1". However I am seeing a lot of buffering in the output. If I read in a fast loop (1000Hz) I am seeing data returned in 2048 bytes lumps every 114 ms. This is a problem as the lidar is outputing frames at 10 Hz so data being returned from the UART in bigger packets every 114ms introduces some deplay.

      Q. Is this expected?
      Q. Are there any settings I can use to make the data return in more frequent smaller lumps?

      I open the file as follows

        fd = open("/dev/ttyHS1", O_RDWR);
      
        tcgetattr(fd_, &term);
        cfmakeraw(&term);
        cfsetispeed(&term, B230400);
      
        // term.c_cflag &= ~CRTSCTS; // hw flow conrol off
        // term.c_iflag &= ~(IXON | IXOFF | IXANY);  // Turn off s/w flow ctrl
      
        term.c_cc[VTIME] = 0;
        term.c_cc[VMIN] = 0;
        tcsetattr(fd, TCSANOW, &term);
      
        tcflush(fd, TCIFLUSH);
      

      I also tried fd = open("/dev/ttyHS1", O_RDONLY|O_NOCTTY|O_NONBLOCK); various extra args and turning off flow control with no change.

      Any ideas appreciated.
      Thanks

      1 Reply Last reply Reply Quote 0
      • modaltbM
        modaltb ModalAI Team
        last edited by

        Hi @MartinP ,

        This is what we use in our MAVLink server to talk to external flight controllers that we use at 921k with success as far as I know as a reference:

        https://gitlab.com/voxl-public/voxl-sdk/services/voxl-mavlink-server/-/blob/master/src/qrb5165_interface.c#L251

        We test a loop back at 4Mbit as well with success, so it's not expected as far as I know! Can you give the code above a look? When I write UART code this is where I start typically.

        Thanks!

        1 Reply Last reply Reply Quote 0
        • modaltbM
          modaltb ModalAI Team
          last edited by

          Actually our loop back doesn't check latency right, let us get a test going over here and I can let you know what we see (might be a couple/few days).

          1 Reply Last reply Reply Quote 0
          • Alex KushleyevA
            Alex Kushleyev ModalAI Team
            last edited by

            Hello @MartinP ,

            I believe here is what is happening in your case:

            • Your sensor (Lidar) is sending data continuously without any breaks (360 degree lidar?). Maybe the Lidar processes each measurement and sends it out right away, so perhaps there are small breaks between the data measurements
            • The hardware UART buffer size in VOXL2 is set to 2048 (based on the data chunk size you get)
            • You are using the High Speed uart port (HS in the ttyHS1), which uses DMA to transfer data to cpu (one cpu interrupt per buffer)
            • Typically, the DMA-based UART hardware decides when to send the data to CPU when one of several conditions is met: there is a long enough break in the data stream that can be considered end of "packet" or the current data buffer is full (2048 in this case)
            • Since it looks like the data from Lidar is coming without long breaks, I see several possible solutions:
            1. If possible, configure the Lidar to have a break between each scan (but you would need to know the minimum break size for UART hardware to trigger a rx interrupt to CPU)
            2. reduce the rx buffer size for UART (probably somewhere in the Device Tree)

            However, it would be helpful to understand what the data transmission from Lidar looks like. Also, please note that increasing the baud rate of the communication will probably not help. Significantly increasing the baud rate may result in potentially rx interrupt triggering on each measurement, which would not be very good for the CPU.

            1 Reply Last reply Reply Quote 0
            • First post
              Last post
            Powered by NodeBB | Contributors