ifm / libo3d3xx

Driver and utilities for IFM Efector O3D3xx depth cameras
Apache License 2.0
38 stars 39 forks source link

Image capture time (more than 1.5 seconds) #143

Closed robinbansal08 closed 3 years ago

robinbansal08 commented 4 years ago

I have cross compiled my code and deployed it over the camera O3D303 and the code is continuously running since 3 weeks. I have noticed that initially the time to capture images was around 450-500ms for couple of days but later I noticed that the max image capture time was increasing slowing with each and every day with around 30-50ms. At present, after 3 weeks, the image capture time is more than 1.5 seconds, which is around more than 3 times what it should be. Can you please suggest, what is the issue here.


    auto start = high_resolution_clock::now();

    o3d3xx::Logging::Init();
    cout<<"Getting image over cam directly "<<endl;
    o3d3xx::Camera::Ptr cam = std::make_shared<o3d3xx::Camera>();
    o3d3xx::ImageBuffer::Ptr img = std::make_shared<o3d3xx::ImageBuffer>();
    o3d3xx::FrameGrabber::Ptr fg = std::make_shared<o3d3xx::FrameGrabber>(cam, o3d3xx::IMG_AMP|o3d3xx::IMG_RDIS|o3d3xx::IMG_CART);
    fg->SWTrigger();
    if (! fg->WaitForFrame(img.get(), 2000))
    {
        cout << RED<<"Timeout waiting for camera!" << RESET <<std::endl;
        exit (-1);
    }
    pcl::copyPointCloud(*(img->Cloud()), *cloud_xyzi);
    image = img->DepthImage();

    auto end = high_resolution_clock::now();
    auto duration = duration_cast<milliseconds>(end - start);
    cout<<"=> Current Image capture time: "<<duration.count()<<"ms"<<endl;
    if(duration.count() > maxImageCaptureTime)
        maxImageCaptureTime = duration.count();
    cout<<"=> Max Image capture time: "<<maxImageCaptureTime<<"ms"<<endl;

Here is the dump file:

