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

    no data while querying /run/mpa/tflight_data/request using Python

    Ask your questions right here!
    2
    18
    972
    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.
    • ?
      A Former User @sansoy
      last edited by

      @sansoy

      I appreciate that you think I've ascended to the Jedi level... I don't know if I agree but I'll keep trying to help you out!

      You're getting the error because of the line that has the pipe_is_type() function. That function is, for example purposes, checking that a pipe has type "text" which is the type the pipe is publishing in the example code.

      But you're modifying the example code to read from a different pipe and so the type might not be text. To check what type was being published to the pipe, I ran:

      voxl2:/$ cat /run/mpa/tflite_data/info
      {
      	"name":	"tflite_data",
      	"location":	"/run/mpa/tflite_data/",
      	"type":	"ai_detection_t",
      	"server_name":	"voxl-tflite-server",
      	"size_bytes":	16384,
      	"server_pid":	2910
      }
      

      Okay, so we can see here "type" : "ai_detection_t" which you may remember as the ai_detection_t struct from voxl-tflite-server. So instead, you need to modify that pipe_is_type() function to have it check for "ai_detection_t" instead of "text". You could, also, just delete the line as it's just a safety check. But better to be safe!!

      Now that should fix your immediate issue. The final piece of the puzzle, here, will be creating a callback function and registering your client to it. I'm not a libmodal-pipe expert but I think the way we do it in the example code will work for you. The simple callback that's defined there just passes raw bytes of data as a char* and so what I think you'll want to do is typecast that data to type ai_detection_t*. I'm going to double check this sometime today. But then you'll have a struct of type ai_detection_t and you can access the member variables to get what you're looking for. For right now, you should just copy-paste the ai_detection_t struct definition in your code so that your module will know what an ai_detection_t is. In the future we'll expose this header in /usr/include.

      Hope this helps!!

      Thomas Patton
      thomas.patton@modalai.com

      1 Reply Last reply Reply Quote 0
      • S
        sansoy @sansoy
        last edited by

        @sansoy so i updated my copy named modal-tflite_data-client.c with fields listed in tflite_data/info
        {
        "name": "tflite_data",
        "location": "/run/mpa/tflite_data/",
        "type": "ai_detection_t",
        "server_name": "voxl-tflite-server",
        "size_bytes": 16384,
        "server_pid": 25994
        }

        Recompiled the script and ran
        voxl2:/run/mpa/tflite_data$ modal-tflite_data-client
        channel 0 connected to server
        sending tflite_data to server control pipe
        failed to send control command to server
        ERROR: control pipe not available

        but when i put a picture in front of it and the object detection is working i'm getting!

        voxl2:/run/mpa/tflite_data$ modal-tflite_data-client
        channel 0 connected to server
        sending tflite_data to server control pipe
        failed to send control command to server
        ERROR: control pipe not available
        received 172 bytes on channel 0: LXOV��O6
        received 172 bytes on channel 0: LXOV��F[6
        received 172 bytes on channel 0: LXOV7?_�6
        received 172 bytes on channel 0: LXOV! ��6
        received 172 bytes on channel 0: LXOV
        ���6
        received 172 bytes on channel 0: LXOV����6

        ? 1 Reply Last reply Reply Quote 0
        • ?
          A Former User @sansoy
          last edited by

          @sansoy

          Sweet, you should be able then to cast the char* data coming into your callback function into type ai_detection_t* and then access the member variables for x/y min/max for the boxes.

          Thomas Patton

          S 3 Replies Last reply Reply Quote 0
          • S
            sansoy @Guest
            last edited by

            @thomas so i included ai_detection.h and cast the char* data variable and compiled successfully and several of my services died ...lol

            Service Name | Enabled | Running | CPU Usage

            docker-autorun | Disabled | Not Running |
            modallink-relink | Disabled | Not Running |
            voxl-camera-server | Enabled | Not Running |
            voxl-cpu-monitor | Enabled | Not Running |
            voxl-dfs-server | Disabled | Not Running |
            voxl-feature-tracker | Disabled | Not Running |
            voxl-flow-server | Disabled | Not Running |

            I've tried everything to restart both camera server and cpu monitor and no luck. Rebooted, Cycled Power,
            Any thoughts on how to recover from this?

            1 Reply Last reply Reply Quote 0
            • S
              sansoy @Guest
              last edited by

              @thomas from my syslog

              Jan 23 00:46:51 m0054 voxl-camera-server[4202]: /usr/bin/voxl-camera-server: symbol lookup error: /usr/bin/voxl-camera-server: undefined symbol: pipe_validate_mavlin
              k_message_t
              Jan 23 00:46:51 m0054 systemd[1]: voxl-camera-server.service: Main process exited, code=exited, status=127/n/a
              Jan 23 00:46:51 m0054 systemd[1]: voxl-camera-server.service: Failed with result 'exit-code'.
              Jan 23 00:46:51 m0054 voxl-px4[1656]: ERROR [muorb] SLPI: Failed to parse version request response packet!
              Jan 23 00:46:53 m0054 voxl-px4[1656]: message repeated 534 times: [ ERROR [muorb] SLPI: Failed to parse version request response packet!]
              Jan 23 00:46:53 m0054 systemd[1]: voxl-camera-server.service: Service hold-off time over, scheduling restart.
              Jan 23 00:46:53 m0054 systemd[1]: voxl-camera-server.service: Scheduled restart job, restart counter is at 1.
              Jan 23 00:46:53 m0054 systemd[1]: Stopped voxl-camera-server.
              Jan 23 00:46:53 m0054 systemd[1]: Started voxl-camera-server.
              Jan 23 00:46:53 m0054 voxl-camera-server[4226]: /usr/bin/voxl-camera-server: symbol lookup error: /usr/bin/voxl-camera-server: undefined symbol: pipe_validate_mavlin
              k_message_t
              Jan 23 00:46:53 m0054 systemd[1]: voxl-camera-server.service: Main process exited, code=exited, status=127/n/a
              Jan 23 00:46:53 m0054 systemd[1]: voxl-camera-server.service: Failed with result 'exit-code'.
              Jan 23 00:46:53 m0054 voxl-px4[1656]: ERROR [muorb] SLPI: Failed to parse version request response packet!

              Actually several enabled services wont restart
              Service Name | Enabled | Running | CPU Usage

              docker-autorun | Disabled | Not Running |
              modallink-relink | Disabled | Not Running |
              voxl-camera-server | Enabled | Not Running |
              voxl-cpu-monitor | Enabled | Not Running |
              voxl-dfs-server | Disabled | Not Running |
              voxl-feature-tracker | Disabled | Not Running |
              voxl-flow-server | Disabled | Not Running |
              voxl-imu-server | Enabled | Running | 0.0%
              voxl-lepton-server | Enabled | Not Running |
              voxl-mavcam-manager | Disabled | Not Running |
              voxl-mavlink-server | Enabled | Not Running |
              voxl-modem | Disabled | Not Running |
              voxl-neopixel-manager | Disabled | Not Running |
              voxl-portal | Enabled | Not Running |
              voxl-px4-imu-server | Disabled | Not Running |
              voxl-px4 | Enabled | Running | 32.9%
              voxl-qvio-server | Disabled | Not Running |
              voxl-rangefinder-server | Disabled | Not Running |
              voxl-remote-id | Disabled | Not Running |
              voxl-softap | Disabled | Not Running |
              voxl-static-ip | Disabled | Not Running |
              voxl-stitcher | Disabled | Not Running |
              voxl-streamer | Disabled | Not Running |
              voxl-tag-detector | Disabled | Not Running |
              voxl-tflite-server | Enabled | Running | 0.8%
              voxl-time-sync | Disabled | Not Running |
              voxl-uvc-server | Disabled | Not Running |
              voxl-vision-hub | Enabled | Not Running |
              voxl-wait-for-fs | Enabled | Completed |
              voxl-wfb-rx-video | Disabled | Not Running |
              voxl-wfb-rx | Disabled | Not Running |
              voxl-wfb-tx-video | Disabled | Not Running |
              voxl-wfb-tx | Disabled | Not Running |
              voxl2:/$

              all i did was compile and make install my modal-tflite_data-client.c file

              1 Reply Last reply Reply Quote 0
              • S
                sansoy @Guest
                last edited by

                @thomas its all working now.

                had to reinstall the latest sdk. I'm guessing make install is a no-no. so just did a make and ran the executable.

                voxl2:/libmodal-pipe/build/examples(master)$ ./modal-tflite_data-client
                channel 0 connected to server
                Bounding Box Coordinates:
                score: 0.558105, x_min: 406.000000, y_min: 417.000000, x_max: 535.000000, y_max: 472.000000
                Bounding Box Coordinates:
                score: 0.429199, x_min: 427.000000, y_min: 370.000000, x_max: 573.000000, y_max: 426.000000
                Bounding Box Coordinates:
                score: 0.617676, x_min: 498.000000, y_min: 300.000000, x_max: 655.000000, y_max: 358.000000
                Bounding Box Coordinates:
                score: 0.416748, x_min: 505.000000, y_min: 302.000000, x_max: 659.000000, y_max: 359.000000
                Bounding Box Coordinates:
                score: 0.739258, x_min: 506.000000, y_min: 304.000000, x_max: 667.000000, y_max: 364.000000
                Bounding Box Coordinates:
                score: 0.493652, x_min: 4.000000, y_min: -1.000000, x_max: 781.000000, y_max: 109.000000
                Bounding Box Coordinates:
                score: 0.547852, x_min: 509.000000, y_min: 306.000000, x_max: 664.000000, y_max: 363.000000
                Bounding Box Coordinates:
                score: 0.640625, x_min: 505.000000, y_min: 310.000000, x_max: 660.000000, y_max: 369.000000

                ? 1 Reply Last reply Reply Quote 0
                • ?
                  A Former User @sansoy
                  last edited by

                  @sansoy

                  Amazing, glad you got it working!!

                  Thomas

                  S 1 Reply Last reply Reply Quote 0
                  • S
                    sansoy @Guest
                    last edited by

                    @thomas Hey thomas, we've got the handshaking between your C helper program and our python script working well. i successfully loaded Yolov8 on the voxl and it works really well on images. Was wondering if we could open the camera pipe the same as the tflite_data pipe to run inference on the frames in realtime. i noticed in your /data/web_root/index.html that you are using websockets for serving the videos in the browsers. is this the better route?

                    ? 1 Reply Last reply Reply Quote 0
                    • ?
                      A Former User @sansoy
                      last edited by

                      @sansoy

                      When you say "open the camera pipe" I'm not fully sure I understand what you mean. voxl-tflite-server in its current state already opens up a camera pipe for input images and then publishes its predictions out in that tflite_data pipe and so if you're asking if that's possible then absolutely. Or are you trying to make an output image pipe or something with the predictions overlayed or something?

                      Sorry, just not fully sure what you're asking.

                      Thomas Patton

                      S 1 Reply Last reply Reply Quote 0
                      • S
                        sansoy @Guest
                        last edited by

                        @thomas i'm not using voxl-tflite-server. On my voxl2 i installed the latest version of YOLOv8 from Ultralytics https://docs.ultralytics.com/ and it works well when i run inference on local images. i wanted to test just using a local python script that streams video frames from the hires_small_color camera and runs inference.

                        ? 1 Reply Last reply Reply Quote 0
                        • ?
                          A Former User @sansoy
                          last edited by

                          @sansoy

                          Oh ok I see what you're going for then. However we don't currently have an API for doing streaming video in Python, only C++ through libmodal-pipe like we do in modules like voxl-tflite-server.

                          If you really want to use Python, you could write a small C++ helper program to take in images from the camera and then use some sort of event-driven framework to pass those images to your Python script. Perhaps you could do something clever with just writing them to a temporary directory and setting up a callback-based interface in Python to detect when new files are present.

                          Sorry for the indirect answer, hope this at least helps some!!

                          Thomas Patton

                          S 1 Reply Last reply Reply Quote 0
                          • S
                            sansoy @Guest
                            last edited by

                            @thomas I already wrote a c helper function that uses libmodal-pipe to pipe tflite_data that my python script reads in realtime. it works well
                            per your message " small C++ helper program to take in images from the camera". how would i modify my c helper to use libmodal-pipe to stream data from one of the cameras?

                            ? 1 Reply Last reply Reply Quote 0
                            • ?
                              A Former User @sansoy
                              last edited by

                              @sansoy

                              Oh great, if you already have a function that works with libmodal-pipe then you shouldn't have much trouble writing one for the cameras. Take a look at these lines for the initial code to register the callback function to the camera pipe, this sets up _camera_helper_cb to receive images on callback. For an example of parsing that data, maybe check out these lines in a different module. There's a bit of extra info here but this shows the gist of casting the raw char* bytes into something like an OpenCV image. Definitely modify as needed to fit your use case!

                              Keep me posted, happy to help however I can!

                              Thomas Patton

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