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

    voxl-camera-server failed to set pipe size: Cannot allocate memory

    Ask your questions right here!
    3
    3
    71
    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.
    • P
      paul.foley
      last edited by

      Hello,
      I have a C++ application for doing image processing of frames from voxl-camera-server. When I run it, within a few minutes, my application stops receiving frames and I see the following from the camera server about failing to set pipe size. Once that occurs, restarting my application or the camera server does not help. Rebooting is the only thing I have found that consistently gets the camera server back in a good state.

      Oct 03 14:11:21 m0054 voxl-camera-server[10625]: thread is locked to cores: 4 5 6 7
      Oct 03 14:11:21 m0054 voxl-camera-server[10625]: Connected to cpu-monitor
      Oct 03 14:11:21 m0054 voxl-camera-server[10625]: Skipping Camera: tracking_front, configuration marked disabled
      Oct 03 14:11:21 m0054 voxl-camera-server[10625]: Skipping Camera: hires_front, configuration marked disabled
      Oct 03 14:11:21 m0054 voxl-camera-server[10625]: Starting Camera: hires_down (id #2)
      Oct 03 14:11:21 m0054 voxl-camera-server[10625]: gbm_create_device(156): Info: backend name is: msm_drm
      Oct 03 14:11:21 m0054 voxl-camera-server[10625]: Skipping Camera: tracking_down, configuration marked disabled
      Oct 03 14:11:21 m0054 voxl-camera-server[10625]: ------ voxl-camera-server: Started 1 of 4 cameras
      Oct 03 14:11:21 m0054 voxl-camera-server[10625]: ------ voxl-camera-server: Camera server is now running
      Oct 03 14:16:48 m0054 voxl-camera-server[10625]: WARNING failed to set pipe size: Cannot allocate memory
      

      I'm on a Starling 2 Max. Below is the version information.

      voxl2:~$ voxl-version 
      --------------------------------------------------------------------------------
      system-image: 1.8.02-M0054-14.1a-perf
      kernel:       #1 SMP PREEMPT Mon Nov 11 22:59:41 UTC 2024 4.19.125
      --------------------------------------------------------------------------------
      hw platform:  M0054
      mach.var:     1.2.1
      --------------------------------------------------------------------------------
      voxl-suite:   1.4.1
      --------------------------------------------------------------------------------
      Packages:
      Repo:  http://voxl-packages.modalai.com/ ./dists/qrb5165/sdk-1.4/binary-arm64/
      Last Updated: 2023-03-02 12:58:40
      WARNING: repo file has changed since last update,
              packages may have originated from a different repo
      List:
      kernel-module-voxl-fsync-mod-4.19.125     1.0-r0
      kernel-module-voxl-gpio-mod-4.19.125      1.0-r0
      kernel-module-voxl-platform-mod-4.19.125  1.0-r0
      libfc-sensor                              1.0.7
      libmodal-cv                               0.5.16
      libmodal-exposure                         0.1.3
      libmodal-journal                          0.2.2
      libmodal-json                             0.4.3
      libmodal-pipe                             2.10.6
      libqrb5165-io                             0.4.9
      libvoxl-cci-direct                        0.2.5
      libvoxl-cutils                            0.1.1
      modalai-slpi                              1.1.19
      mv-voxl                                   0.1-r0
      qrb5165-bind                              0.1-r0
      qrb5165-dfs-server                        0.2.0
      qrb5165-imu-server                        1.1.2
      qrb5165-rangefinder-server                0.1.4
      qrb5165-slpi-test-sig                     01-r0
      qrb5165-system-tweaks                     0.3.4
      qrb5165-tflite                            2.8.0-2
      voxl-bind-spektrum                        0.1.1
      voxl-camera-calibration                   0.5.9
      voxl-camera-server                        2.1.1
      voxl-ceres-solver                         2:1.14.0-10
      voxl-configurator                         0.9.7
      voxl-cpu-monitor                          0.5.3
      voxl-docker-support                       1.3.1
      voxl-elrs                                 0.4.1
      voxl-esc                                  1.5.1
      voxl-feature-tracker                      0.5.2
      voxl-flow-server                          0.3.6
      voxl-fsync-mod                            1.0-r0
      voxl-gphoto2-server                       0.0.10
      voxl-gpio-mod                             1.0-r0
      voxl-io-server                            0.0.4
      voxl-jpeg-turbo                           2.1.3-5
      voxl-lepton-server                        1.3.3
      voxl-lepton-tracker                       0.0.4
      voxl-libgphoto2                           0.0.4
      voxl-libuvc                               1.0.7
      voxl-logger                               0.4.9
      voxl-mavcam-manager                       0.5.7
      voxl-mavlink                              0.1.1
      voxl-mavlink-server                       1.4.4
      voxl-modem                                1.1.5
      voxl-mongoose                             7.7.0-1
      voxl-mpa-to-ros                           0.3.9
      voxl-mpa-tools                            1.3.7
      voxl-open-vins                            0.4.16
      voxl-open-vins-server                     0.3.0
      voxl-opencv                               4.5.5-2
      voxl-osd                                  0.1.1
      voxl-platform-mod                         1.0-r0
      voxl-portal                               0.7.5
      voxl-px4                                  1.14.0-2.0.94
      voxl-px4-imu-server                       0.1.2
      voxl-px4-params                           0.6.3
      voxl-qvio-server                          1.1.1
      voxl-remote-id                            0.0.9
      voxl-reset-slpi                           0.0.1
      voxl-state-estimator                      0.0.4
      voxl-streamer                             0.7.5
      voxl-suite                                1.4.1
      voxl-tag-detector                         0.0.4
      voxl-tflite-server                        0.3.9
      voxl-utils                                1.4.4
      voxl-uvc-server                           0.1.7
      voxl-vision-hub                           1.8.17
      voxl-vtx                                  1.1.8
      voxl2-io                                  0.0.3
      voxl2-system-image                        1.8.02-r0
      voxl2-wlan                                1.0-r0
      --------------------------------------------------------------------------------
      

      As a test I created a very simple application that just connects to the camera pipe and logs each time it receives a frame. I've included the code below. This exhibits the same behavior as my more complex image processing application. Is there any issue with the way I am connecting to the pipe and processing frames?

      #include <atomic>
      #include <csignal>
      #include <cstdint>
      #include <iostream>
      #include <modal_pipe.h>
      #include <thread>
      #include <unistd.h>
      #include <mutex>
      #include <chrono>
      
      using namespace std::chrono_literals;
      
      std::string g_cameraString="hires_down_small_color";
      uint32_t g_frameCounter=0;
      uint32_t g_numIterations=100;
      std::mutex g_iterationMutex;
      bool g_keepRunning=true;
      // Use atomic to ensure safety in signal handlers
      std::atomic<bool> got_signal{false};
      
      
      void _camera_connect_cb( int   ch,
                                      void* context){
          printf("Connected to camera server\n");
      }
      
      
      void _camera_disconnect_cb( int   ch,
                                         void* context) {
          fprintf(stderr, "Disonnected from camera server\n");
      }
      
      void _camera_helper_cb( int ch,
                                    camera_image_metadata_t meta, char* frame,
                                    void* context) {
        std::cout<<__func__<<"Got notified of new frame #"<<g_frameCounter++<<"..."<<std::endl;
      
        //if pipe_client_bytes_in_pipe returns a positive number it means we have fallen behind and should skip this frame 
        if (pipe_client_bytes_in_pipe(ch) > 0) {
                  fprintf(
                      stderr,
                      "WARNING, skipping frame on channel %d due to frame backup\n",
                      ch);
              return;
          }
          {
            std::lock_guard<std::mutex> lg(g_iterationMutex);
            g_numIterations--;
          }
      
        return;
      } 
      
      void cleanup()
      {
        std::cout<<__func__<<std::endl;
        pipe_client_close_all();
      }
      
      void connectToCameraPipe()
      {
          // connect to camera pipe
          int ch = pipe_client_get_next_available_channel();
          pipe_client_set_connect_cb(ch, _camera_connect_cb, NULL);
          pipe_client_set_disconnect_cb(ch, _camera_disconnect_cb, NULL);
          pipe_client_set_camera_helper_cb(ch, _camera_helper_cb, NULL);
          //pipes all live under /run/mpa on VOXL
          std::string input_pipe_dir( "/run/mpa/");
          // add the name of the camera we want to get frames from
          std::string camera_pipe_path=input_pipe_dir;
          camera_pipe_path.append(g_cameraString);
          if (pipe_client_open(ch, camera_pipe_path.c_str(), "VoxlCameaFramePipeTest",
                               CLIENT_FLAG_EN_CAMERA_HELPER, 0)) {
              printf("%s | Failed to open pipe: %s \n", __func__, camera_pipe_path.c_str());
              return;
          }
          else {
              printf("%s | Successfully opened pipe: %s \n", __func__, camera_pipe_path.c_str());
          }
      }
      
      void usage() {
          std::cout << "Usage: VoxlCameraFramePipeTest <options> \n"
                    << "Options:\n"
                    << "  -c <camera_name>   Name of the camera (string). Default value is "<<g_cameraString<<"\n"
                    << "  -n <iterations>    Number of iterations (unsigned integer). Default value is "<<g_numIterations<<"\n"
                    << "  -h                 Print this help message"<<std::endl;
      }
      
      bool parseArgs(int argc, char** argv) {
        int opt;
        while ( (opt = getopt (argc, argv, "c:n:h") ) != -1)
        {
          switch (opt)
          {
            case 'c':
              g_cameraString=optarg;
              break; 
            case 'n':
              g_numIterations=std::stoul(optarg);
              break;
            case 'h':
              usage();
              g_keepRunning=false;
              break; 
            default:
              printf("%s | received unexpected argument.", __func__); 
              usage();
              return false;
          }
        }
        return true;
      }
      
      void signal_handler(int signal) {
          if (signal == SIGINT) {
              std::cout<<"Got signal"<<std::endl;
              got_signal = true;
          } 
      }
      
      int main(int argc, char** argv)
      {
        if(!parseArgs(argc, argv))
        {
          return -1;
        }
        if(g_keepRunning)
        {
          // Register the signal handler
          std::signal(SIGINT, signal_handler);
          std::cout << "Press Ctrl+C to trigger SIGINT...\n";
          connectToCameraPipe();
          while (g_keepRunning && !got_signal) {
            std::this_thread::sleep_for(10ms);
            {
              std::lock_guard<std::mutex> lg(g_iterationMutex);
              g_keepRunning=(g_numIterations>0);
            }
          }
            cleanup();
        }
      
        return 0;
      }
      
      
      

      Thank you,
      Paul

      1 Reply Last reply Reply Quote 0
      • Riccardo BenedettiR
        Riccardo Benedetti
        last edited by Riccardo Benedetti

        Hello,
        Same issue and same SDK here:

        voxl2:~$ voxl-camera-server
        detected system image 1.8.2
        using new imx412 defaults
        MISP awb str: auto
        Setting MISP AWB to AutoMISP awb str: auto
        Setting MISP AWB to Auto=================================================================
        configuration for 3 cameras:
        
        cam #0
            name:                hires
            sensor type:         imx412
            isEnabled:           1
            camId:               1
            camId2:              -1
            fps:                 30
            en_rotate:           0
            en_rotate2:          0
        
            en_preview:          0
            pre_width:           640
            pre_height:          480
            en_raw_preview:      0
        
            en_small_video:      1
            small_video_width:   1024
            small_video_height:  768
        
            en_large_video:      1
            large_video_width:   4056
            large_video_height:  3040
        
            en_misp:             0
            misp_width:          -1
            misp_height:         -1
        
            en_snapshot:         1
            snap_width:          4056
            snap_height:         3040
            exif_focal_length:   3.100000
            exif_focal_len_35mm_format:17
            exif_fnumber:        1.240000
        
            ae_mode:             isp
            msv_exposure_min_us: 20
            msv_exposure_max_us: 33000
            gain_min           : 54
            gain_max           : 8000
            standby_enabled:     0
            decimator:           1
            independent_exposure:0
        
        cam #1
            name:                tracking_rear
            sensor type:         ar0144
            isEnabled:           0
            camId:               2
            camId2:              -1
            fps:                 30
            en_rotate:           0
            en_rotate2:          0
        
            en_preview:          1
            pre_width:           1280
            pre_height:          800
            en_raw_preview:      1
        
            en_small_video:      0
            small_video_width:   -1
            small_video_height:  -1
        
            en_large_video:      0
            large_video_width:   -1
            large_video_height:  -1
        
            en_misp:             1
            misp_width:          1280
            misp_height:         800
        
            en_snapshot:         0
            snap_width:          -1
            snap_height:         -1
            exif_focal_length:   0.000000
            exif_focal_len_35mm_format:0
            exif_fnumber:        0.000000
        
            ae_mode:             lme_msv
            msv_exposure_min_us: 20
            msv_exposure_max_us: 12000
            gain_min           : 54
            gain_max           : 8000
            standby_enabled:     0
            decimator:           1
            independent_exposure:0
        
        cam #2
            name:                tracking_down
            sensor type:         ar0144
            isEnabled:           0
            camId:               0
            camId2:              -1
            fps:                 30
            en_rotate:           0
            en_rotate2:          0
        
            en_preview:          1
            pre_width:           1280
            pre_height:          800
            en_raw_preview:      1
        
            en_small_video:      0
            small_video_width:   -1
            small_video_height:  -1
        
            en_large_video:      0
            large_video_width:   -1
            large_video_height:  -1
        
            en_misp:             1
            misp_width:          1280
            misp_height:         800
        
            en_snapshot:         0
            snap_width:          -1
            snap_height:         -1
            exif_focal_length:   0.000000
            exif_focal_len_35mm_format:0
            exif_fnumber:        0.000000
        
            ae_mode:             lme_msv
            msv_exposure_min_us: 20
            msv_exposure_max_us: 12000
            gain_min           : 54
            gain_max           : 8000
            standby_enabled:     0
            decimator:           1
            independent_exposure:0
        
        fsync_en:            1
        fsync_gpio:          109
        =================================================================
        thread is locked to cores: 4 5 6 7
        connected to mavlink pipe
        Connected to cpu-monitor
        Starting Camera: hires (id #1)
        gbm_create_device(156): Info: backend name is: msm_drm
        Skipping Camera: tracking_rear, configuration marked disabled
        Skipping Camera: tracking_down, configuration marked disabled
        
        ------ voxl-camera-server: Started 1 of 3 cameras
        
        ------ voxl-camera-server: Camera server is now running
        WARNING failed to set pipe size: Cannot allocate memory
        ***
        PIPE NOT CREATED!!
        ***
        pipe 5 size achieved: -1 requested: 1048576
        Killed
        voxl2:~$ 
        
        voxl2:~$ voxl-version
        --------------------------------------------------------------------------------
        system-image: 1.8.02-M0054-14.1a-perf
        kernel:       #1 SMP PREEMPT Mon Nov 11 22:47:44 UTC 2024 4.19.125
        --------------------------------------------------------------------------------
        hw platform:  M0054
        mach.var:     1.0.1
        --------------------------------------------------------------------------------
        voxl-suite:   1.4.1
        

        Any insight?

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

          Hi @Riccardo-Benedetti and @paul-foley ,

          This issue is not common. There is a potential condition (which we are going to look into) when a MPA client crashes and does not close the pipes properly, the MPA server side will keep the allocated resources open. If the client crashes repeatedly, eventually there will be no more memory for the Kernel to allocate for the new pipes.

          Please check to make sure that you have no client processes that are subscribing to image streams and are crashing and restarting (perhaps restarting automatically by systemd). It is possible that a process that is not your test app is misbehaving for some reason and is causing this memory leak by continuous crashing and re-starting.

          Also, what if you just use voxl-inspect-cam to inspect the single camera stream and no other camera clients running, does the same issue happen?

          Alex

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