Skip to content

Add parameter to skip frames#1

Open
cosama wants to merge 6 commits intoros-o:obese-develfrom
cosama:adds_stride
Open

Add parameter to skip frames#1
cosama wants to merge 6 commits intoros-o:obese-develfrom
cosama:adds_stride

Conversation

@cosama
Copy link

@cosama cosama commented May 28, 2025

We are having a bunch of cameras that we typically run at lower frame rates (5-10Hz). After looking into this for quite some time, I realized that those camera's do not support these frame rates and that the timestamp is often off considerably, so the kernel must write weird information in the data buffer. I don't know exactly what is happening, but the effect disappears when running at a supported frame rate (30Hz in our case). So I added an optional parameter (stride) to the driver that can be used to only read every Nth frame. It reduces the load of the driver considerably (100%CPU at 30HZ vs 40%CPU at 10Hz). Would be cool if it can be merged, might be useful to others too.

I tested the driver and it works as expected.

@cosama
Copy link
Author

cosama commented May 28, 2025

Here some more output running the driver at 30Hz and a stride of 3:

usb_camera     | [WARN] [1748457339.410597293]: NOTE: the parameters generated for V4L intrinsic camera controls will be placed under namespace 'intrinsic_controls'
usb_camera     | [INFO] [1748457339.331578693]: Initializing ROS V4L USB camera 'camera' (/dev/video0) at 1280x720 via mmap (uyvy) at 30 FPS and 3 framestride
usb_camera     | [INFO] [1748457339.335379644]: camera calibration URL: file:///workspace/config/camera_calibration/ost.yaml
usb_camera     | [INFO] [1748457339.335940934]: Advertising std_srvs::Empty start service under name 'start_capture'
usb_camera     | [INFO] [1748457339.336392678]: Advertising std_srvs::Empty suspension service under name 'stop_capture'
usb_camera     | [INFO] [1748457339.336725873]: Advertising std_srvs::Trigger supported formats information service under name 'supported_formats'
usb_camera     | [INFO] [1748457339.337139135]: Advertising std_srvs::Trigger supported V4L controls information service under name 'supported_controls'
usb_camera     | Opening streaming device /dev/video0
usb_camera     | Video4Linux: IOCTL is not supported
usb_camera     | Video4linux: Querying V4L2 driver for available controls (register base 0x980900, 0..99)
usb_camera     | Sorting control names:
usb_camera     | 	exposure_auto
usb_camera     | 	white_balance_temperature_auto
usb_camera     | 	brightness
usb_camera     | 	contrast
usb_camera     | 	saturation
usb_camera     | 	gamma
usb_camera     | 	gain
usb_camera     | 	power_line_frequency
usb_camera     | 	white_balance_temperature
usb_camera     | 	sharpness
usb_camera     | 	exposure_absolute
usb_camera     | [INFO] [1748457339.410730837]: Use 'intrinsic_controls/ignore' list to enumerate the controls provoking errors or the ones you just want to keep untouched
usb_camera     | [INFO] [1748457339.410765712]: Attempting to generate ROS parameter for V4L2 control 'exposure_auto':
usb_camera     | 	Exposure, Auto, min = 0, max = 3, step = 1, flags = 0x0 [ 0: Auto Mode 1: Manual Mode ] [0]
usb_camera     | [INFO] [1748457339.411878690]: Parameter intrinsic_controls/exposure_auto exposed with value 0
usb_camera     | [INFO] [1748457339.411930374]: Attempting to generate ROS parameter for V4L2 control 'white_balance_temperature_auto':
usb_camera     | 	White Balance Temperature, Auto, min = 0, max = 1, step = 1, flags = 0x0 [1] (bool 1/0)
usb_camera     | [INFO] [1748457339.412993571]: Parameter intrinsic_controls/white_balance_temperature_auto exposed with value 1
usb_camera     | [INFO] [1748457339.413077543]: Attempting to generate ROS parameter for V4L2 control 'brightness':
usb_camera     | 	Brightness, min = -15, max = 15, step = 1, flags = 0x0 [0]
usb_camera     | [INFO] [1748457339.413850186]: Parameter intrinsic_controls/brightness exposed with value 0
usb_camera     | [INFO] [1748457339.413934538]: Attempting to generate ROS parameter for V4L2 control 'contrast':
usb_camera     | 	Contrast, min = 0, max = 30, step = 1, flags = 0x0 [10]
usb_camera     | [INFO] [1748457339.414654362]: Parameter intrinsic_controls/contrast exposed with value 10
usb_camera     | [INFO] [1748457339.414737896]: Attempting to generate ROS parameter for V4L2 control 'saturation':
usb_camera     | 	Saturation, min = 0, max = 60, step = 1, flags = 0x0 [16]
usb_camera     | [INFO] [1748457339.415433016]: Parameter intrinsic_controls/saturation exposed with value 16
usb_camera     | [INFO] [1748457339.415515211]: Attempting to generate ROS parameter for V4L2 control 'gamma':
usb_camera     | 	Gamma, min = 40, max = 500, step = 1, flags = 0x0 [220]
usb_camera     | [INFO] [1748457339.416182891]: Parameter intrinsic_controls/gamma exposed with value 220
usb_camera     | [INFO] [1748457339.416259994]: Attempting to generate ROS parameter for V4L2 control 'gain':
usb_camera     | 	Gain, min = 1, max = 100, step = 1, flags = 0x0 [1]
usb_camera     | [INFO] [1748457339.416924698]: Parameter intrinsic_controls/gain exposed with value 1
usb_camera     | [INFO] [1748457339.417001491]: Attempting to generate ROS parameter for V4L2 control 'power_line_frequency':
usb_camera     | 	Power Line Frequency, min = 0, max = 2, step = 1, flags = 0x0 [ 0: Disabled 1: 50 Hz 2: 60 Hz ] [0]
usb_camera     | [INFO] [1748457339.417628956]: Parameter intrinsic_controls/power_line_frequency exposed with value 0
usb_camera     | [INFO] [1748457339.417706149]: Attempting to generate ROS parameter for V4L2 control 'white_balance_temperature':
usb_camera     | 	White Balance Temperature, min = 1000, max = 10000, step = 50, flags = 0x10 [4500]
usb_camera     | [INFO] [1748457339.418275380]: Parameter intrinsic_controls/white_balance_temperature exposed with value 4500
usb_camera     | [INFO] [1748457339.418326150]: Attempting to generate ROS parameter for V4L2 control 'sharpness':
usb_camera     | 	Sharpness, min = 0, max = 127, step = 1, flags = 0x0 [16]

and checking the frame rate:

# rostopic list
/camera/camera_info
/camera/image_raw
/rosout
/rosout_agg
root@slamp:/workspace# rostopic hz /camera/image_raw
subscribed to [/camera/image_raw]
average rate: 9.937
	min: 0.098s max: 0.106s std dev: 0.00234s window: 10
average rate: 9.970
	min: 0.095s max: 0.106s std dev: 0.00239s window: 20
average rate: 9.984
	min: 0.095s max: 0.106s std dev: 0.00197s window: 30
average rate: 9.985
	min: 0.087s max: 0.114s std dev: 0.00354s window: 40
average rate: 9.991
	min: 0.087s max: 0.114s std dev: 0.00320s window: 50
average rate: 9.993
	min: 0.087s max: 0.114s std dev: 0.00303s window: 60
average rate: 9.994
	min: 0.087s max: 0.114s std dev: 0.00282s window: 70
average rate: 9.994
	min: 0.087s max: 0.114s std dev: 0.00326s window: 80
average rate: 9.995
	min: 0.087s max: 0.114s std dev: 0.00308s window: 90
average rate: 9.995
	min: 0.087s max: 0.114s std dev: 0.00301s window: 100
average rate: 9.996

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant