Open kvmanohar22 opened 4 years ago
You can try increasing the "request" parameter and see if it helps.
On Tue, Mar 10, 2020, 02:53 Kv Manohar notifications@github.com wrote:
I am using this package in conjunction with bluefox2 https://github.com/KumarRobotics/bluefox2 package for matrixvision bluefox MLC200wC camera with resolution 752x480. Settings are adjusted so as to acquire images at a rate ~80 FPS. Turns out the method CameraRosBase::PublishCamera https://github.com/KumarRobotics/camera_base/blob/master/include/camera_base/camera_ros_base.h#L78 takes too long to process images and the max. FPS that I can get is ~35 FPS.
Also, my launch file is following.
test_triggering.launch:
single_node.launch:
So, my question is, are any methods tried that can overcome this bottleneck and acquire images at high frame rate (atleast 70)?
— You are receiving this because you are subscribed to this thread. Reply to this email directly, view it on GitHub https://github.com/KumarRobotics/camera_base/issues/5?email_source=notifications&email_token=AAAWTGRHXXQKA2AL7QFWW3LRGYE2TA5CNFSM4LE27J52YY3PNVWWK3TUL52HS4DFUVEXG43VMWVGG33NNVSW45C7NFSM4IT2SP7A, or unsubscribe https://github.com/notifications/unsubscribe-auth/AAAWTGRNLK2G3CLZ2FVGVKTRGYE2TANCNFSM4LE27J5Q .
Thanks for such a fast reply!
The parameter seems to have no effect. Just to know, were there any tests that were done to determine max. frame rate that has been achieved with this package based on bluefox2?
max frame rate I had was 85, this is a long time ago, i need to take a look.
make sure you don't have auto exposure on, set it to fixed say 5ms and see what's the max framerate
I have disabled all the auto features and have set them manually (see the launch file above).
Currently the trigger interval is 14ms and from this the camera is expected to deliver at ~71 FPS. I have made sure exposure is less than 14ms to account for the desired frame rate. And 71 FPS is achieved for fixed exposure between 1ms-3ms but anything more than 3ms of expsure time, there is a bottleneck in CameraRosBase::PublishCamera
. Additionally I have set the pixel clock at 40MHz which is the max. available on the camera to ensure minimal time spent on readout.
From my calculations, for 14ms trigger interval, 71 FPS should have been achieved for exposure upto atleast 8ms. But this doesn't seem to be the case.
So, in conclusion although the camera is publishing at 71FPS, CameraRosBase::PublishCamera
is holding up.
PulishCamera isn't doing anything other than calling the derived Grab method, which calls https://github.com/KumarRobotics/bluefox2/blob/b792108837e37337ae98ae09b8422b6efafe6a61/src/bluefox2.cpp#L73
the only thing I can think of that is holding this back is the timeout_ms which is default to 200ms, you can try to decrease that to 50 maybe and see what happens. https://github.com/KumarRobotics/bluefox2/blob/b792108837e37337ae98ae09b8422b6efafe6a61/include/bluefox2/bluefox2.h#L57
I have achieved 90fps before, but it was very long ago and I don't have a camera with me right now to try it.
Check the formula for computing the max frame rate based on your settings here: https://github.com/KumarRobotics/bluefox2/blob/b792108837e37337ae98ae09b8422b6efafe6a61/src/bluefox2_setting.cpp#L60 It looks like about 3ms exposure time is the max you can have for getting
70fps.
On Tue, Mar 10, 2020, 07:31 Chao Qu notifications@github.com wrote:
PulishCamera isn't doing anything other than calling the derived Grab method, which calls
the only thing I can think of that is holding this back is the timeout_ms which is default to 200ms, you can try to decrease that to 50 maybe and see what happens.
I have achieved 90fps before, but it was very long ago and I don't have a camera with me right now to try it.
— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/KumarRobotics/camera_base/issues/5?email_source=notifications&email_token=AAAWTGQWPTLH2RR2OCQG643RGZFMXA5CNFSM4LE27J52YY3PNVWWK3TUL52HS4DFVREXG43VMVBW63LNMVXHJKTDN5WW2ZLOORPWSZGOEOLUXYI#issuecomment-597117921, or unsubscribe https://github.com/notifications/unsubscribe-auth/AAAWTGRGYFUGCRF7U436LRDRGZFMXANCNFSM4LE27J5Q .
Yes, based on that formula 3ms is the max. exposure time that results in ~71FPS. But the thing is, when I change the exposure time to more than 3ms (say 5ms or higher), FPS drops significantly straight to ~35.
I just played around with timeout_ms
parameter, and it doesn't seem to have any effect. i.e, by changing exposure to 6ms and with timeout of 200ms or 1ms, there is no difference in FPS observable.
Also, in addition to timeout_ms
parameter, are there any other parameters that could play a role
Maybe you could add some timing stuff and measure it yourself? I don't have a camera right now otherwise I'd do it.
Since you are doing an external trigger, you won't get a frame rate which is something in between ~70 and 70/2. Once the camera misses a trigger, since it's still reading out the current frame, it would wait for the next trigger to start a new capture so you get half the frame rate.
@versatran01 Yes, I did do that analysis. Counter to my initial assumption, Grab(...)
takes nearly constant time of around 0.2 ms to 0.3 ms. But often, CameraRosBase::PublishCamera
takes up 4-5ms (although exposure time is only 3ms! and with timeout_ms
of 1ms). I am investigating what is causing this issue.
@kartikmohta The request
parameter is non-zero, so I would guess the frames are still stored in the buffer right? in which case, there should not be any drop in the frames?
In the hardware trigger mode, the requests are only to get the data from the camera once the frame is captured, it doesn't matter how many requests you have in the queue if the frame has not been captured on the camera. If the camera misses one trigger due to being busy, it has to wait for the next trigger to start the image capture, so with hardware triggering your frame rates can only be trigger_freq/n
where n is an positive integer. If you set it to on-demand mode, you should be able to get the intermediate frame rates, but I assume you need hardware triggering for some other purpose.
In the hardware trigger mode, the requests are only to get the data from the camera once the frame is captured...
Yes, I get this now.
Yes, hardware triggering is of prime importance to synchronize with IMU data for SLAM. Anyway around to get past this problem without lossing much of the frames that you have had experience with?
If you can handle the lower exposure time, that would be easiest. Otherwise just reduce the trigger frequency to something which works with the exposure time you need for the environment you're operating in. 70 fps seems to be a bit too high for a typical SLAM system, something around 50 might be sufficient.
On bright day low exposure (<2ms) seems to be more than sufficient. Will play around with the trigger frequency as well.
Thanks a lot for the helpful pointers!
I am using this package in conjunction with bluefox2 package for matrixvision bluefox MLC200wC camera with resolution
752x480
. Settings are adjusted so as to acquire images at a rate ~80 FPS. Turns out the method CameraRosBase::PublishCamera takes too long to process images and the max. FPS that I can get is ~35 FPS.Also, my launch file is following.
test_triggering.launch
:single_node.launch
:So, my question is, are any methods tried that can overcome this bottleneck and acquire images at high frame rate (atleast 70)?