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

    micrortps setup via voxl_io

    Ask your questions right here!
    3
    14
    963
    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.
    • Alex KushleyevA
      Alex Kushleyev ModalAI Team
      last edited by

      Hi Ryan,

      Does the micrortps agent need to open a standard UART port, such as /dev/ttySx or /dev/ttyUSBx or similar? how hard is it to extend the micrortps client to use libvoxl_io functionality to access the serial port via libvoxl_io instead of standard serial port libraries? You would need to use this header https://gitlab.com/voxl-public/core-libs/libvoxl_io/-/blob/master/lib/include/voxl_io.h and link against libvoxl_io.

      If changing micrortps code is not an option, then some sort of bridge could work. I have done similar things before using pseudo terminals (pty/tty pairs). Basically the bridge could be the master and would read/write using ptyXY and micrortps would be the client and read/write using ttyXY. However, i don't think pseudo terminals are available on VOXL.

      https://stackoverflow.com/questions/52187/virtual-serial-port-for-linux this discusses the pseudo terminal as well another solution using socat. Now, socat is not available on VOXL either, but if you use docker, it can be installed in a small container using apt-get install socat.

      Let me check if we can easily add the socat and pseudo terminals to the VOXL system image..

      It seems perhaps the most robust solution (for now) would be extending micrortps to work with libvolx_io serial ports..

      Alex

      ryan_meagherR 1 Reply Last reply Reply Quote 1
      • ryan_meagherR
        ryan_meagher @Alex Kushleyev
        last edited by ryan_meagher

        @Alex-Kushleyev Thanks for the response! the micrortps_client is running in the nuttx shell on the flight core and is autogenerated based on the *.msg files when building the px4 firmware. In order for it to work with a companion computer (according to the px4/ros slack channel) you have to pass one of the tty devices that is setup for telemetry in modalai's rtps.cmake file.

        The following command will be run from the mavlink console or the voxl-px4-shell:
        micrortps_client start -t UART -d /dev/ttyS6 -b 921600

        The following command will be run from a docker image on voxl:
        micrortps_agent start -t UART -d /dev/ttyX -b 921600

        Due to the fact that the flight core doesn't have wifi, I dont think I can setup a socat connection or pseudo terminal as I am assuming this requires ipv4/ipv6 connectivity on both sides of client/agent.

        It looks like the msg/generate_microRTPS_bridge.py file is calling microRTPS_transport.cpp which is setting up the read/writes so I will try to change this file to use the voxl_io on both sides.

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

          hi @ryan_meagher , yes it looks like you need to implement a custom version of UART_node class, with init, read, write, and a few other functions, which can be just wrappers for libvoxl_io calls. I think this is the best solution in this case and hopefully does not take too much time. Some options are not available, like poll_ms, flow_control, but i think it should be just fine to not implement those.

          Let me know if you have any particular questions regarding using uart with libvoxl_io or anything else.

          Alex

          ryan_meagherR 1 Reply Last reply Reply Quote 0
          • ryan_meagherR
            ryan_meagher @Alex Kushleyev
            last edited by ryan_meagher

            @Alex-Kushleyev That is the route I was taking and have finished implementing in the micrortps_transport.cpp file.

            I have a few questions:

            • @Chad-Sweet said that the libvoxl_io is not supported in a docker environment which is needed in order to build the micrortps_agent with ROS2. Is this possible?

            • The voxl_io.h specifies a buffer length of 128 bytes whereas the micrortps_transport.h uses 1024 byte buffers. Can I pass a buffer larger than 128 to the voxl_uart_write()?

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

              @ryan_meagher , see responses..

              • yes, that is an issue.. libvoxl_io library needs to run on the VOXL host operating system because it calls into some device-specific hardware libraries to talk to the DSP. Hmm. It does seem like some sort of a bridge is needed.. Since microRTPS supports UDP, perhaps the next thing to try is writing a simple app that uses libvoxl_io on the host OS and exposes the data via UDP (read/write)?

              • I don't actually think this is a limitation (128 bytes), it just has not been tested. I am pretty sure you can send more than 128 bytes at a time and receive as well, as long as you allocate a big enough buffer for receiving (see https://gitlab.com/voxl-public/core-libs/libvoxl_io/-/blob/master/lib/apps/voxl-uart-loopback.c for allocation example)

              1 Reply Last reply Reply Quote 0
              • ryan_meagherR
                ryan_meagher
                last edited by ryan_meagher

                @Alex-Kushleyev So something utilitzing the io_rpc similar to the io_rpc_mavparser.c and then exposing it to the voxl_io.h similar to voxl_io_mavparser.c then using this like how you guys are using it in the voxl-vision?

                When developing this functionality on the hexagon sDSP are there any special issues or pitfalls I should pay particular attention to?

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

                  At first, I would not try changing any code that runs on the DSP - just using the functions already exposed in voxl_io.h. So you would write an application that would get data from UDP and send to the serial port using voxl_uart_write. Then read any data using voxl_uart_read and send it out via UDP. Does that make sense?

                  1 Reply Last reply Reply Quote 0
                  • ryan_meagherR
                    ryan_meagher
                    last edited by ryan_meagher

                    @Alex-Kushleyev Thanks for the help, still working on this bridge but have made some progress, able to create io_rpc functions and add some stuff to voxl-vision and am now able to get messages in my docker container with
                    ros2 launch px4_ros_com <launch_file>

                    1 Reply Last reply Reply Quote 0
                    • B
                      benjamin linne
                      last edited by

                      Hey @ryan_meagher , I've managed to get micrortps working without the internal uart. I'm using an ftdi adapter from a uart on the voxl to a usb port on-top of the microhard adapter. This is working well, except the voxl is locking up when we are running several nodes. I suspect it to be a problem with DDS requiring more bandwidth and potentially a race condition occurring. I'm interested in trying your voxl_io version if that is working, and I can provide some help to get the ftdi to usb version working if needed.

                      1 Reply Last reply Reply Quote 0
                      • ryan_meagherR
                        ryan_meagher
                        last edited by

                        I was able to get the microRTPS_client and microRTPS_agent working between the flight core and the voxl. My ROS2 setup is now complete and I have done various testing between the flight core and voxl to confirm this. It turned out to be more work than I expected.

                        I created a compact microRTPS parser on the hexagon sDSP in the voxl_io on the receive side to minimize the snapdragon’s involvement with assembling messages. The messages are passed through the shared memory from the hexagon sDSP to the ARM CPU. I created a UDP tunnel in the voxl_vision (running on yocto Jethro) to tunnel UDP microRTPS messages between the host os and the Ubuntu 20.04 docker container running the micrortps_agent and ros2 px4_ros_com launch file.

                        There are a couple gotchas that I faced. The first is that some characters are being dropped between the flight core and the voxl every so often. I have not isolated which side is at fault (need to connect a logic analyzer and capture the event on the wire), but these cause CRC errors in the messages. Neither side reports an error on the write or read that I was able to log. If I get some additional equipment, I’ll probably try to track down which side is at fault.

                        I wrote a utility program that captures characters on any of the serial buses and logs the data to a file. I’ve verified that even in this simple setup, characters are being dropped. I have the baud rate set at 921600. With only about 6 messages being sent, I’m sending about 650kbps over the wire so this baud rate may need to be increased as the px4 guys recommend a minimum of 1MB.

                        There is also an issue with the way the micrortps_agent handles errors that can cause an eventual lockup if you have CRC errors in the messages that required some modification, which is what I believe you are facing @benjamin-linne . It seemed like the UDP messages were stopping but with tcpdump and voxl-perfmon, I was able to isolate it to the way the transport was handling errors. The fix is reasonably straightforward, but eliminating any CRC errors beforehand avoids this issue.

                        @benjamin-linne not sure if I’m allowed to give out the code but send me you contact info and we can talk offline.

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

                          Hi @ryan_meagher, nice work! Regarding CRC errors, keep in mind that 650kbit/s requires 812kbit/s using UART protocol, since there are 10bits sent for each 8 data bits (1 start and 1 stop bit). So it's possible that one of the sides is not keeping up. You should be able to change the baud rate to 2mbit/s without any issue, at least on VOXL SDSP side (which I have used myself)

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

                            Also, you could do a quick test on DSP side, just write more data to UART port than the baud rate can handle and see what the write() function returns and how much time it takes. Usually the write() function is non-blocking, as it will hand off data to underlying layers to take care of UART writing. But I suspect that if the SDSP UART system runs out of buffers to put your data in, it will probably block until buffer space for writing frees up instead of dropping data. I have not confirmed this, but that's my expectation.

                            1 Reply Last reply Reply Quote 0
                            • B
                              benjamin linne @ryan_meagher
                              last edited by

                              This post is deleted!
                              1 Reply Last reply Reply Quote 0
                              • First post
                                Last post
                              Powered by NodeBB | Contributors