{
    "o3d3xx": {
        "libo3d3xx": "707",
        "Date": "Mon Aug 31 10:15:10 2020",
        "HWInfo": {
            "Illumination": "#!02_I300_001_04201465_008001175",
            "Diagnose": "#!02_D322_C34_04068012_008026824",
            "Connector": "#!02_A300_C40_04246016_008023176",
            "MACAddress": "00:02:01:41:39:8D",
            "MiraSerial": "8270-81ca-0e78-0290",
            "Frontend": "#!02_F342_C34_19_00155_008023607",
            "Mainboard": "#!02_M381_C41_04215040_008023690"
        },
        "SWVersion": {
            "Main_Application": "1.0.44",
            "Linux": "Linux version 3.14.34-rt31-yocto-standard-00048-gc8112a91aeb2-dirty (jenkins@dettlx190) (gcc version 4.9.2 (GCC) ) #1 SMP PREEMPT RT Wed Mar 27 18:25:10 CET 2019",
            "Diagnostic_Controller": "v1.0.44-2dcaabbc73-dirty",
            "IFM_Recovery": "unversioned",
            "Algorithm_Version": "2.2.14",
            "Calibration_Device": "00:02:01:41:39:8d",
            "Calibration_Version": "1.0.2",
            "IFM_Software": "1.30.5309"
        },
        "Device": {
            "Name": "New sensor",
            "Description": "",
            "ActiveApplication": "1",
            "PcicTcpPort": "50010",
            "PcicProtocolVersion": "3",
            "IOLogicType": "1",
            "IODebouncing": "true",
            "IOExternApplicationSwitch": "0",
            "SessionTimeout": "30",
            "ServiceReportPassedBuffer": "15",
            "ServiceReportFailedBuffer": "15",
            "ExtrinsicCalibTransX": "0",
            "ExtrinsicCalibTransY": "0",
            "ExtrinsicCalibTransZ": "0",
            "ExtrinsicCalibRotX": "0",
            "ExtrinsicCalibRotY": "0",
            "ExtrinsicCalibRotZ": "0",
            "EvaluationFinishedMinHoldTime": "10",
            "SaveRestoreStatsOnApplSwitch": "true",
            "IPAddressConfig": "0",
            "PasswordActivated": "false",
            "OperatingMode": "1",
            "DeviceType": "1:2",
            "ArticleNumber": "O3D303",
            "ArticleStatus": "AD",
            "UpTime": "713.91333333333296",
            "ImageTimestampReference": "1574208180",
            "TemperatureFront1": "3276.6999999999998",
            "TemperatureFront2": "3276.6999999999998",
            "TemperatureIMX6": "28.906000137329102",
            "TemperatureIllu": "35.600000000000001",
            "PNIODeviceName": "",
            "EthernetFieldBus": "0",
            "EthernetFieldBusEndianness": "0",
            "EnableAcquisitionFinishedPCIC": "false"
        },
        "Net": {
            "MACAddress": "",
            "NetworkSpeed": "0",
            "StaticIPv4Address": "192.168.0.12",
            "StaticIPv4SubNetMask": "255.255.255.0",
            "StaticIPv4Gateway": "192.168.0.201",
            "UseDHCP": "false"
        },
        "Apps": [
            {
                "Name": "Box Detection Application",
                "Description": "",
                "TriggerMode": "2",
                "PcicTcpResultSchema": "{ \"layouter\": \"flexible\", \"format\": { \"dataencoding\": \"ascii\" }, \"elements\": [ { \"type\": \"string\", \"value\": \"star\", \"id\": \"start_string\" }, { \"type\": \"blob\", \"id\": \"normalized_amplitude_image\" }, { \"type\": \"blob\", \"id\": \"distance_image\" }, { \"type\": \"blob\", \"id\": \"x_image\" }, { \"type\": \"blob\", \"id\": \"y_image\" }, { \"type\": \"blob\", \"id\": \"z_image\" }, { \"type\": \"blob\", \"id\": \"confidence_image\" }, { \"type\": \"blob\", \"id\": \"diagnostic_data\" }, { \"type\": \"string\", \"value\": \"stop\", \"id\": \"end_string\" } ] }",
                "PcicEipResultSchema": "{ \"layouter\": \"flexible\", \"format\": { \"dataencoding\": \"binary\", \"order\": \"big\" }, \"elements\" : [ { \"type\": \"string\", \"value\": \"star\", \"id\": \"start_string\" }, { \"type\": \"records\", \"id\": \"models\", \"elements\": [ { \"type\": \"int16\", \"id\": \"boxFound\" }, { \"type\": \"int16\", \"id\": \"width\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"height\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"length\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"xMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"yMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"zMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"yawAngle\" }, { \"type\": \"int16\", \"id\": \"qualityLength\" }, { \"type\": \"int16\", \"id\": \"qualityWidth\" }, { \"type\": \"int16\", \"id\": \"qualityHeight\" } ] }, { \"type\": \"string\", \"value\": \"stop\", \"id\": \"end_string\" } ] }",
                "PcicPnioResultSchema": "{\"layouter\" : \"flexible\", \"format\": { \"dataencoding\": \"binary\", \"order\": \"big\" }, \"elements\" : [ { \"type\": \"string\", \"value\": \"star\", \"id\": \"start_string\" }, { \"type\": \"records\", \"id\": \"models\", \"elements\": [ { \"type\": \"int16\", \"id\": \"boxFound\" }, { \"type\": \"int16\", \"id\": \"width\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"height\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"length\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"xMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"yMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"zMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"yawAngle\" }, { \"type\": \"int16\", \"id\": \"qualityLength\" }, { \"type\": \"int16\", \"id\": \"qualityWidth\" }, { \"type\": \"int16\", \"id\": \"qualityHeight\" } ] }, { \"type\": \"string\", \"value\": \"stop\", \"id\": \"end_string\" } ] }",
                "LogicGraph": "{\"IOMap\": {\"OUT1\": \"RFT\",\"OUT2\": \"AQUFIN\"},\"blocks\": {\"B00001\": {\"pos\": {\"x\": 200,\"y\": 200},\"properties\": {},\"type\": \"PIN_EVENT_IMAGE_ACQUISITION_FINISHED\"},\"B00002\": {\"pos\": {\"x\": 200,\"y\": 75},\"properties\": {},\"type\": \"PIN_EVENT_READY_FOR_TRIGGER\"},\"B00003\": {\"pos\": {\"x\": 600,\"y\": 75},\"properties\": {\"pulse_duration\": 0},\"type\": \"DIGITAL_OUT1\"},\"B00005\": {\"pos\": {\"x\": 600,\"y\": 200},\"properties\": {\"pulse_duration\": 0},\"type\": \"DIGITAL_OUT2\"}},\"connectors\": {\"C00000\": {\"dst\": \"B00003\",\"dstEP\": 0,\"src\": \"B00002\",\"srcEP\": 0},\"C00001\": {\"dst\": \"B00005\",\"dstEP\": 0,\"src\": \"B00001\",\"srcEP\": 0}}}",
                "Type": "Camera",
                "Index": "1",
                "Id": "476707713",
                "Imager": {
                    "AutoExposureReferencePointX": "88",
                    "AutoExposureReferencePointY": "66",
                    "AutoExposureReferenceType": "0",
                    "AutoExposureMaxExposureTime": "10000",
                    "AutoExposureReferenceROI": "{\"ROIs\":[{\"id\":0,\"group\":0,\"type\":\"Rect\",\"width\":130,\"height\":100,\"angle\":0,\"center_x\":88,\"center_y\":66}]}",
                    "Channel": "0",
                    "ClippingBottom": "263",
                    "ClippingLeft": "0",
                    "ClippingRight": "351",
                    "ClippingTop": "0",
                    "ContinuousAutoExposure": "false",
                    "EnableAmplitudeCorrection": "true",
                    "EnableFastFrequency": "false",
                    "EnableFilterAmplitudeImage": "false",
                    "EnableFilterDistanceImage": "true",
                    "EnableRectificationAmplitudeImage": "false",
                    "EnableRectificationDistanceImage": "false",
                    "UseSimpleBinning": "false",
                    "ExposureTime": "10000",
                    "ExposureTimeList": "2500;10000",
                    "ExposureTimeRatio": "4",
                    "FrameRate": "5",
                    "MinimumAmplitude": "2",
                    "Resolution": "1",
                    "ClippingCuboid": "{\"XMin\": -3.402823e+38, \"XMax\": 3.402823e+38, \"YMin\": -3.402823e+38, \"YMax\": 3.402823e+38, \"ZMin\": -3.402823e+38, \"ZMax\": 3.402823e+38}",
                    "SpatialFilterType": "1",
                    "SymmetryThreshold": "0",
                    "TemporalFilterType": "0",
                    "ThreeFreqMax2FLineDistPercentage": "80",
                    "ThreeFreqMax3FLineDistPercentage": "80",
                    "TwoFreqMaxLineDistPercentage": "80",
                    "Type": "upto30m_moderate",
                    "MaxAllowedLEDFrameRate": "4.9000000000000004",
                    "SpatialFilter": {
                        "Type": "1",
                        "TypeStr_": "Median Filter",
                        "MaskSize": "1",
                        "MaskSizeStr_": "5x5"
                    },
                    "TemporalFilter": {
                        "Type": "0",
                        "TypeStr_": "Off"
                    }
                }
            }
        ]
    }
}
robinbansal08 commented 3 years ago

Any feedbacks on this issue please.

graugans commented 3 years ago

As discussed on the phone, we try to reproduce this issue on our side.

robinbansal08 commented 3 years ago

My algorithms are running continuously since one week over 20 sensors to check the memory usage as per our discussion to check any memory leakage. Currently, every thing is running normally, memory usage is constant and frame grabbing time is still within 600ms. I will provide you the feedback as soon I observe any abnormalities again.

robinbansal08 commented 3 years ago

I am running the same algorithm in many O3D303 sensors since few days and till now I have noticed increase in frame grabbing time only in one sensor out of 18 sensors running the same algorithm over several days.

To further check this issue, I have started more sensors with same algorithm running over several days to check if such behavior is noticed in more sensors also.

graugans commented 3 years ago

Thanks for the update @robinbansal08 , could you please be so kind and upload the output of the following commands to this URL I'll send you the password by mail.

The following messages can be ignored.

loadConfig: Redis connection problem for connecting via /tmp/redis-cache.sock
loadConfig: Redis connection problem for connecting via /tmp/redis-cache.sock
robinbansal08 commented 3 years ago

@graugans I have uploaded the outputs of the first two points but I guess you meant different command in the 3rd point (you have mentioned the command in 3rd point same as 1st point by mistake).

graugans commented 3 years ago

Sorry, I have updated the previous comment

robinbansal08 commented 3 years ago

I have uploaded the output of all three commands.

graugans commented 3 years ago

Hey @robinbansal08,

we started a test on our side with the dump you have provided:

{
    "o3d3xx": {
        "libo3d3xx": "707",
        "Date": "Mon Aug 31 10:15:10 2020",
        "Device": {
            "Name": "New sensor",
            "Description": "",
            "ActiveApplication": "1",
            "PcicTcpPort": "50010",
            "PcicProtocolVersion": "3",
            "IOLogicType": "1",
            "IODebouncing": "true",
            "IOExternApplicationSwitch": "0",
            "SessionTimeout": "30",
            "ServiceReportPassedBuffer": "15",
            "ServiceReportFailedBuffer": "15",
            "ExtrinsicCalibTransX": "0",
            "ExtrinsicCalibTransY": "0",
            "ExtrinsicCalibTransZ": "0",
            "ExtrinsicCalibRotX": "0",
            "ExtrinsicCalibRotY": "0",
            "ExtrinsicCalibRotZ": "0",
            "EvaluationFinishedMinHoldTime": "10",
            "SaveRestoreStatsOnApplSwitch": "true",
            "IPAddressConfig": "0",
            "PasswordActivated": "false",
            "OperatingMode": "1",
            "DeviceType": "1:2",
            "ArticleNumber": "O3D303",
            "ArticleStatus": "AD",
            "UpTime": "713.91333333333296",
            "ImageTimestampReference": "1574208180",
            "TemperatureFront1": "3276.6999999999998",
            "TemperatureFront2": "3276.6999999999998",
            "TemperatureIMX6": "28.906000137329102",
            "TemperatureIllu": "35.600000000000001",
            "PNIODeviceName": "",
            "EthernetFieldBus": "0",
            "EthernetFieldBusEndianness": "0",
            "EnableAcquisitionFinishedPCIC": "false"
        },
        "Apps": [
            {
                "Name": "Box Detection Application",
                "Description": "",
                "TriggerMode": "2",
                "PcicTcpResultSchema": "{ \"layouter\": \"flexible\", \"format\": { \"dataencoding\": \"ascii\" }, \"elements\": [ { \"type\": \"string\", \"value\": \"star\", \"id\": \"start_string\" }, { \"type\": \"blob\", \"id\": \"normalized_amplitude_image\" }, { \"type\": \"blob\", \"id\": \"distance_image\" }, { \"type\": \"blob\", \"id\": \"x_image\" }, { \"type\": \"blob\", \"id\": \"y_image\" }, { \"type\": \"blob\", \"id\": \"z_image\" }, { \"type\": \"blob\", \"id\": \"confidence_image\" }, { \"type\": \"blob\", \"id\": \"diagnostic_data\" }, { \"type\": \"string\", \"value\": \"stop\", \"id\": \"end_string\" } ] }",
                "PcicEipResultSchema": "{ \"layouter\": \"flexible\", \"format\": { \"dataencoding\": \"binary\", \"order\": \"big\" }, \"elements\" : [ { \"type\": \"string\", \"value\": \"star\", \"id\": \"start_string\" }, { \"type\": \"records\", \"id\": \"models\", \"elements\": [ { \"type\": \"int16\", \"id\": \"boxFound\" }, { \"type\": \"int16\", \"id\": \"width\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"height\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"length\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"xMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"yMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"zMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"yawAngle\" }, { \"type\": \"int16\", \"id\": \"qualityLength\" }, { \"type\": \"int16\", \"id\": \"qualityWidth\" }, { \"type\": \"int16\", \"id\": \"qualityHeight\" } ] }, { \"type\": \"string\", \"value\": \"stop\", \"id\": \"end_string\" } ] }",
                "PcicPnioResultSchema": "{\"layouter\" : \"flexible\", \"format\": { \"dataencoding\": \"binary\", \"order\": \"big\" }, \"elements\" : [ { \"type\": \"string\", \"value\": \"star\", \"id\": \"start_string\" }, { \"type\": \"records\", \"id\": \"models\", \"elements\": [ { \"type\": \"int16\", \"id\": \"boxFound\" }, { \"type\": \"int16\", \"id\": \"width\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"height\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"length\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"xMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"yMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"zMidTop\", \"format\": { \"scale\": 1000 } }, { \"type\": \"int16\", \"id\": \"yawAngle\" }, { \"type\": \"int16\", \"id\": \"qualityLength\" }, { \"type\": \"int16\", \"id\": \"qualityWidth\" }, { \"type\": \"int16\", \"id\": \"qualityHeight\" } ] }, { \"type\": \"string\", \"value\": \"stop\", \"id\": \"end_string\" } ] }",
                "LogicGraph": "{\"IOMap\": {\"OUT1\": \"RFT\",\"OUT2\": \"AQUFIN\"},\"blocks\": {\"B00001\": {\"pos\": {\"x\": 200,\"y\": 200},\"properties\": {},\"type\": \"PIN_EVENT_IMAGE_ACQUISITION_FINISHED\"},\"B00002\": {\"pos\": {\"x\": 200,\"y\": 75},\"properties\": {},\"type\": \"PIN_EVENT_READY_FOR_TRIGGER\"},\"B00003\": {\"pos\": {\"x\": 600,\"y\": 75},\"properties\": {\"pulse_duration\": 0},\"type\": \"DIGITAL_OUT1\"},\"B00005\": {\"pos\": {\"x\": 600,\"y\": 200},\"properties\": {\"pulse_duration\": 0},\"type\": \"DIGITAL_OUT2\"}},\"connectors\": {\"C00000\": {\"dst\": \"B00003\",\"dstEP\": 0,\"src\": \"B00002\",\"srcEP\": 0},\"C00001\": {\"dst\": \"B00005\",\"dstEP\": 0,\"src\": \"B00001\",\"srcEP\": 0}}}",
                "Type": "Camera",
                "Index": "1",
                "Id": "476707713",
                "Imager": {
                    "AutoExposureReferencePointX": "88",
                    "AutoExposureReferencePointY": "66",
                    "AutoExposureReferenceType": "0",
                    "AutoExposureMaxExposureTime": "10000",
                    "AutoExposureReferenceROI": "{\"ROIs\":[{\"id\":0,\"group\":0,\"type\":\"Rect\",\"width\":130,\"height\":100,\"angle\":0,\"center_x\":88,\"center_y\":66}]}",
                    "Channel": "0",
                    "ClippingBottom": "263",
                    "ClippingLeft": "0",
                    "ClippingRight": "351",
                    "ClippingTop": "0",
                    "ContinuousAutoExposure": "false",
                    "EnableAmplitudeCorrection": "true",
                    "EnableFastFrequency": "false",
                    "EnableFilterAmplitudeImage": "false",
                    "EnableFilterDistanceImage": "true",
                    "EnableRectificationAmplitudeImage": "false",
                    "EnableRectificationDistanceImage": "false",
                    "UseSimpleBinning": "false",
                    "ExposureTime": "10000",
                    "ExposureTimeList": "2500;10000",
                    "ExposureTimeRatio": "4",
                    "FrameRate": "5",
                    "MinimumAmplitude": "2",
                    "Resolution": "1",
                    "ClippingCuboid": "{\"XMin\": -3.402823e+38, \"XMax\": 3.402823e+38, \"YMin\": -3.402823e+38, \"YMax\": 3.402823e+38, \"ZMin\": -3.402823e+38, \"ZMax\": 3.402823e+38}",
                    "SpatialFilterType": "1",
                    "SymmetryThreshold": "0",
                    "TemporalFilterType": "0",
                    "ThreeFreqMax2FLineDistPercentage": "80",
                    "ThreeFreqMax3FLineDistPercentage": "80",
                    "TwoFreqMaxLineDistPercentage": "80",
                    "Type": "upto30m_moderate",
                    "MaxAllowedLEDFrameRate": "4.9000000000000004",
                    "SpatialFilter": {
                        "Type": "1",
                        "TypeStr_": "Median Filter",
                        "MaskSize": "1",
                        "MaskSizeStr_": "5x5"
                    },
                    "TemporalFilter": {
                        "Type": "0",
                        "TypeStr_": "Off"
                    }
                }
            }
        ]
    }
}

and a loop which looks like this:

    // Measure trigger duration    
    auto start = std::chrono::high_resolution_clock::now(); 
    frameGrabber->SWTrigger();     
    frameGrabber->WaitForFrame(imageBuffer.get(), 10000);     auto end = std::chrono::high_resolution_clock::now();     auto 
    durationUs = (std::chrono::duration_cast<std::chrono::microseconds>(end - start)).count();

What we do see:

9509 378.617 1.5172
9508 378.637 1.5399
9508 378.621 1.50632
9510 378.554 1.51092
9509 378.61 1.50967

We have a std::vector which is filled for an hour and the result above is organized in the following way:

  1. column samples colected in an hour
  2. the average time
  3. the standard deviation over the sample time

Our numbers are significantly lower than yours. Do you also measure your algorithm runtime?

robinbansal08 commented 3 years ago
    auto start = high_resolution_clock::now();

    o3d3xx::Logging::Init();
    cout<<"Getting image over cam directly "<<endl;
    o3d3xx::Camera::Ptr cam = std::make_shared<o3d3xx::Camera>();
    o3d3xx::ImageBuffer::Ptr img = std::make_shared<o3d3xx::ImageBuffer>();
    o3d3xx::FrameGrabber::Ptr fg = std::make_shared<o3d3xx::FrameGrabber>(cam, o3d3xx::IMG_AMP|o3d3xx::IMG_RDIS|o3d3xx::IMG_CART);
    fg->SWTrigger();
    if (! fg->WaitForFrame(img.get(), 2000))
    {
        cout << RED<<"Timeout waiting for camera!" << RESET <<std::endl;
        exit (-1);
    }
    pcl::copyPointCloud(*(img->Cloud()), *cloud_xyzi);
    image = img->DepthImage();

    auto end = high_resolution_clock::now();
    auto duration = duration_cast<milliseconds>(end - start);

Possibly 100ms might be required for variable initialisation, point cloud and image copy process. I will check this and provide you the feedback.

robinbansal08 commented 3 years ago

I have noticed something which I am not sure if this is normal. There is much difference in the memory usage in IDLE state of the camera. Here is the memory usage for 2 cameras in idle state:

             total         used         free       shared      buffers
Mem:        511696       390536       121160            0            0
-/+ buffers:             390536       121160
Swap:            0            0            0
             total         used         free       shared      buffers
Mem:        511696       422500        89196            0            0
-/+ buffers:             422500        89196
Swap:            0            0            0

Is this expected behaviour ?

graugans commented 3 years ago

In your example:

auto start = high_resolution_clock::now();

    o3d3xx::Logging::Init();
    cout<<"Getting image over cam directly "<<endl;
    o3d3xx::Camera::Ptr cam = std::make_shared<o3d3xx::Camera>();
    o3d3xx::ImageBuffer::Ptr img = std::make_shared<o3d3xx::ImageBuffer>();
    o3d3xx::FrameGrabber::Ptr fg = std::make_shared<o3d3xx::FrameGrabber>(cam, o3d3xx::IMG_AMP|o3d3xx::IMG_RDIS|o3d3xx::IMG_CART);
    fg->SWTrigger();
    if (! fg->WaitForFrame(img.get(), 2000))
    {
        cout << RED<<"Timeout waiting for camera!" << RESET <<std::endl;
        exit (-1);
    }
    pcl::copyPointCloud(*(img->Cloud()), *cloud_xyzi);
    image = img->DepthImage();

    auto end = high_resolution_clock::now();
    auto duration = duration_cast<milliseconds>(end - start);

You do measure the time which is used for object instantiation:

  auto start = high_resolution_clock::now();
   o3d3xx::Logging::Init();
    cout<<"Getting image over cam directly "<<endl;
    o3d3xx::Camera::Ptr cam = std::make_shared<o3d3xx::Camera>();
    o3d3xx::ImageBuffer::Ptr img = std::make_shared<o3d3xx::ImageBuffer>();
    o3d3xx::FrameGrabber::Ptr fg = std::make_shared<o3d3xx::FrameGrabber>(cam, 3d3xx::IMG_AMP|o3d3xx::IMG_RDIS|o3d3xx::IMG_CART);

My expectation is more a code like this:

while(true)
{
    auto start = high_resolution_clock::now();
    fg->SWTrigger();
    if (! fg->WaitForFrame(img.get(), 2000))
    {
        cout << RED<<"Timeout waiting for camera!" << RESET <<std::endl;
        exit (-1);
    }
    auto end = high_resolution_clock::now();
    // do something
    auto duration = duration_cast<milliseconds>(end - start);
}

The available memory in idle mode can differ, which is caused how Linux is organizing memory.

robinbansal08 commented 3 years ago

This issue is resolved now. I did the object instantiation only once as global objects instead of new object instantiation for each frame-grabbing event. After this I was able to achieve 380-400ms of frame grabbing time and also it is pretty constant, not increasing like before after many iterations.

Thanks a lot for your support.