ros-drivers/usb_cam

Segmentation fault on Humble with Logithech C930e

zweistein opened this issue ยท 9 comments

Hi, I want to use the Logithech C930e at high resolution and fps, but the launch script results in a Segmentation fault. It works with default camera info and params (640x480 30fsp)m, though it supports high-resolution images with Motion-JPEG but compressed.
What can be the problem?

From $ v4l2-ctl -d /dev/video0 --list-formats-ext:

ioctl: VIDIOC_ENUM_FMT
	Type: Video Capture

	[0]: 'YUYV' (YUYV 4:2:2)
		Size: Discrete 640x480
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.040s (25.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.040s (25.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 1920x1080
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 1600x896
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 1280x720
			Interval: Discrete 0.100s (10.000 fps)
		Size: Discrete 1024x576
			Interval: Discrete 0.100s (10.000 fps)
		Size: Discrete 960x720
			Interval: Discrete 0.100s (10.000 fps)
		Size: Discrete 864x480
			Interval: Discrete 0.100s (10.000 fps)
		Size: Discrete 800x600
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 800x448
			Interval: Discrete 0.100s (10.000 fps)
		Size: Discrete 640x360
			Interval: Discrete 0.033s (30.000 fps)
		Size: Discrete 432x240
			Interval: Discrete 0.033s (30.000 fps)
		Size: Discrete 352x288
			Interval: Discrete 0.033s (30.000 fps)
		Size: Discrete 320x240
			Interval: Discrete 0.040s (25.000 fps)
		Size: Discrete 320x180
			Interval: Discrete 0.033s (30.000 fps)
		Size: Discrete 176x144
			Interval: Discrete 0.033s (30.000 fps)
		Size: Discrete 160x120
			Interval: Discrete 0.033s (30.000 fps)
		Size: Discrete 160x90
			Interval: Discrete 0.033s (30.000 fps)
		Size: Discrete 640x480
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.040s (25.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.040s (25.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
	[1]: 'MJPG' (Motion-JPEG, compressed)
		Size: Discrete 640x480
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 2048x1536
			Interval: Discrete 0.067s (15.000 fps)
		Size: Discrete 1920x1080
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 1600x896
			Interval: Discrete 0.033s (30.000 fps)
		Size: Discrete 1280x720
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 1024x576
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 960x720
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 864x480
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 800x600
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 800x448
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 640x360
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 432x240
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 352x288
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 320x240
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 320x180
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 176x144
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 160x120
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 160x90
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
		Size: Discrete 640x480
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)
			Interval: Discrete 0.033s (30.000 fps)
			Interval: Discrete 0.050s (20.000 fps)
			Interval: Discrete 0.067s (15.000 fps)
			Interval: Discrete 0.100s (10.000 fps)
			Interval: Discrete 0.200s (5.000 fps)

In params.yaml:

/**:
    ros__parameters:
      video_device: "/dev/video0"
      framerate: 30.0
      io_method: 'mmap' # "mmap"
      frame_id: "camera"
      pixel_format: "mjpeg2rgb"  # see usb_cam/supported_formats for list of supported formats
      image_width: 1920 # SF: 1600  # works 640 
      image_height: 1080 # SF: 896 # works 480 
      camera_name: "test_camera"
      camera_info_url: "package://data_recording_utils/config/camera_info.yaml"
      brightness: -1
      contrast: -1
      saturation: -1
      sharpness: -1
      gain: -1
      auto_white_balance: true
      white_balance: 4000
      autoexposure: true
      exposure: 100
      autofocus: false
      focus: -1

In camer_info.yaml:

image_width: 1600
image_height: 896
camera_name: c930e
camera_matrix:
  rows: 3
  cols: 3
  data: [438.783367, 0.000000, 305.593336, 0.000000, 437.302876, 243.738352, 0.000000, 0.000000, 1.000000]
distortion_model: plumb_bob
distortion_coefficients:
  rows: 1
  cols: 5
  data: [-0.361976, 0.110510, 0.001014, 0.000505, 0.000000]
rectification_matrix:
  rows: 3
  cols: 3
  data: [0.999978, 0.002789, -0.006046, -0.002816, 0.999986, -0.004401, 0.006034, 0.004417, 0.999972]
projection_matrix:
  rows: 3
  cols: 4
  data: [393.653800, 0.000000, 322.797939, 0.000000, 0.000000, 393.653800, 241.090902, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]

Launch output

$ ros2 run usb_cam usb_cam_node_exe --ros-args --params-file ./config/params.yaml  
[INFO] [1698745505.161535647] [usb_cam]: camera_name value: test_camera
[WARN] [1698745505.161617477] [usb_cam]: framerate: 30.000000
[INFO] [1698745505.164443214] [usb_cam]: camera calibration URL: package://data_recording_utils/config/camera_info.yaml
[INFO] [1698745505.164991210] [usb_cam]: Starting 'test_camera' (/dev/video0) at 1600x896 via mmap (mjpeg2rgb) at 30 FPS
[INFO] [1698745511.230479640] [usb_cam]: This devices supproted formats:
[INFO] [1698745511.230814299] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (30 Hz)
[INFO] [1698745511.230828417] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (25 Hz)
[INFO] [1698745511.230837282] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (20 Hz)
[INFO] [1698745511.230845153] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (15 Hz)
[INFO] [1698745511.230852816] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (10 Hz)
[INFO] [1698745511.230876613] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (5 Hz)
[INFO] [1698745511.230898626] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (30 Hz)
[INFO] [1698745511.230919394] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (25 Hz)
[INFO] [1698745511.230936967] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (20 Hz)
[INFO] [1698745511.230945885] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (15 Hz)
[INFO] [1698745511.230954094] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (10 Hz)
[INFO] [1698745511.230962413] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (5 Hz)
[INFO] [1698745511.230970984] [usb_cam]: 	YUYV 4:2:2: 1920 x 1080 (5 Hz)
[INFO] [1698745511.230979484] [usb_cam]: 	YUYV 4:2:2: 1600 x 896 (5 Hz)
[INFO] [1698745511.230987862] [usb_cam]: 	YUYV 4:2:2: 1280 x 720 (10 Hz)
[INFO] [1698745511.230996130] [usb_cam]: 	YUYV 4:2:2: 1024 x 576 (10 Hz)
[INFO] [1698745511.231004312] [usb_cam]: 	YUYV 4:2:2: 960 x 720 (10 Hz)
[INFO] [1698745511.231012767] [usb_cam]: 	YUYV 4:2:2: 864 x 480 (10 Hz)
[INFO] [1698745511.231021019] [usb_cam]: 	YUYV 4:2:2: 800 x 600 (20 Hz)
[INFO] [1698745511.231029330] [usb_cam]: 	YUYV 4:2:2: 800 x 600 (15 Hz)
[INFO] [1698745511.231037909] [usb_cam]: 	YUYV 4:2:2: 800 x 600 (10 Hz)
[INFO] [1698745511.231046285] [usb_cam]: 	YUYV 4:2:2: 800 x 600 (5 Hz)
[INFO] [1698745511.231055014] [usb_cam]: 	YUYV 4:2:2: 800 x 448 (10 Hz)
[INFO] [1698745511.231063363] [usb_cam]: 	YUYV 4:2:2: 640 x 360 (30 Hz)
[INFO] [1698745511.231071367] [usb_cam]: 	YUYV 4:2:2: 432 x 240 (30 Hz)
[INFO] [1698745511.231079489] [usb_cam]: 	YUYV 4:2:2: 352 x 288 (30 Hz)
[INFO] [1698745511.231087651] [usb_cam]: 	YUYV 4:2:2: 320 x 240 (25 Hz)
[INFO] [1698745511.231096083] [usb_cam]: 	YUYV 4:2:2: 320 x 180 (30 Hz)
[INFO] [1698745511.231104283] [usb_cam]: 	YUYV 4:2:2: 176 x 144 (30 Hz)
[INFO] [1698745511.231112552] [usb_cam]: 	YUYV 4:2:2: 160 x 120 (30 Hz)
[INFO] [1698745511.231120847] [usb_cam]: 	YUYV 4:2:2: 160 x 90 (30 Hz)
[INFO] [1698745511.231129093] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (30 Hz)
[INFO] [1698745511.231139182] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (25 Hz)
[INFO] [1698745511.231148634] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (20 Hz)
[INFO] [1698745511.231157956] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (15 Hz)
[INFO] [1698745511.231166792] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (10 Hz)
[INFO] [1698745511.231175285] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (5 Hz)
[INFO] [1698745511.231183677] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (30 Hz)
[INFO] [1698745511.231191964] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (25 Hz)
[INFO] [1698745511.231200355] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (20 Hz)
[INFO] [1698745511.231208745] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (15 Hz)
[INFO] [1698745511.231217153] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (10 Hz)
[INFO] [1698745511.231225397] [usb_cam]: 	YUYV 4:2:2: 640 x 480 (5 Hz)
[INFO] [1698745511.231233751] [usb_cam]: 	Motion-JPEG: 640 x 480 (30 Hz)
[INFO] [1698745511.231242124] [usb_cam]: 	Motion-JPEG: 640 x 480 (20 Hz)
[INFO] [1698745511.231250695] [usb_cam]: 	Motion-JPEG: 640 x 480 (15 Hz)
[INFO] [1698745511.231259472] [usb_cam]: 	Motion-JPEG: 640 x 480 (10 Hz)
[INFO] [1698745511.231267854] [usb_cam]: 	Motion-JPEG: 640 x 480 (5 Hz)
[INFO] [1698745511.231276338] [usb_cam]: 	Motion-JPEG: 640 x 480 (30 Hz)
[INFO] [1698745511.231284651] [usb_cam]: 	Motion-JPEG: 640 x 480 (20 Hz)
[INFO] [1698745511.231292991] [usb_cam]: 	Motion-JPEG: 640 x 480 (15 Hz)
[INFO] [1698745511.231341842] [usb_cam]: 	Motion-JPEG: 640 x 480 (10 Hz)
[INFO] [1698745511.231367304] [usb_cam]: 	Motion-JPEG: 640 x 480 (5 Hz)
[INFO] [1698745511.231376285] [usb_cam]: 	Motion-JPEG: 2048 x 1536 (15 Hz)
[INFO] [1698745511.231384974] [usb_cam]: 	Motion-JPEG: 1920 x 1080 (30 Hz)
[INFO] [1698745511.231393453] [usb_cam]: 	Motion-JPEG: 1920 x 1080 (20 Hz)
[INFO] [1698745511.231401723] [usb_cam]: 	Motion-JPEG: 1920 x 1080 (15 Hz)
[INFO] [1698745511.231410359] [usb_cam]: 	Motion-JPEG: 1920 x 1080 (10 Hz)
[INFO] [1698745511.231418591] [usb_cam]: 	Motion-JPEG: 1920 x 1080 (5 Hz)
[INFO] [1698745511.231426838] [usb_cam]: 	Motion-JPEG: 1600 x 896 (30 Hz)
[INFO] [1698745511.231434998] [usb_cam]: 	Motion-JPEG: 1280 x 720 (30 Hz)
[INFO] [1698745511.231443199] [usb_cam]: 	Motion-JPEG: 1280 x 720 (20 Hz)
[INFO] [1698745511.231451292] [usb_cam]: 	Motion-JPEG: 1280 x 720 (15 Hz)
[INFO] [1698745511.231459591] [usb_cam]: 	Motion-JPEG: 1280 x 720 (10 Hz)
[INFO] [1698745511.231467894] [usb_cam]: 	Motion-JPEG: 1280 x 720 (5 Hz)
[INFO] [1698745511.231476160] [usb_cam]: 	Motion-JPEG: 1024 x 576 (30 Hz)
[INFO] [1698745511.231484585] [usb_cam]: 	Motion-JPEG: 1024 x 576 (20 Hz)
[INFO] [1698745511.231492829] [usb_cam]: 	Motion-JPEG: 1024 x 576 (15 Hz)
[INFO] [1698745511.231501072] [usb_cam]: 	Motion-JPEG: 1024 x 576 (10 Hz)
[INFO] [1698745511.231509940] [usb_cam]: 	Motion-JPEG: 1024 x 576 (5 Hz)
[INFO] [1698745511.231518188] [usb_cam]: 	Motion-JPEG: 960 x 720 (30 Hz)
[INFO] [1698745511.231526495] [usb_cam]: 	Motion-JPEG: 960 x 720 (20 Hz)
[INFO] [1698745511.231534775] [usb_cam]: 	Motion-JPEG: 960 x 720 (15 Hz)
[INFO] [1698745511.231542834] [usb_cam]: 	Motion-JPEG: 960 x 720 (10 Hz)
[INFO] [1698745511.231550985] [usb_cam]: 	Motion-JPEG: 960 x 720 (5 Hz)
[INFO] [1698745511.231559412] [usb_cam]: 	Motion-JPEG: 864 x 480 (30 Hz)
[INFO] [1698745511.231567628] [usb_cam]: 	Motion-JPEG: 864 x 480 (20 Hz)
[INFO] [1698745511.231575988] [usb_cam]: 	Motion-JPEG: 864 x 480 (15 Hz)
[INFO] [1698745511.231584199] [usb_cam]: 	Motion-JPEG: 864 x 480 (10 Hz)
[INFO] [1698745511.231592415] [usb_cam]: 	Motion-JPEG: 864 x 480 (5 Hz)
[INFO] [1698745511.231600860] [usb_cam]: 	Motion-JPEG: 800 x 600 (30 Hz)
[INFO] [1698745511.231609120] [usb_cam]: 	Motion-JPEG: 800 x 600 (20 Hz)
[INFO] [1698745511.231617371] [usb_cam]: 	Motion-JPEG: 800 x 600 (15 Hz)
[INFO] [1698745511.231625684] [usb_cam]: 	Motion-JPEG: 800 x 600 (10 Hz)
[INFO] [1698745511.231633927] [usb_cam]: 	Motion-JPEG: 800 x 600 (5 Hz)
[INFO] [1698745511.231642444] [usb_cam]: 	Motion-JPEG: 800 x 448 (30 Hz)
[INFO] [1698745511.231650679] [usb_cam]: 	Motion-JPEG: 800 x 448 (20 Hz)
[INFO] [1698745511.231659003] [usb_cam]: 	Motion-JPEG: 800 x 448 (15 Hz)
[INFO] [1698745511.231667203] [usb_cam]: 	Motion-JPEG: 800 x 448 (10 Hz)
[INFO] [1698745511.231675270] [usb_cam]: 	Motion-JPEG: 800 x 448 (5 Hz)
[INFO] [1698745511.231683507] [usb_cam]: 	Motion-JPEG: 640 x 360 (30 Hz)
[INFO] [1698745511.231691768] [usb_cam]: 	Motion-JPEG: 640 x 360 (20 Hz)
[INFO] [1698745511.231700011] [usb_cam]: 	Motion-JPEG: 640 x 360 (15 Hz)
[INFO] [1698745511.231708193] [usb_cam]: 	Motion-JPEG: 640 x 360 (10 Hz)
[INFO] [1698745511.231716419] [usb_cam]: 	Motion-JPEG: 640 x 360 (5 Hz)
[INFO] [1698745511.231724728] [usb_cam]: 	Motion-JPEG: 432 x 240 (30 Hz)
[INFO] [1698745511.231735724] [usb_cam]: 	Motion-JPEG: 432 x 240 (20 Hz)
[INFO] [1698745511.231748305] [usb_cam]: 	Motion-JPEG: 432 x 240 (15 Hz)
[INFO] [1698745511.231756976] [usb_cam]: 	Motion-JPEG: 432 x 240 (10 Hz)
[INFO] [1698745511.231765338] [usb_cam]: 	Motion-JPEG: 432 x 240 (5 Hz)
[INFO] [1698745511.231774150] [usb_cam]: 	Motion-JPEG: 352 x 288 (30 Hz)
[INFO] [1698745511.231782318] [usb_cam]: 	Motion-JPEG: 352 x 288 (20 Hz)
[INFO] [1698745511.231790530] [usb_cam]: 	Motion-JPEG: 352 x 288 (15 Hz)
[INFO] [1698745511.231798652] [usb_cam]: 	Motion-JPEG: 352 x 288 (10 Hz)
[INFO] [1698745511.231806795] [usb_cam]: 	Motion-JPEG: 352 x 288 (5 Hz)
[INFO] [1698745511.231815346] [usb_cam]: 	Motion-JPEG: 320 x 240 (30 Hz)
[INFO] [1698745511.231823603] [usb_cam]: 	Motion-JPEG: 320 x 240 (20 Hz)
[INFO] [1698745511.231840110] [usb_cam]: 	Motion-JPEG: 320 x 240 (15 Hz)
[INFO] [1698745511.231850645] [usb_cam]: 	Motion-JPEG: 320 x 240 (10 Hz)
[INFO] [1698745511.231858869] [usb_cam]: 	Motion-JPEG: 320 x 240 (5 Hz)
[INFO] [1698745511.231867173] [usb_cam]: 	Motion-JPEG: 320 x 180 (30 Hz)
[INFO] [1698745511.231875499] [usb_cam]: 	Motion-JPEG: 320 x 180 (20 Hz)
[INFO] [1698745511.231883735] [usb_cam]: 	Motion-JPEG: 320 x 180 (15 Hz)
[INFO] [1698745511.231891989] [usb_cam]: 	Motion-JPEG: 320 x 180 (10 Hz)
[INFO] [1698745511.231900048] [usb_cam]: 	Motion-JPEG: 320 x 180 (5 Hz)
[INFO] [1698745511.231908353] [usb_cam]: 	Motion-JPEG: 176 x 144 (30 Hz)
[INFO] [1698745511.231916897] [usb_cam]: 	Motion-JPEG: 176 x 144 (20 Hz)
[INFO] [1698745511.231925107] [usb_cam]: 	Motion-JPEG: 176 x 144 (15 Hz)
[INFO] [1698745511.231935962] [usb_cam]: 	Motion-JPEG: 176 x 144 (10 Hz)
[INFO] [1698745511.231944727] [usb_cam]: 	Motion-JPEG: 176 x 144 (5 Hz)
[INFO] [1698745511.231953099] [usb_cam]: 	Motion-JPEG: 160 x 120 (30 Hz)
[INFO] [1698745511.231961377] [usb_cam]: 	Motion-JPEG: 160 x 120 (20 Hz)
[INFO] [1698745511.231969569] [usb_cam]: 	Motion-JPEG: 160 x 120 (15 Hz)
[INFO] [1698745511.231977833] [usb_cam]: 	Motion-JPEG: 160 x 120 (10 Hz)
[INFO] [1698745511.231986660] [usb_cam]: 	Motion-JPEG: 160 x 120 (5 Hz)
[INFO] [1698745511.231995027] [usb_cam]: 	Motion-JPEG: 160 x 90 (30 Hz)
[INFO] [1698745511.232003323] [usb_cam]: 	Motion-JPEG: 160 x 90 (20 Hz)
[INFO] [1698745511.232011516] [usb_cam]: 	Motion-JPEG: 160 x 90 (15 Hz)
[INFO] [1698745511.232019624] [usb_cam]: 	Motion-JPEG: 160 x 90 (10 Hz)
[INFO] [1698745511.232027928] [usb_cam]: 	Motion-JPEG: 160 x 90 (5 Hz)
[INFO] [1698745511.232036371] [usb_cam]: 	Motion-JPEG: 640 x 480 (30 Hz)
[INFO] [1698745511.232044555] [usb_cam]: 	Motion-JPEG: 640 x 480 (20 Hz)
[INFO] [1698745511.232052841] [usb_cam]: 	Motion-JPEG: 640 x 480 (15 Hz)
[INFO] [1698745511.232061147] [usb_cam]: 	Motion-JPEG: 640 x 480 (10 Hz)
[INFO] [1698745511.232069374] [usb_cam]: 	Motion-JPEG: 640 x 480 (5 Hz)
[INFO] [1698745511.232077549] [usb_cam]: 	Motion-JPEG: 640 x 480 (30 Hz)
[INFO] [1698745511.232085689] [usb_cam]: 	Motion-JPEG: 640 x 480 (20 Hz)
[INFO] [1698745511.232093728] [usb_cam]: 	Motion-JPEG: 640 x 480 (15 Hz)
[INFO] [1698745511.232101835] [usb_cam]: 	Motion-JPEG: 640 x 480 (10 Hz)
[INFO] [1698745511.232110196] [usb_cam]: 	Motion-JPEG: 640 x 480 (5 Hz)
unknown control 'white_balance_temperature_auto'

[INFO] [1698745511.236571864] [usb_cam]: Setting 'white_balance_temperature_auto' to 1
[INFO] [1698745511.236645601] [usb_cam]: Setting 'exposure_auto' to 3
unknown control 'exposure_auto'

[INFO] [1698745511.242242138] [usb_cam]: Setting 'focus_auto' to 0
unknown control 'focus_auto'

[INFO] [1698745511.921160505] [usb_cam]: Timer triggering every 33 ms
[ros2run]: Segmentation fault

@zweistein hmm interesting bug report. Would you be able to run valgrind on your setup to see where exactly the segfault happens?

I've tested it locally on my machine with the highest resolution my HW has but cannot reproduce....so will need to rely on your help to dig into it ๐Ÿ˜…

Let me know if you need some help with valgrind at all ๐Ÿ‘๐Ÿผ

I'm not familiar with `valgrind, ' but I have basic knowledge of GDB:

(gdb) where
#0  0x00007ffff6b05787 in  () at /lib/x86_64-linux-gnu/libswscale.so.5
#1  0x00007ffff6b0423b in  () at /lib/x86_64-linux-gnu/libswscale.so.5
#2  0x00007ffff6ad312d in sws_scale () at /lib/x86_64-linux-gnu/libswscale.so.5
#3  0x00007ffff745e3bf in  () at /opt/ros/humble/lib/libusb_cam.so
#4  0x00007ffff7460a75 in usb_cam::UsbCam::process_image(char const*, char*&, int const&) () at /opt/ros/humble/lib/libusb_cam.so
#5  0x00007ffff7460dfa in usb_cam::UsbCam::read_frame() () at /opt/ros/humble/lib/libusb_cam.so
#6  0x00007ffff7462378 in usb_cam::UsbCam::grab_image() () at /opt/ros/humble/lib/libusb_cam.so
#7  0x00007ffff7482ecf in usb_cam::UsbCamNode::take_and_send_image() () at /opt/ros/humble/lib/libusb_cam_node.so
#8  0x00007ffff7483778 in usb_cam::UsbCamNode::update() () at /opt/ros/humble/lib/libusb_cam_node.so
#9  0x00007ffff74840a5 in  () at /opt/ros/humble/lib/libusb_cam_node.so
#10 0x00007ffff7eabf51 in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&) () at /opt/ros/humble/lib/librclcpp.so
#11 0x00007ffff7eb38a0 in rclcpp::executors::SingleThreadedExecutor::spin() () at /opt/ros/humble/lib/librclcpp.so
#12 0x0000555555557f56 in  ()
#13 0x00007ffff7629d90 in __libc_start_call_main (main=main@entry=0x555555557a00, argc=argc@entry=4, argv=argv@entry=0x7fffffffc8f8) at ../sysdeps/nptl/libc_start_call_main.h:58
#14 0x00007ffff7629e40 in __libc_start_main_impl
     (main=0x555555557a00, argc=4, argv=0x7fffffffc8f8, init=<optimized out>, fini=<optimized out>, rtld_fini=<optimized out>, stack_end=0x7fffffffc8e8) at ../csu/libc-start.c:392
#15 0x000055555555a1f5 in  ()

I'm not sure if the backtrace helps the $_siginfo is empty. I will remove the installed library and build with the debug flag from the source. I'll come back with more debug info from gdb, but I'm happy to try valgrind as well.

Building from source poses a new issue. I checked out the ros2 branch in a custom workspace, then built it with:

$ colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo --packages-select usb_ca

Running node without arguments works and, as before, starts driver: Starting 'default_cam' (/dev/video0) at 640x480 via mmap (yuyv) at 30 FPS

But providing config file as argument: ros2 run usb_cam usb_cam_node_exe --ros-args --params-file /home/.../ros/usb_cam_debug_ws/src/usb_cam/config/params.yaml results in failure:

[INFO] [1699271094.667174012] [usb_cam]: camera_name value: test_camera
[WARN] [1699271094.667266129] [usb_cam]: framerate: 30.000000
[INFO] [1699271094.668386361] [usb_cam]: camera calibration URL: package://usb_cam/config/camera_info.yaml
[INFO] [1699271100.581520402] [usb_cam]: Starting 'test_camera' (/dev/video0) at 1920x1080 via mmap (mjpeg2rgb) at 30 FPS
/home/elod/ros/usb_cam_debug_ws/install/usb_cam/lib/usb_cam/usb_cam_node_exe: symbol lookup error: /home/elod/ros/usb_cam_debug_ws/install/usb_cam/lib/libusb_cam.so: undefined symbol: avcodec_find_decoder
[ros2run]: Process exited with failure 127

Now, I have a debug build from release 0.7.0 where I can lunch with the yaml from above and backtrace in gdb the segfault. The output is:

backtrace
#0  0x00007ffff6b05787 in  () at /lib/x86_64-linux-gnu/libswscale.so.5
#1  0x00007ffff6b0423b in  () at /lib/x86_64-linux-gnu/libswscale.so.5
#2  0x00007ffff6ad312d in sws_scale () at /lib/x86_64-linux-gnu/libswscale.so.5
#3  0x00007ffff74576ff in usb_cam::formats::MJPEG2RGB::convert(char const*&, char*&, int const&)
    (this=0x555555ea1f70, src=@0x7fffffffbca8: 0x7fffd95bb000 "\377\330\377\300", dest=@0x555555891be0: 0x7fffd87e2010 "", bytes_used=@0x7fffffffbccc: 75528)
    at /home/elod/ros/usb_cam_debug_ws/src/usb_cam/include/usb_cam/formats/mjpeg.hpp:201
#4  0x00007ffff7453eb5 in usb_cam::UsbCam::process_image(char const*, char*&, int const&)
    (this=this@entry=0x555555891ba0, src=<optimized out>, dest=@0x555555891be0: 0x7fffd87e2010 "", bytes_used=@0x7fffffffbccc: 75528)
    at /home/elod/ros/usb_cam_debug_ws/src/usb_cam/src/usb_cam.cpp:87
#5  0x00007ffff745423a in usb_cam::UsbCam::read_frame() (this=0x555555891ba0) at /usr/include/c++/11/bits/shared_ptr_base.h:1295
#6  0x00007ffff74552c8 in usb_cam::UsbCam::grab_image() (this=0x555555891ba0) at /home/elod/ros/usb_cam_debug_ws/src/usb_cam/src/usb_cam.cpp:647
#7  0x00007ffff74553e1 in usb_cam::UsbCam::get_image(char*) (this=<optimized out>, destination=<optimized out>) at /home/elod/ros/usb_cam_debug_ws/src/usb_cam/src/usb_cam.cpp:566
#8  0x00007ffff7478b00 in usb_cam::UsbCamNode::take_and_send_image() (this=0x555555623370) at /usr/include/c++/11/bits/stl_vector.h:1043
#9  0x00007ffff74791e8 in usb_cam::UsbCamNode::update() (this=0x555555623370) at /home/elod/ros/usb_cam_debug_ws/src/usb_cam/src/usb_cam_node.cpp:366
#10 0x00007ffff747c525 in std::__invoke_impl<void, void (usb_cam::UsbCamNode::*&)(), usb_cam::UsbCamNode*&>(std::__invoke_memfun_deref, void (usb_cam::UsbCamNode::*&)(), usb_cam::UsbCamNode*&) (__t=@0x555555ea21e0: 0x555555623370, __f=@0x555555ea21d0: (void (usb_cam::UsbCamNode::*)(usb_cam::UsbCamNode * const)) 0x7ffff7479180 <usb_cam::UsbCamNode::update()>)
    at /usr/include/c++/11/bits/invoke.h:71
#11 std::__invoke<void (usb_cam::UsbCamNode::*&)(), usb_cam::UsbCamNode*&>(void (usb_cam::UsbCamNode::*&)(), usb_cam::UsbCamNode*&)
    (__fn=@0x555555ea21d0: (void (usb_cam::UsbCamNode::*)(usb_cam::UsbCamNode * const)) 0x7ffff7479180 <usb_cam::UsbCamNode::update()>) at /usr/include/c++/11/bits/invoke.h:96
#12 std::_Bind<void (usb_cam::UsbCamNode::*(usb_cam::UsbCamNode*))()>::__call<void, , 0ul>(std::tuple<>&&, std::_Index_tuple<0ul>) (__args=<optimized out>, this=0x555555ea21d0)
    at /usr/include/c++/11/functional:420
#13 std::_Bind<void (usb_cam::UsbCamNode::*(usb_cam::UsbCamNode*))()>::operator()<, void>() (this=0x555555ea21d0) at /usr/include/c++/11/functional:503
#14 rclcpp::GenericTimer<std::_Bind<void (usb_cam::UsbCamNode::*(usb_cam::UsbCamNode*))()>, (void*)0>::execute_callback_delegate<std::_Bind<void (usb_cam::UsbCamNode::*(usb_cam::UsbCamNode*))()>, (void*)0>() (this=0x555555ea21a0) at /opt/ros/humble/include/rclcpp/rclcpp/timer.hpp:244
#15 rclcpp::GenericTimer<std::_Bind<void (usb_cam::UsbCamNode::*(usb_cam::UsbCamNode*))()>, (void*)0>::execute_callback() (this=0x555555ea21a0)
    at /opt/ros/humble/include/rclcpp/rclcpp/timer.hpp:230
#16 0x00007ffff7eabf51 in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&) () at /opt/ros/humble/lib/librclcpp.so
#17 0x00007ffff7eb38a0 in rclcpp::executors::SingleThreadedExecutor::spin() () at /opt/ros/humble/lib/librclcpp.so
#18 0x0000555555558510 in main(int, char**) (argc=<optimized out>, argv=<optimized out>)
    at /home/elod/ros/usb_cam_debug_ws/build/usb_cam/rclcpp_components/node_main_usb_cam_node_exe.cpp:65

@zweistein that segfault issue should already be fixed I think on the ros2 branch.

When you build from source, make sure to have a clean environment / remove any already-existing build/ and install/ directories. Also make sure not to source them before building, only source the underlay in /opt/ros/

@zweistein I'll also try and cut a new release this week so the fixes will be available with an apt update soon then ๐Ÿ‘

Hi, unfortunately, the fix didn't solve the issue on my end. I pulled the fix from ros2 branch, purged the sys installed version, built from source in a new workspace, then sourced the ws and ran the node the same way as last time. The backtrace error is also the same:

#16 0x00007ffff7eabf51 in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&) () at /opt/ros/humble/lib/librclcpp.so
#17 0x00007ffff7eb38a0 in rclcpp::executors::SingleThreadedExecutor::spin() () at /opt/ros/humble/lib/librclcpp.so
#18 0x0000555555558510 in main(int, char**) (argc=<optimized out>, argv=<optimized out>) at /home/elod/ros/usb_cam_debug_ws/build/usb_cam/rclcpp_components/node_main_usb_cam_node_exe.cpp:65

Can I provide you with any more details to help nail down the source of the issue?

@zweistein as I said before I think this issue is solved already on the ros2 branch...just when you build from source you need to make sure you are building in a clean environment (e.g. remove build/, install/ directories and do not source any other workspaces). Double check your .bashrc file if you are sourcing other older workspaces from another build.

Also its worth asking: what OS are you using? Double check you have the right dependencies installed (since your latest issue looks like a missing symbol from ffmpeg maybe?

@zweistein going to close this issue as I believe it's already solved and I haven't heard back from you.

Feel free to reopen it if needed.