Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Std::length_error in running the camera_node #50

Closed
ethanblaylock opened this issue Jun 12, 2024 · 27 comments · Fixed by #15
Closed

Std::length_error in running the camera_node #50

ethanblaylock opened this issue Jun 12, 2024 · 27 comments · Fixed by #15

Comments

@ethanblaylock
Copy link

I installed the camera_ros from source. On my attempts to run the node using ros2 jazzy, I am using a YUYV pixel format with a pi camera 3. Every resolution I try ends up with the node terminating after throwing an instance of 'std::length_error'. The error description saws that it cannot create std::vector larger than max_size().

@christianrauch
Copy link
Owner

Is this the same as #13?

@snaens
Copy link

snaens commented Jun 13, 2024

I have the same problem with the same hardware,
this problem persists between both channels (cam0 and cam1) on the CM4,
with both the wide-angle and regular pi cam v3

→ this very likely is #13

@snaens
Copy link

snaens commented Jun 13, 2024

Using #15 worked!

this was built inside a container with the command:
docker run -it --network=host -v /dev:/dev/ -v /run/udev/:/run/udev/ --privileged --rm ros:humble bash
using the build instructions
I removed --skip-keys=libcamera,
didn't compile/install any libcamera dependencies or libcamera itself
and ran git checkout fix_dynamic_extent

mkdir -p ~/camera_ws/
cd ~/camera_ws/
git clone https://github.com/christianrauch/camera_ros.git src/camera_ros
cd src/camera_ros
git checkout fix_dynamic_extent
cd ../..

apt update
source /opt/ros/humble/setup.bash
rosdep install --from-paths src --ignore-src -y #-y for automatic 'yes'
colcon build

source install/setup.bash
ros2 run camera_ros camera_node

setting no parameters used the NV21 format, resulting in Unrecognized image encoding [nv21] once a subscriber reads images
this is probably because ROS doesn't support that encoding?
Anyway, I also set some other parameters to remove warnings

root@bento-dev:~/camera_ws# ros2 run camera_ros camera_node --ros-args -p format:=XRGB8888 -p width:=1920 -p height:=1080 -p camera:=0
[0:24:41.552822524] [5042]  INFO Camera camera_manager.cpp:284 libcamera v0.1.0
[0:24:41.660784514] [5052]  INFO RPI vc4.cpp:390 Registered camera /base/soc/i2c0mux/i2c@0/imx708@1a to Unicam device /dev/media0 and ISP device /dev/media1
[WARN] [1718294411.663979311] [camera]: stream configuration adjusted from "1920x1080-XRGB8888" to "1920x1080-XRGB8888"
[0:24:41.662344396] [5042]  INFO Camera camera.cpp:1033 configuring streams: (0) 1920x1080-XRGB8888
[0:24:41.662978671] [5052]  INFO RPI vc4.cpp:512 Sensor: /base/soc/i2c0mux/i2c@0/imx708@1a - Selected sensor format: 2304x1296-SBGGR10_1X10 - Selected unicam format: 2304x1296-pBAA
[INFO] [1718294411.666719355] [camera]: camera "/base/soc/i2c0mux/i2c@0/imx708@1a" configured with 1920x1080-XRGB8888 stream
[WARN] [1718294411.669851100] [camera]: control NoiseReductionMode (39) not handled
[0:24:41.692182414] [5059]  WARN IPARPI ipa_base.cpp:1050 Could not set AF_PAUSE - no AF algorithm or not Continuous
[0:24:41.692278487] [5059]  WARN IPARPI ipa_base.cpp:1067 Could not set AF_TRIGGER - no AF algorithm or not Auto
[INFO] [1718294412.140485575] [camera]: using default calibration URL
[INFO] [1718294412.140828647] [camera]: camera calibration URL: file:///root/.ros/camera_info/imx708__base_soc_i2c0mux_i2c_0_imx708_1a_1920x1080.yaml
[ERROR] [1718294412.141129961] [camera_calibration_parsers]: Unable to open camera calibration file [/root/.ros/camera_info/imx708__base_soc_i2c0mux_i2c_0_imx708_1a_1920x1080.yaml]
[WARN] [1718294412.141239905] [camera]: Camera calibration file /root/.ros/camera_info/imx708__base_soc_i2c0mux_i2c_0_imx708_1a_1920x1080.yaml not found
[0:24:42.213161149] [5059]  WARN IPARPI ipa_base.cpp:1050 Could not set AF_PAUSE - no AF algorithm or not Continuous
[0:24:42.213275537] [5059]  WARN IPARPI ipa_base.cpp:1067 Could not set AF_TRIGGER - no AF algorithm or not Auto

Thank you for maintaining this package @christianrauch!
It's the best way to interface Pi cameras with ROS!

Edit: I just realized libcamera also works on my desktop PC.
Well, i guess it's most modern camera software then, even better!

@christianrauch
Copy link
Owner

Using #15 worked!

Nice. In the other issue it was reported that it causes another issue. Therefore I did not merge it yet.

Could you provide some details on how the AfWindows (the one that causes the issue) plays out in the end? Since I don't own the hardware, I cannot test how the AfWindows is exactly used. The AfWindows is a list of Rectangle, that as far as I understand, defines auto-focus areas in form of a bounding box made out of 4 values per "area".

If AfWindows only contains one Rectangle, then you should be able to get and set the parameter via a list of integers. If there are multiple Rectangle in AfWindows, then we cannot represent this in form of ROS parameters and the node should show a warning.

Could you please check the following:

  1. start the node on the Raspberry Pi
  2. check if the node prints [ERROR] [<timestamp>] [camera]: unsupported control 'AfWindows' (type: Rectangle): ParameterValue only supported for arithmetic types
  3. get the parameter description and value via ros2 param describe /camera AfWindows and ros2 param describe /camera AfWindows (where /camera is the node name)

setting no parameters used the NV21 format, resulting in Unrecognized image encoding [nv21] once a subscriber reads images
this is probably because ROS doesn't support that encoding?

Correct. The encoding exists for the message, but a lot of tools in the ROS ecosystem do not support that encoding.

Could you provide a full log of the terminal output when running the node with the default parameters? Since #47, the node should select defaults that match the libcamera defaults when supported by the ROS message. Theoretically, the selected pixel format should be the same as the one selected by the cam example.

Thank you for maintaining this package @christianrauch! It's the best way to interface Pi cameras with ROS!

Thanks :-)

Edit: I just realized libcamera also works on my desktop PC. Well, i guess it's most modern camera software then, even better!

libcamera is quite versatile and aims to support all the "standard webcam" hardware. So I think this is a good replacement for the V4L2 and Raspberry Pi specific libraries.

@snaens
Copy link

snaens commented Jun 14, 2024

1&2: The log in my last comment is the entire log, nothing else was written

3: AfWindows seems to contain one rectangle and makes sense

root@frameslap:/bento_ws# ros2 param get /camera AfWindows 
Integer values are: array('q', [0, 0, 0, 0])

root@frameslap:/bento_ws# ros2 param describe /camera AfWindows
Parameter name: AfWindows
  Type: integer array
  Description: Rectangle array[] range {(0, 0)/0x0}..{(65535, 65535)/65535x65535} (default: {(0, 0)/0x0})
  Constraints:

I fiddled around with the autofocus, everything seems to work fine
only AfTrigger acts weird, as you need to toggle it for it to work
(send a 1, nothing happens, then send a 0, and it triggers autofocus)


Correct. The encoding exists for the message, but a lot of tools in the ROS ecosystem do not support that encoding.

Thought so 👍


The entire default log, for good measure:

root@bento-dev:~/camera_ws# ros2 run camera_ros camera_node
[1:53:37.700525972] [3994]  INFO Camera camera_manager.cpp:284 libcamera v0.1.0
[1:53:37.854544722] [4004]  INFO RPI vc4.cpp:390 Registered camera /base/soc/i2c0mux/i2c@0/imx708@1a to Unicam device /dev/media1 and ISP device /dev/media3
[1:53:37.855800148] [4004]  WARN CameraSensorProperties camera_sensor_properties.cpp:249 No static properties available for 'imx708_wide'
[1:53:37.855871813] [4004]  WARN CameraSensorProperties camera_sensor_properties.cpp:251 Please consider updating the camera sensor properties database
[1:53:37.864540517] [4004]  INFO RPI vc4.cpp:390 Registered camera /base/soc/i2c0mux/i2c@1/imx708@1a to Unicam device /dev/media2 and ISP device /dev/media5
[INFO] [1718323520.386056317] [camera]: 
>> cameras:
   0: imx708 (/base/soc/i2c0mux/i2c@0/imx708@1a)
   1: imx708_wide (/base/soc/i2c0mux/i2c@1/imx708@1a)
[WARN] [1718323520.386842805] [camera]: no camera selected, using default: "/base/soc/i2c0mux/i2c@0/imx708@1a"
[WARN] [1718323520.386986044] [camera]: set parameter 'camera' to silent this warning
[INFO] [1718323520.387802569] [camera]: 
>> stream formats:
   - Pixelformat: NV21 (64x64 - 4608x2592)
   - Pixelformat: XBGR8888 (64x64 - 4608x2592)
   - Pixelformat: BGR888 (64x64 - 4608x2592)
   - Pixelformat: RGB888 (64x64 - 4608x2592)
   - Pixelformat: XRGB8888 (64x64 - 4608x2592)
   - Pixelformat: YUYV (64x64 - 4608x2592)
   - Pixelformat: UYVY (64x64 - 4608x2592)
[WARN] [1718323520.388042695] [camera]: no pixel format selected, using default: "NV21"
[WARN] [1718323520.388119768] [camera]: set parameter 'format' to silent this warning
[INFO] [1718323520.388332783] [camera]: 
>> NV21 format sizes:
   - 160x120
   - 240x160
   - 320x240
   - 400x240
   - 480x320
   - 640x360
   - 640x480
   - 720x480
   - 768x480
   - 854x480
   - 720x576
   - 800x600
   - 960x540
   - 1024x576
   - 960x640
   - 1024x600
   - 1024x768
   - 1280x720
   - 1152x864
   - 1280x800
   - 1360x768
   - 1366x768
   - 1440x900
   - 1280x1024
   - 1536x864
   - 1280x1080
   - 1600x900
   - 1400x1050
   - 1680x1050
   - 1600x1200
   - 1920x1080
   - 2048x1080
   - 1920x1200
   - 2160x1080
   - 2048x1152
   - 2560x1080
   - 2048x1536
   - 2560x1440
   - 2560x1600
   - 3840x1080
   - 2960x1440
   - 3440x1440
   - 2560x2048
   - 3200x1800
   - 3840x1600
   - 3200x2048
   - 3200x2400
   - 3840x2160
   - 4096x2160
   - 3840x2400
[WARN] [1718323520.388697778] [camera]: no dimensions selected, auto-selecting: "1920x1080"
[WARN] [1718323520.388751481] [camera]: set parameter 'width' or 'height' to silent this warning
[1:53:37.867970466] [3994]  INFO Camera camera.cpp:1033 configuring streams: (0) 1920x1080-NV21
[1:53:37.869038894] [4004]  INFO RPI vc4.cpp:512 Sensor: /base/soc/i2c0mux/i2c@0/imx708@1a - Selected sensor format: 2304x1296-SBGGR10_1X10 - Selected unicam format: 2304x1296-pBAA
[INFO] [1718323520.391931563] [camera]: camera "/base/soc/i2c0mux/i2c@0/imx708@1a" configured with 1920x1080-NV21 stream
[WARN] [1718323520.394777668] [camera]: control NoiseReductionMode (39) not handled
[1:53:37.888444678] [4013]  WARN IPARPI ipa_base.cpp:1050 Could not set AF_PAUSE - no AF algorithm or not Continuous
[1:53:37.888534658] [4013]  WARN IPARPI ipa_base.cpp:1067 Could not set AF_TRIGGER - no AF algorithm or not Auto
[INFO] [1718323520.831088415] [camera]: using default calibration URL
[INFO] [1718323520.831297931] [camera]: camera calibration URL: file:///root/.ros/camera_info/imx708__base_soc_i2c0mux_i2c_0_imx708_1a_1920x1080.yaml
[ERROR] [1718323520.831643648] [camera_calibration_parsers]: Unable to open camera calibration file [/root/.ros/camera_info/imx708__base_soc_i2c0mux_i2c_0_imx708_1a_1920x1080.yaml]
[WARN] [1718323520.831859108] [camera]: Camera calibration file /root/.ros/camera_info/imx708__base_soc_i2c0mux_i2c_0_imx708_1a_1920x1080.yaml not found
[1:53:38.420992929] [4013]  WARN IPARPI ipa_base.cpp:1050 Could not set AF_PAUSE - no AF algorithm or not Continuous
[1:53:38.421077872] [4013]  WARN IPARPI ipa_base.cpp:1067 Could not set AF_TRIGGER - no AF algorithm or not Auto

Note the Format, 1920x1080-NV21
Interestingly the cam demo takes a different one per default 800x600-XRGB8888:

bento@bento-dev:~ $ cam -c1 --capture=1
[1:57:27.523006513] [21553]  INFO Camera camera_manager.cpp:313 libcamera v0.3.0+49-e76bb1f5
[1:57:27.809698111] [21554]  WARN RPiSdn sdn.cpp:40 Using legacy SDN tuning - please consider moving SDN inside rpi.denoise
[1:57:27.821443546] [21554]  INFO RPI vc4.cpp:400 Registered camera /base/soc/i2c0mux/i2c@0/imx708@1a to Unicam device /dev/media1 and ISP device /dev/media3
[1:57:27.825800925] [21554]  WARN CameraSensorProperties camera_sensor_properties.cpp:274 No static properties available for 'imx708_wide'
[1:57:27.825903979] [21554]  WARN CameraSensorProperties camera_sensor_properties.cpp:276 Please consider updating the camera sensor properties database
[1:57:27.925924234] [21554]  WARN RPiSdn sdn.cpp:40 Using legacy SDN tuning - please consider moving SDN inside rpi.denoise
[1:57:27.933452084] [21554]  INFO RPI vc4.cpp:400 Registered camera /base/soc/i2c0mux/i2c@1/imx708@1a to Unicam device /dev/media2 and ISP device /dev/media5
Using camera /base/soc/i2c0mux/i2c@0/imx708@1a as cam0
[1:57:27.936054990] [21553]  INFO Camera camera.cpp:1183 configuring streams: (0) 800x600-XRGB8888
[1:57:27.937278286] [21554]  INFO RPI vc4.cpp:569 Sensor: /base/soc/i2c0mux/i2c@0/imx708@1a - Selected sensor format: 1536x864-SBGGR10_1X10 - Selected unicam format: 1536x864-pBAA
cam0: Capture 1 frames
7048.315389 (0.00 fps) cam0-stream0 seq: 000007 bytesused: 1920000

About the error:

I found out the isArray_ error comes from building libcamera yourself.
If I use the ros-humble-libcamera package it works just fine, no error.

If I compile camera_ros with ros-humble-libcamera (and then uninstall it and compile libcamera) and run it with self-compiled libcamera it also shows the error.
I tried this with the latest libcamera source, and with 0.1.0 and 0.2.0, all behaved the same.


libcamera is quite versatile and aims to support all the "standard webcam" hardware. So I think this is a good replacement for the V4L2 and Raspberry Pi specific libraries.

Definitely! There's somewhat of a revolution happening in the linux-camera world.
Pipewire is planning having camera support / already has it.
And V4L2 cameras that needed binary blobs are being replaced with open-source libcamera drivers.

@ethanblaylock
Copy link
Author

ethanblaylock commented Jun 14, 2024

Hi this may be an ignorant question, but I am trying to install the ros-jazzy-libcamera because rosdep tells me that the package exists. I cannot seem to get the system to find the package, nor can I find any documentation for it. I am running Ubuntu 24.04 with ros jazzy. Any tips?

@christianrauch
Copy link
Owner

Trying to untie some of the issues here:

The entire default log, for good measure:

root@bento-dev:~/camera_ws# ros2 run camera_ros camera_node
[1:53:37.700525972] [3994]  INFO Camera camera_manager.cpp:284 libcamera v0.1.0
[1:53:37.854544722] [4004]  INFO RPI vc4.cpp:390 Registered camera /base/soc/i2c0mux/i2c@0/imx708@1a to Unicam device /dev/media1 and ISP device /dev/media3
[1:53:37.855800148] [4004]  WARN CameraSensorProperties camera_sensor_properties.cpp:249 No static properties available for 'imx708_wide'
[1:53:37.855871813] [4004]  WARN CameraSensorProperties camera_sensor_properties.cpp:251 Please consider updating the camera sensor properties database
[1:53:37.864540517] [4004]  INFO RPI vc4.cpp:390 Registered camera /base/soc/i2c0mux/i2c@1/imx708@1a to Unicam device /dev/media2 and ISP device /dev/media5
[...]
[1:53:37.867970466] [3994]  INFO Camera camera.cpp:1033 configuring streams: (0) 1920x1080-NV21
[1:53:37.869038894] [4004]  INFO RPI vc4.cpp:512 Sensor: /base/soc/i2c0mux/i2c@0/imx708@1a - Selected sensor format: 2304x1296-SBGGR10_1X10 - Selected unicam format: 2304x1296-pBAA
[INFO] [1718323520.391931563] [camera]: camera "/base/soc/i2c0mux/i2c@0/imx708@1a" configured with 1920x1080-NV21 stream
[...]

Note the Format, 1920x1080-NV21 Interestingly the cam demo takes a different one per default 800x600-XRGB8888:

bento@bento-dev:~ $ cam -c1 --capture=1
[1:57:27.523006513] [21553]  INFO Camera camera_manager.cpp:313 libcamera v0.3.0+49-e76bb1f5
[...]
Using camera /base/soc/i2c0mux/i2c@0/imx708@1a as cam0
[1:57:27.936054990] [21553]  INFO Camera camera.cpp:1183 configuring streams: (0) 800x600-XRGB8888
[1:57:27.937278286] [21554]  INFO RPI vc4.cpp:569 Sensor: /base/soc/i2c0mux/i2c@0/imx708@1a - Selected sensor format: 1536x864-SBGGR10_1X10 - Selected unicam format: 1536x864-pBAA
cam0: Capture 1 frames
7048.315389 (0.00 fps) cam0-stream0 seq: 000007 bytesused: 1920000

With #47 this should not happen. But previously, these commits were not in the PR for the dynamic extends (#15). I rebased the PR recently. Can you update the remote branches, hard-reset on the updated remote branch for fix_dynamic_extent, and then try this again?

About the error:

I found out the isArray_ error comes from building libcamera yourself. If I use the ros-humble-libcamera package it works just fine, no error.

If I compile camera_ros with ros-humble-libcamera (and then uninstall it and compile libcamera) and run it with self-compiled libcamera it also shows the error. I tried this with the latest libcamera source, and with 0.1.0 and 0.2.0, all behaved the same.

So you are saying that the Assertion 'isArray_' failed error that was reported in the other issue does not occur with the binary ros-humble-libcamera (version 0.1), but only happens when building versions 0.1 and 0.2 from source?

@christianrauch
Copy link
Owner

Hi this may be an ignorant question, but I am trying to install the ros-jazzy-libcamera because rosdep tells me that the package exists. I cannot seem to get the system to find the package, nor can I find any documentation for it. I am running Ubuntu 24.04 with ros jazzy. Any tips?

The bloomed libcamera version is in the "testing" repositories (https://docs.ros.org/en/jazzy/Installation/Testing.html). The rosdep index seems to be updated before the packages are actually released to "stable".

You can either use the "testing" repository to use the ros-jazzy-libcamera (version 0.3) right now or you have to wait for the next jazzy sync when the "testing" packages will move to "stable".

@snaens
Copy link

snaens commented Jun 14, 2024

Can you update the remote branches, hard-reset on the updated remote branch for fix_dynamic_extent, and then try this again?

I did all of this yesterday, the latest commit in fix_dynamic_extent was 2 weeks ago
→ nothing changed when I updated just now! :P

I also tried using 6a68576 (checked out to it), it too starts a 1920x1080-NV21 stream


So you are saying that the Assertion 'isArray_' failed error that was reported in the other issue does not occur with the binary ros-humble-libcamera (version 0.1), but only happens when building versions 0.1 and 0.2 from source?

Exactly. this issue is persistent across all libcamera versions, not only 0.1.0 and 0.2.0.
Every from-source build causes the error.

I just tried it on jazzy with the testing repo and ros-jazzy-libcamera
it compiles and runs just fine, running on libcamera 0.3.0
It also does a 1920x1080-NV21 stream per default :/

root@bento-dev:/camera_ws# ros2 run camera_ros camera_node 
[6:00:30.598025078] [4625]  INFO Camera camera_manager.cpp:313 libcamera v0.3.0
[6:00:30.748962703] [4640]  WARN RPiSdn sdn.cpp:40 Using legacy SDN tuning - please consider moving SDN inside rpi.denoise
[6:00:30.751851532] [4640]  INFO RPI vc4.cpp:400 Registered camera /base/soc/i2c0mux/i2c@0/imx708@1a to Unicam device /dev/media4 and ISP device /dev/media1
[6:00:30.752833092] [4640]  WARN CameraSensorProperties camera_sensor_properties.cpp:274 No static properties available for 'imx708_wide'
[6:00:30.752885573] [4640]  WARN CameraSensorProperties camera_sensor_properties.cpp:276 Please consider updating the camera sensor properties database
[6:00:30.762190940] [4640]  WARN RPiSdn sdn.cpp:40 Using legacy SDN tuning - please consider moving SDN inside rpi.denoise
[6:00:30.764633572] [4640]  INFO RPI vc4.cpp:400 Registered camera /base/soc/i2c0mux/i2c@1/imx708@1a to Unicam device /dev/media5 and ISP device /dev/media3
[INFO] [1718347963.455339498] [camera]: 
>> cameras:
   0: imx708 (/base/soc/i2c0mux/i2c@0/imx708@1a)
   1: imx708_wide (/base/soc/i2c0mux/i2c@1/imx708@1a)
[WARN] [1718347963.455850528] [camera]: no camera selected, using default: "/base/soc/i2c0mux/i2c@0/imx708@1a"
[WARN] [1718347963.455905805] [camera]: set parameter 'camera' to silent this warning
[INFO] [1718347963.456957235] [camera]: 
>> stream formats:
   - Pixelformat: NV21 (64x64 - 4608x2592)
   - Pixelformat: XBGR8888 (64x64 - 4608x2592)
   - Pixelformat: BGR888 (64x64 - 4608x2592)
   - Pixelformat: RGB888 (64x64 - 4608x2592)
   - Pixelformat: XRGB8888 (64x64 - 4608x2592)
   - Pixelformat: YUYV (64x64 - 4608x2592)
   - Pixelformat: UYVY (64x64 - 4608x2592)
[WARN] [1718347963.457257527] [camera]: no pixel format selected, using default: "NV21"
[WARN] [1718347963.457331896] [camera]: set parameter 'format' to silent this warning
[INFO] [1718347963.457832444] [camera]: 
>> NV21 format sizes:
   - 160x120
   - 240x160
   - 320x240
   - 400x240
   - 480x320
   - 640x360
   - 640x480
   - 720x480
   - 768x480
   - 854x480
   - 720x576
   - 800x600
   - 960x540
   - 1024x576
   - 960x640
   - 1024x600
   - 1024x768
   - 1280x720
   - 1152x864
   - 1280x800
   - 1360x768
   - 1366x768
   - 1440x900
   - 1280x1024
   - 1536x864
   - 1280x1080
   - 1600x900
   - 1400x1050
   - 1680x1050
   - 1600x1200
   - 1920x1080
   - 2048x1080
   - 1920x1200
   - 2160x1080
   - 2048x1152
   - 2560x1080
   - 2048x1536
   - 2560x1440
   - 2560x1600
   - 3840x1080
   - 2960x1440
   - 3440x1440
   - 2560x2048
   - 3200x1800
   - 3840x1600
   - 3200x2048
   - 3200x2400
   - 3840x2160
   - 4096x2160
   - 3840x2400
[WARN] [1718347963.458043997] [camera]: no dimensions selected, auto-selecting: "1920x1080"
[WARN] [1718347963.458091644] [camera]: set parameter 'width' or 'height' to silent this warning
[6:00:30.768202002] [4625]  INFO Camera camera.cpp:1183 configuring streams: (0) 1920x1080-NV21
[6:00:30.769263413] [4640]  INFO RPI vc4.cpp:569 Sensor: /base/soc/i2c0mux/i2c@0/imx708@1a - Selected sensor format: 2304x1296-SBGGR10_1X10 - Selected unicam format: 2304x1296-pBAA
[INFO] [1718347963.461402727] [camera]: camera "/base/soc/i2c0mux/i2c@0/imx708@1a" configured with 1920x1080-NV21 stream
[WARN] [1718347963.464597737] [camera]: control NoiseReductionMode (10002) not handled
[6:00:30.786225227] [4649]  WARN IPARPI ipa_base.cpp:1166 Could not set AF_TRIGGER - no AF algorithm or not Auto
[6:00:30.786499130] [4649]  WARN IPARPI ipa_base.cpp:1149 Could not set AF_PAUSE - no AF algorithm or not Continuous
[INFO] [1718347963.907671899] [camera]: using default calibration URL
[INFO] [1718347963.907864230] [camera]: camera calibration URL: file:///root/.ros/camera_info/imx708__base_soc_i2c0mux_i2c_0_imx708_1a_1920x1080.yaml
[ERROR] [1718347963.908123300] [camera_calibration_parsers]: Unable to open camera calibration file [/root/.ros/camera_info/imx708__base_soc_i2c0mux_i2c_0_imx708_1a_1920x1080.yaml]
[WARN] [1718347963.908307871] [camera]: Camera calibration file /root/.ros/camera_info/imx708__base_soc_i2c0mux_i2c_0_imx708_1a_1920x1080.yaml not found
[6:00:31.323487990] [4649]  WARN IPARPI ipa_base.cpp:1166 Could not set AF_TRIGGER - no AF algorithm or not Auto
[6:00:31.323689728] [4649]  WARN IPARPI ipa_base.cpp:1149 Could not set AF_PAUSE - no AF algorithm or not Continuous

@snaens
Copy link

snaens commented Jun 14, 2024

I just tried using a different camera that works off of the main branch
It too defaulted to 1920x1080-NV21

@christianrauch
Copy link
Owner

Independent of the default settings:

@ethanblaylock and @snaens Can you confirm that #15 fixes the exception cannot create std::vector larger than max_size()?

@snaens
Copy link

snaens commented Jun 14, 2024

I can confirm:

  1. handle dynamic extents #15 consistently functions correctly if using prepackaged libcamera (ros-xxx-libcamera), and results in Assertion 'isArray_' failed. error when using self-compiled libcamera.

  2. handle dynamic extents #15 consistently fixes cannot create std::vector larger than max_size()

everything was tested on ros humble and jazzy-testing

@christianrauch
Copy link
Owner

christianrauch commented Jun 17, 2024

I believe I also found the cause for the Assertion `!isArray_' failed. This was caused by a less/greater comparison of a scalar with an array in the specific case when the AfWindows control contains a list with a single Rectangle (e.g. std::array<libcamera::Rectangle, 1>) instead of simply a Rectangle. This is now implemented in the latest commit of the PR.

@snaens Could you please check again with the latest #15 that the isArray_ assertion is not triggered on any of the libcamera versions from source?

@snaens
Copy link

snaens commented Jun 18, 2024

Nope, that wasn't it.
The latest commit changes nothing.

I found out what the problem is though :D


I traced the isArray_ error back to it's source.
It's a missing flag that tells libcamera if the control is an Array!

Libcamera expects this flag, and errors out if it is missing.
https://github.com/raspberrypi/libcamera/blob/main/include/libcamera/controls.h#L167
However it only does this when compiled in 'development' release,
as that's what assert does!

ros-xxx-libcamera is compiled as a release
assert() does nothing → no error!


So there's 2 fixes:

  • The first (temporary) one would be for everyone to compile libcamera as release
  • The second (proper) would be to set the isArray_ flag in the parameters map,
    at the defaults setup and the parameter callback.

Demo:

Screenshot_20240618_043128

Changing values via debugger (isArray_: false → true)


Screenshot_20240618_043259

This function contains the troublesome assert(), but the isArray_ value is correct now


Changing the value removes the error, and the node runs as normal afterwards.
This was of course done from the latest #15 commits.

@christianrauch
Copy link
Owner

Libcamera expects this flag, and errors out if it is missing.
https://github.com/raspberrypi/libcamera/blob/main/include/libcamera/controls.h#L167
However it only does this when compiled in 'development' release,
as that's what assert does!

I am kind of embarrassed that I did not see this myself :-) Of course, the assert will compiled out in release mode. The assert should trigger in debug mode, when compiled manually with the defaults, on any version of libcamera.

I traced the isArray_ error back to it's source.
It's a missing flag that tells libcamera if the control is an Array!

The isArray_ flag is nothing that should be changed by the user. The assert there should just make sure that, when this template specialisation with details::is_span<T>::value (i.e. the control is a span/list/array) is used, the isArray_ is also true. Otherwise, something in between would have altered the type of the control.

Forcing the isArray_ flag to some value does not solve the underlying issue.

I assume you get the same assert with 0.3 when compiled from source in debug mode. I found one case where that assert was triggered in 0.3 when I used a Span with a single element. I can see from your screenshots where the assert is generated. But I still cannot reproduce this by faking the controls on my side. Can you see where this ctrl is generated and what its type is?

@snaens
Copy link

snaens commented Jun 23, 2024

Hi, sorry for taking so long, just had a bad few last days.


I found out that this line was where the incorrect values originated.

I believe this is from a somehow non-erroring type mismatch.
onParameterChange expects a libcamera::ControlValue,
but pv_to_cv_int_array, which is called by pv_to_cv, returns a libcamera::Rectangle


As a test I changed the return type to libcamera::Span by changing these lines to this:

[...]
  case libcamera::ControlTypeInteger64:
  case libcamera::ControlTypeRectangle:
    return {libcamera::Span<const CTInteger64>(values)};
[...]

This circumvents the error, and the Node then works fine.


Having what seems to be the wrong type explains why the parameter value wasn't set to an array.
It's values were Jibberish :P

@christianrauch
Copy link
Owner

I found out that this line was where the incorrect values originated.

I believe this is from a somehow non-erroring type mismatch. onParameterChange expects a libcamera::ControlValue, but pv_to_cv_int_array, which is called by pv_to_cv, returns a libcamera::Rectangle

A libcamera::ControlValue can hold scalar or array values of any type in the libcamera::ControlType enum. Amongst others, it can hold a libcamera::Rectangle (type ControlTypeRectangle) or libcamera::Span<libcamera::Rectangle, Extent>.

The section

case libcamera::ControlTypeRectangle:
return {libcamera::Rectangle(values[0], values[1], values[2], values[3])};
you highlighted in pv_to_cv_int_array thus constructs a libcamera::ControlValue from a libcamera::Rectangle, which itself is constructed from 4 integers of an integer array.

So far, this behaviour is correct and the compiler would have complained if the construction/conversion is not possible. E.g. if you try to store a string in a ControlValue, you will get something like error: could not convert ‘{"I am a string."}’ from ‘<brace-enclosed initializer list>’ to ‘libcamera::ControlValue’.

However, I think you are on the right track here.

The ROS 2 parameters only support POD (Plain Old Data) types, strings and array versions thereof. But libcamera allows more complex data types, such as Rectangle and Size and Span<> of these, which cannot be directly mapped to the ROS 2 parameters. However, we can serialise/deserialise some of them, e.g. 4 ints to/from Rectangle and 2 ints to/from Size. This should work if a libcamera::Control holds a single type, such as the Control<Rectangle> ScalerCrop. However, this does not work for a list of unknown size, such as Control<Span<const Rectangle>> AfWindows.

As a test I changed the return type to libcamera::Span by changing these lines to this:

[...]
  case libcamera::ControlTypeInteger64:
  case libcamera::ControlTypeRectangle:
    return {libcamera::Span<const CTInteger64>(values)};
[...]

This circumvents the error, and the Node then works fine.

In

case libcamera::ControlTypeRectangle:
return {libcamera::Rectangle(values[0], values[1], values[2], values[3])};
we try to deserialise 4 integers back into a Rectangle. What you propose instead is to skip this and return the raw integer values instead. That means, setting the parameter via:

ros2 param set /camera AfWindows "[10, 10, 50, 50]"

will result in:

Setting parameter failed: AfWindows: parameter types mismatch, expected 'Rectangle', got 'Integer64'

I think that the underlying problem is that if the ControlId is ControlTypeRectangle, we do not know if we should serialise to a Rectangle or a Span<Rectangle, 1> (i.e. a list with a single element). And here we are returning a Rectangle while later parts of the stack that consume the ControlValue may assume this to be a Span<Rectangle, 1>. In extract_value

template<typename T>
std::vector<T>
extract_value(const libcamera::ControlValue &value)
{
if (value.isArray()) {
const libcamera::Span<const T> span = value.get<libcamera::Span<const T>>();
return std::vector<T>(span.begin(), span.end());
}
else {
return {value.get<T>()};
}
}

single types are converted into a single-element array and in
case 1:
// single element (scalar)
return cv_to_pv_scalar(values[0]);
we convert single-element arrays into scalar representations, e.g. a std::vector<Rectangle> of size 1 into a Rectangle. This information is lost, hence we can later not recover the original type.

As I cannot reproduce this and debug properly, it is still not clear where this issue originates and where the assertion occurs. Could you please run the node with the full debug information from libcamera and the ROS node in gdb and generate the backtrace:

LIBCAMERA_LOG_LEVELS=*:DEBUG ros2 run --prefix 'gdb -ex run --args' camera_ros camera_node --ros-args --log-level camera:=debug

and then paste the full log here?

@snaens
Copy link

snaens commented Jul 2, 2024

Full log:

root@bento-dev:/camera_ws# LIBCAMERA_LOG_LEVELS=*:DEBUG ros2 run --prefix 'gdb -ex run --args' camera_ros camera_node --ros-args --log-level camera:=debug
GNU gdb (Ubuntu 12.1-0ubuntu1~22.04.2) 12.1
Copyright (C) 2022 Free Software Foundation, Inc.
License GPLv3+: GNU GPL version 3 or later <http://gnu.org/licenses/gpl.html>
This is free software: you are free to change and redistribute it.
There is NO WARRANTY, to the extent permitted by law.
Type "show copying" and "show warranty" for details.
This GDB was configured as "aarch64-linux-gnu".
Type "show configuration" for configuration details.
For bug reporting instructions, please see:
<https://www.gnu.org/software/gdb/bugs/>.
Find the GDB manual and other documentation resources online at:
    <http://www.gnu.org/software/gdb/documentation/>.

For help, type "help".
Type "apropos word" to search for commands related to "word"...
Reading symbols from /camera_ws/install/camera_ros/lib/camera_ros/camera_node...
(No debugging symbols found in /camera_ws/install/camera_ros/lib/camera_ros/camera_node)
Starting program: /camera_ws/install/camera_ros/lib/camera_ros/camera_node --ros-args --log-level camera:=debug
[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/aarch64-linux-gnu/libthread_db.so.1".
[New Thread 0x7ff671e8e0 (LWP 6964)]
[New Thread 0x7feb86e8e0 (LWP 6965)]
[New Thread 0x7feb05e8e0 (LWP 6966)]
[New Thread 0x7fea84e8e0 (LWP 6967)]
[New Thread 0x7fe9fb78e0 (LWP 6968)]
[New Thread 0x7fe97a78e0 (LWP 6969)]
[New Thread 0x7fe8f978e0 (LWP 6970)]
[New Thread 0x7fe3ffe8e0 (LWP 6971)]
[New Thread 0x7fe37ee8e0 (LWP 6972)]
[New Thread 0x7fe2fde8e0 (LWP 6973)]
[New Thread 0x7fe27ce8e0 (LWP 6974)]
[0:53:34.188891857] [6962] DEBUG IPAModule ipa_module.cpp:334 ipa_rkisp1.so: IPA module /usr/local/lib/aarch64-linux-gnu/libcamera/ipa_rkisp1.so is signed
[0:53:34.189352612] [6962] DEBUG IPAManager ipa_manager.cpp:245 Loaded IPA module '/usr/local/lib/aarch64-linux-gnu/libcamera/ipa_rkisp1.so'
[0:53:34.191115612] [6962] DEBUG IPAModule ipa_module.cpp:334 ipa_rpi_vc4.so: IPA module /usr/local/lib/aarch64-linux-gnu/libcamera/ipa_rpi_vc4.so is signed
[0:53:34.191319388] [6962] DEBUG IPAManager ipa_manager.cpp:245 Loaded IPA module '/usr/local/lib/aarch64-linux-gnu/libcamera/ipa_rpi_vc4.so'
[0:53:34.191623755] [6962] DEBUG IPAModule ipa_module.cpp:334 ipa_soft_simple.so: IPA module /usr/local/lib/aarch64-linux-gnu/libcamera/ipa_soft_simple.so is signed
[0:53:34.191720550] [6962] DEBUG IPAManager ipa_manager.cpp:245 Loaded IPA module '/usr/local/lib/aarch64-linux-gnu/libcamera/ipa_soft_simple.so'
[0:53:34.261251323] [6962]  INFO Camera camera_manager.cpp:313 libcamera v0.3.0+117-e3310749
[New Thread 0x7fe1fbe8e0 (LWP 6975)]
[0:53:34.262507772] [6975] DEBUG Camera camera_manager.cpp:69 Starting camera manager
[0:53:34.269463478] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:230 New media device "rpivid" created from /dev/media2
[0:53:34.270030990] [6975] DEBUG DeviceEnumerator device_enumerator_udev.cpp:96 Defer media device /dev/media2 due to 1 missing dependencies
[0:53:34.271093720] [6975] DEBUG DeviceEnumerator device_enumerator_udev.cpp:322 All dependencies for media device /dev/media2 found
[0:53:34.271214515] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:258 Added device /dev/media2: rpivid
[0:53:34.272392539] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:230 New media device "bcm2835-codec" created from /dev/media5
[0:53:34.272600519] [6975] DEBUG DeviceEnumerator device_enumerator_udev.cpp:96 Defer media device /dev/media5 due to 5 missing dependencies
[0:53:34.274269353] [6975] DEBUG DeviceEnumerator device_enumerator_udev.cpp:322 All dependencies for media device /dev/media5 found
[0:53:34.274387611] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:258 Added device /dev/media5: bcm2835-codec
[0:53:34.274996049] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:230 New media device "bcm2835-isp" created from /dev/media0
[0:53:34.275165973] [6975] DEBUG DeviceEnumerator device_enumerator_udev.cpp:96 Defer media device /dev/media0 due to 4 missing dependencies
[0:53:34.275724301] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:230 New media device "bcm2835-isp" created from /dev/media1
[0:53:34.275878373] [6975] DEBUG DeviceEnumerator device_enumerator_udev.cpp:96 Defer media device /dev/media1 due to 4 missing dependencies
[0:53:34.277286692] [6975] DEBUG DeviceEnumerator device_enumerator_udev.cpp:322 All dependencies for media device /dev/media0 found
[0:53:34.277400394] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:258 Added device /dev/media0: bcm2835-isp
[0:53:34.278728029] [6975] DEBUG DeviceEnumerator device_enumerator_udev.cpp:322 All dependencies for media device /dev/media1 found
[0:53:34.278833972] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:258 Added device /dev/media1: bcm2835-isp
[0:53:34.279644149] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:230 New media device "unicam" created from /dev/media3
[0:53:34.279782092] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:258 Added device /dev/media3: unicam
[0:53:34.280270457] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:230 New media device "unicam" created from /dev/media4
[0:53:34.280992746] [6975] DEBUG DeviceEnumerator device_enumerator_udev.cpp:96 Defer media device /dev/media4 due to 2 missing dependencies
[0:53:34.281817052] [6975] DEBUG DeviceEnumerator device_enumerator_udev.cpp:322 All dependencies for media device /dev/media4 found
[0:53:34.281921884] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:258 Added device /dev/media4: unicam
[0:53:34.282723931] [6975] DEBUG Camera camera_manager.cpp:134 Found registered pipeline handler 'imx8-isi'
[0:53:34.283786235] [6975] DEBUG Camera camera_manager.cpp:134 Found registered pipeline handler 'mali-c55'
[0:53:34.284264286] [6975] DEBUG Camera camera_manager.cpp:134 Found registered pipeline handler 'rkisp1'
[0:53:34.284840057] [6975] DEBUG Camera camera_manager.cpp:134 Found registered pipeline handler 'rpi/vc4'
[0:53:34.285102573] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:318 Successful match for media device "unicam"
[0:53:34.285279090] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:318 Successful match for media device "bcm2835-isp"
[0:53:34.285374441] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:318 Successful match for media device "unicam"
[0:53:34.285441662] [6975] DEBUG DeviceEnumerator device_enumerator.cpp:318 Successful match for media device "bcm2835-isp"
[0:53:34.286218043] [6975] DEBUG DmaBufAllocator dma_buf_allocator.cpp:109 Using /dev/dma_heap/linux,cma
[0:53:34.287195977] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Exposure (0x00980911)
[0:53:34.288194948] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Horizontal Flip (0x00980914)
[0:53:34.288460186] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Vertical Flip (0x00980915)
[0:53:34.288597537] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Wide Dynamic Range (0x009a0915)
[0:53:34.288712943] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Camera Orientation (0x009a0922)
[0:53:34.289105698] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Camera Sensor Rotation (0x009a0923)
[0:53:34.289287381] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Vertical Blanking (0x009e0901)
[0:53:34.289373529] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Horizontal Blanking (0x009e0902)
[0:53:34.289457120] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Analogue Gain (0x009e0903)
[0:53:34.289549027] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Red Pixel Value (0x009e0904)
[0:53:34.289658896] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Green (Red) Pixel Value (0x009e0905)
[0:53:34.289774524] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Blue Pixel Value (0x009e0906)
[0:53:34.289866838] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Green (Blue) Pixel Value (0x009e0907)
[0:53:34.289947837] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Notify Gains (0x009e0909)
[0:53:34.290081836] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Link Frequency (0x009f0901)
[0:53:34.290223242] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Pixel Rate (0x009f0902)
[0:53:34.290353926] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Test Pattern (0x009f0903)
[0:53:34.290526424] [6975] DEBUG V4L2 v4l2_device.cpp:636 'imx708': Control: Digital Gain (0x009f0905)
[0:53:34.385719465] [6975] DEBUG V4L2 v4l2_device.cpp:636 'dw9807 10-000c': Control: Focus, Absolute (0x009a090a)
[0:53:34.388578232] [6975] DEBUG CameraSensor camera_sensor.cpp:1187 'imx708': Apply test pattern mode 0
[0:53:34.473569898] [6975] DEBUG IPAManager ipa_manager.cpp:316 IPA module /usr/local/lib/aarch64-linux-gnu/libcamera/ipa_rpi_vc4.so signature is valid
[0:53:34.474801071] [6975] DEBUG IPAProxy raspberrypi_ipa_proxy.cpp:45 initializing raspberrypi proxy: loading IPA from /usr/local/lib/aarch64-linux-gnu/libcamera/ipa_rpi_vc4.so
[0:53:35.216459535] [6975] DEBUG RPiBlackLevel black_level.cpp:41  Read black levels red 4096 green 4096 blue 4096
[0:53:35.217104899] [6975]  WARN RPiSdn sdn.cpp:40 Using legacy SDN tuning - please consider moving SDN inside rpi.denoise
[New Thread 0x7fe17ae8e0 (LWP 6976)]
[0:53:35.219508429] [6975] DEBUG RPiAgc agc.cpp:49 Read AGC channel
[0:53:35.219892851] [6975] DEBUG RPiAgc agc_channel.cpp:219 AgcConfig
[0:53:35.222108828] [6975] DEBUG RPiAgc agc.cpp:49 Read AGC channel
[0:53:35.222502287] [6975] DEBUG RPiAgc agc_channel.cpp:219 AgcConfig
[0:53:35.223220983] [6975] DEBUG RPiAgc agc.cpp:49 Read AGC channel
[0:53:35.223378945] [6975] DEBUG RPiAgc agc_channel.cpp:219 AgcConfig
[0:53:35.224038345] [6975] DEBUG RPiAgc agc.cpp:56 Read 3 channel(s)
[New Thread 0x7fe0f9e8e0 (LWP 6977)]
[0:53:35.226000269] [6975] DEBUG RPiAlsc alsc.cpp:139 Read calibrations_Cr calibration for ct 3000
[0:53:35.226394672] [6975] DEBUG RPiAlsc alsc.cpp:139 Read calibrations_Cr calibration for ct 5000
[0:53:35.226700799] [6975] DEBUG RPiAlsc alsc.cpp:139 Read calibrations_Cb calibration for ct 3000
[0:53:35.226989481] [6975] DEBUG RPiAlsc alsc.cpp:139 Read calibrations_Cb calibration for ct 5000
[0:53:35.227625771] [6975] DEBUG RPiSharpen sharpen.cpp:45 Read threshold 1 strength 1 limit 1
[0:53:35.231636432] [6975] DEBUG RPiDelayedControls delayed_controls.cpp:103 Set a delay of 3 and priority write flag 1 for Vertical Blanking
[0:53:35.231880689] [6975] DEBUG RPiDelayedControls delayed_controls.cpp:103 Set a delay of 3 and priority write flag 0 for Horizontal Blanking
[0:53:35.231963762] [6975] DEBUG RPiDelayedControls delayed_controls.cpp:103 Set a delay of 2 and priority write flag 0 for Exposure
[0:53:35.232058224] [6975] DEBUG RPiDelayedControls delayed_controls.cpp:103 Set a delay of 2 and priority write flag 0 for Analogue Gain
[0:53:35.233966260] [6975] DEBUG V4L2 v4l2_videodevice.cpp:632 /dev/video0[30:cap]: Opened device platform:fe801000.csi: unicam: unicam
[0:53:35.235041397] [6975] DEBUG V4L2 v4l2_videodevice.cpp:632 /dev/video1[31:cap]: Opened device platform:fe801000.csi: unicam: unicam
[0:53:35.235279061] [6975] DEBUG V4L2 v4l2_device.cpp:636 /dev/video20[32:cap]: Control: Red Balance (0x0098090e)
[0:53:35.235518318] [6975] DEBUG V4L2 v4l2_device.cpp:636 /dev/video20[32:cap]: Control: Blue Balance (0x0098090f)
[0:53:35.235691297] [6975] DEBUG V4L2 v4l2_device.cpp:636 /dev/video20[32:cap]: Control: Colour Correction Matrix (0x009819e1)
[0:53:35.235849555] [6975] DEBUG V4L2 v4l2_device.cpp:636 /dev/video20[32:cap]: Control: Lens Shading (0x009819e2)
[0:53:35.235968313] [6975] DEBUG V4L2 v4l2_device.cpp:636 /dev/video20[32:cap]: Control: Black Level (0x009819e3)
[0:53:35.236111626] [6975] DEBUG V4L2 v4l2_device.cpp:636 /dev/video20[32:cap]: Control: Green Equalisation (0x009819e4)
[0:53:35.236220755] [6975] DEBUG V4L2 v4l2_device.cpp:636 /dev/video20[32:cap]: Control: Gamma (0x009819e5)
[0:53:35.236314272] [6975] DEBUG V4L2 v4l2_device.cpp:636 /dev/video20[32:cap]: Control: Denoise (0x009819e6)
[0:53:35.236399068] [6975] DEBUG V4L2 v4l2_device.cpp:636 /dev/video20[32:cap]: Control: Sharpen (0x009819e7)
[0:53:35.236494326] [6975] DEBUG V4L2 v4l2_device.cpp:636 /dev/video20[32:cap]: Control: Defective Pixel Correction (0x009819e8)
[0:53:35.236592380] [6975] DEBUG V4L2 v4l2_device.cpp:636 /dev/video20[32:cap]: Control: Colour Denoise (0x009819e9)
[0:53:35.236691324] [6975] DEBUG V4L2 v4l2_device.cpp:636 /dev/video20[32:cap]: Control: Digital Gain (0x009f0905)
[0:53:35.236969247] [6975] DEBUG V4L2 v4l2_videodevice.cpp:632 /dev/video20[32:out]: Opened device platform:bcm2835-isp: bcm2835-isp: bcm2835-isp
[0:53:35.237501926] [6975] DEBUG V4L2 v4l2_videodevice.cpp:632 /dev/video21[33:cap]: Opened device platform:bcm2835-isp: bcm2835-isp: bcm2835-isp
[0:53:35.237855886] [6975] DEBUG V4L2 v4l2_videodevice.cpp:632 /dev/video22[34:cap]: Opened device platform:bcm2835-isp: bcm2835-isp: bcm2835-isp
[0:53:35.238157864] [6975] DEBUG V4L2 v4l2_videodevice.cpp:632 /dev/video23[35:cap]: Opened device platform:bcm2835-isp: bcm2835-isp: bcm2835-isp
[0:53:35.239462647] [6975]  INFO RPI vc4.cpp:400 Registered camera /base/soc/i2c0mux/i2c@1/imx708@1a to Unicam device /dev/media4 and ISP device /dev/media1
[0:53:35.239823902] [6975] DEBUG Camera camera_manager.cpp:155 Pipeline handler "rpi/vc4" matched
[0:53:35.239999511] [6975] DEBUG RPI vc4.cpp:178 Unable to acquire a Unicam instance
[0:53:35.240092344] [6975] DEBUG RPI vc4.cpp:178 Unable to acquire a Unicam instance
[0:53:35.240203880] [6975] DEBUG Camera camera_manager.cpp:134 Found registered pipeline handler 'simple'
[0:53:35.240550913] [6975] DEBUG Camera camera_manager.cpp:134 Found registered pipeline handler 'uvcvideo'
[INFO] [1719912487.991487108] [camera]: 
>> cameras:
   0: imx708 (/base/soc/i2c0mux/i2c@1/imx708@1a)
[WARN] [1719912487.992780891] [camera]: no camera selected, using default: "/base/soc/i2c0mux/i2c@1/imx708@1a"
[WARN] [1719912487.992898426] [camera]: set parameter 'camera' to silent this warning
[0:53:35.244862516] [6962] DEBUG Camera camera.cpp:1118 streams configuration: (0) 1920x1080-YUV420
[DEBUG] [1719912487.995610546] [camera]: 
>> stream formats:
   - Pixelformat: NV21 (64x64 - 4608x2592)
   - Pixelformat: YUV420 (64x64 - 4608x2592)
   - Pixelformat: NV12 (64x64 - 4608x2592)
   - Pixelformat: YVU420 (64x64 - 4608x2592)
   - Pixelformat: XBGR8888 (64x64 - 4608x2592)
   - Pixelformat: BGR888 (64x64 - 4608x2592)
   - Pixelformat: RGB888 (64x64 - 4608x2592)
   - Pixelformat: XRGB8888 (64x64 - 4608x2592)
   - Pixelformat: RGB565 (64x64 - 4608x2592)
   - Pixelformat: YVYU (64x64 - 4608x2592)
   - Pixelformat: YUYV (64x64 - 4608x2592)
   - Pixelformat: VYUY (64x64 - 4608x2592)
   - Pixelformat: UYVY (64x64 - 4608x2592)
[INFO] [1719912487.996321539] [camera]: 
>> stream formats:
   - Pixelformat: NV21 (64x64 - 4608x2592)
   - Pixelformat: XBGR8888 (64x64 - 4608x2592)
   - Pixelformat: BGR888 (64x64 - 4608x2592)
   - Pixelformat: RGB888 (64x64 - 4608x2592)
   - Pixelformat: XRGB8888 (64x64 - 4608x2592)
   - Pixelformat: YUYV (64x64 - 4608x2592)
   - Pixelformat: UYVY (64x64 - 4608x2592)
[WARN] [1719912487.996553518] [camera]: no pixel format selected, using default: "NV21"
[WARN] [1719912487.996747201] [camera]: set parameter 'format' to silent this warning
[INFO] [1719912487.997711895] [camera]: 
>> NV21 format sizes:
   - 160x120
   - 240x160
   - 320x240
   - 400x240
   - 480x320
   - 640x360
   - 640x480
   - 720x480
   - 768x480
   - 854x480
   - 720x576
   - 800x600
   - 960x540
   - 1024x576
   - 960x640
   - 1024x600
   - 1024x768
   - 1280x720
   - 1152x864
   - 1280x800
   - 1360x768
   - 1366x768
   - 1440x900
   - 1280x1024
   - 1536x864
   - 1280x1080
   - 1600x900
   - 1400x1050
   - 1680x1050
   - 1600x1200
   - 1920x1080
   - 2048x1080
   - 1920x1200
   - 2160x1080
   - 2048x1152
   - 2560x1080
   - 2048x1536
   - 2560x1440
   - 2560x1600
   - 3840x1080
   - 2960x1440
   - 3440x1440
   - 2560x2048
   - 3200x1800
   - 3840x1600
   - 3200x2048
   - 3200x2400
   - 3840x2160
   - 4096x2160
   - 3840x2400
[WARN] [1719912487.998807976] [camera]: no dimensions selected, auto-selecting: "1920x1080"
[WARN] [1719912487.998937400] [camera]: set parameter 'width' or 'height' to silent this warning
[0:53:35.249631207] [6962] DEBUG RPI pipeline_base.cpp:957 Format: 1536x864 fmt SRGGB10 Score: 2200 (best 2200)
[0:53:35.250014759] [6962] DEBUG RPI pipeline_base.cpp:957 Format: 2304x1296 fmt SRGGB10 Score: 1150 (best 1150)
[0:53:35.250078888] [6962] DEBUG RPI pipeline_base.cpp:957 Format: 4608x2592 fmt SRGGB10 Score: 2050 (best 1150)
[0:53:35.250229738] [6962] DEBUG RPI pipeline_base.cpp:284 Try color space Rec709
[0:53:35.251329078] [6962] DEBUG RPI pipeline_base.cpp:957 Format: 1536x864 fmt SRGGB10 Score: 2200 (best 2200)
[0:53:35.251465262] [6962] DEBUG RPI pipeline_base.cpp:957 Format: 2304x1296 fmt SRGGB10 Score: 1150 (best 1150)
[0:53:35.251518595] [6962] DEBUG RPI pipeline_base.cpp:957 Format: 4608x2592 fmt SRGGB10 Score: 2050 (best 1150)
[0:53:35.251600946] [6962] DEBUG RPI pipeline_base.cpp:284 Try color space Rec709
[0:53:35.251722611] [6962]  INFO Camera camera.cpp:1183 configuring streams: (0) 1920x1080-NV21
[0:53:35.254013124] [6975]  INFO RPI vc4.cpp:569 Sensor: /base/soc/i2c0mux/i2c@1/imx708@1a - Selected sensor format: 2304x1296-SBGGR10_1X10 - Selected unicam format: 2304x1296-pBAA
[0:53:35.254163900] [6975] DEBUG RPI vc4.cpp:584 Setting ISP Output0 to 1920x1080-NV21
[0:53:35.254394083] [6975] DEBUG RPI vc4.cpp:591 Stream ISP Output0 has color space Rec709
[0:53:35.254541785] [6975] DEBUG RPI vc4.cpp:655 Setting ISP Output1 (internal) to 960x540-YU12
[0:53:35.254965781] [6975] DEBUG RPI vc4.cpp:692 Setting embedded data format 0x0-SENS
[0:53:35.256953371] [6975] DEBUG IPARPI ipa_base.cpp:1480 Applying AGC Exposure: 19987.54us (Shutter lines: 1496, AGC requested 20000.00us) Gain: 1 (Gain Code: 112)
[0:53:35.257317719] [6975] DEBUG RPiAf af.cpp:723 setLensPosition: 1
[INFO] [1719912488.009323403] [camera]: camera "/base/soc/i2c0mux/i2c@1/imx708@1a" configured with 1920x1080-NV21 stream
[DEBUG] [1719912488.009711584] [camera]: declare HdrMode with default 0
[DEBUG] [1719912488.010023840] [camera]: declare Contrast with default 1.000000
[DEBUG] [1719912488.010235467] [camera]: declare AfPause with default 0
[DEBUG] [1719912488.011079255] [camera]: declare Brightness with default 0.000000
[DEBUG] [1719912488.011377270] [camera]: declare ColourGains with default not set
[DEBUG] [1719912488.011508065] [camera]: declare AeFlickerPeriod with default not set
[DEBUG] [1719912488.011626564] [camera]: declare AwbMode with default 0
[DEBUG] [1719912488.011760637] [camera]: declare AfTrigger with default 0
[DEBUG] [1719912488.011906913] [camera]: declare AeFlickerMode with default 0
[DEBUG] [1719912488.012454185] [camera]: declare AeExposureMode with default 0
[DEBUG] [1719912488.012877458] [camera]: declare Sharpness with default 1.000000
[DEBUG] [1719912488.013595580] [camera]: declare AfMetering with default 0
[DEBUG] [1719912488.014004817] [camera]: declare ExposureValue with default 0.000000
[DEBUG] [1719912488.014765716] [camera]: declare AeConstraintMode with default 0
[DEBUG] [1719912488.015830890] [camera]: declare ScalerCrop with default [0, 0, 4608, 2592]
[DEBUG] [1719912488.016744288] [camera]: declare AfRange with default 0
[DEBUG] [1719912488.017139858] [camera]: declare AeEnable with default not set
[DEBUG] [1719912488.017871073] [camera]: declare ExposureTime with default not set
[DEBUG] [1719912488.018135681] [camera]: declare AfSpeed with default 0
[DEBUG] [1719912488.019194244] [camera]: declare AfWindows with default [0, 0, 0, 0]
[DEBUG] [1719912488.020062753] [camera]: declare AwbEnable with default not set
[DEBUG] [1719912488.020429824] [camera]: declare LensPosition with default 1.000000
[DEBUG] [1719912488.021250222] [camera]: declare Saturation with default 1.000000
[DEBUG] [1719912488.021968826] [camera]: declare AfMode with default 0
[DEBUG] [1719912488.022721633] [camera]: declare StatsOutputEnable with default false
[DEBUG] [1719912488.023104870] [camera]: declare FrameDurationLimits with default not set
[DEBUG] [1719912488.023620494] [camera]: declare AnalogueGain with default not set
[DEBUG] [1719912488.024314005] [camera]: declare AeMeteringMode with default 0
[WARN] [1719912488.025259810] [camera]: control NoiseReductionMode (10002) not handled
[DEBUG] [1719912488.026060820] [camera]: setting integer parameter AeConstraintMode to 0
[DEBUG] [1719912488.026872016] [camera]: setting integer parameter AeExposureMode to 0
[DEBUG] [1719912488.027275900] [camera]: setting integer parameter AeFlickerMode to 0
[DEBUG] [1719912488.027943727] [camera]: setting integer parameter AeMeteringMode to 0
[DEBUG] [1719912488.028493147] [camera]: setting integer parameter AfMetering to 0
[DEBUG] [1719912488.029159955] [camera]: setting integer parameter AfMode to 0
[DEBUG] [1719912488.029595431] [camera]: setting integer parameter AfPause to 0
[DEBUG] [1719912488.030373849] [camera]: setting integer parameter AfRange to 0
[DEBUG] [1719912488.031135545] [camera]: setting integer parameter AfSpeed to 0
[DEBUG] [1719912488.031816149] [camera]: setting integer parameter AfTrigger to 0
[DEBUG] [1719912488.032466142] [camera]: setting integer_array parameter AfWindows to [0, 0, 0, 0]
[DEBUG] [1719912488.033203949] [camera]: setting integer parameter AwbMode to 0
[DEBUG] [1719912488.033932534] [camera]: setting double parameter Brightness to 0.000000
[DEBUG] [1719912488.034687619] [camera]: setting double parameter Contrast to 1.000000
[DEBUG] [1719912488.035474166] [camera]: setting double parameter ExposureValue to 0.000000
[DEBUG] [1719912488.036151770] [camera]: setting integer parameter HdrMode to 0
[DEBUG] [1719912488.036943947] [camera]: setting double parameter LensPosition to 1.000000
[DEBUG] [1719912488.037700013] [camera]: setting double parameter Saturation to 1.000000
[DEBUG] [1719912488.038425247] [camera]: setting integer_array parameter ScalerCrop to [0, 0, 4608, 2592]
[DEBUG] [1719912488.039236923] [camera]: setting double parameter Sharpness to 1.000000
[DEBUG] [1719912488.040112377] [camera]: setting bool parameter StatsOutputEnable to false
[0:53:35.296972564] [6975] DEBUG V4L2 v4l2_videodevice.cpp:1254 /dev/video21[33:cap]: 4 buffers requested.
[0:53:35.298248458] [6975] DEBUG Buffer framebuffer.cpp:346 Buffer is contiguous
[0:53:35.298656787] [6975] DEBUG Buffer framebuffer.cpp:346 Buffer is contiguous
[0:53:35.298894229] [6975] DEBUG Buffer framebuffer.cpp:346 Buffer is contiguous
[0:53:35.299153689] [6975] DEBUG Buffer framebuffer.cpp:346 Buffer is contiguous
[0:53:35.299270225] [6975] DEBUG V4L2 v4l2_videodevice.cpp:1254 /dev/video21[33:cap]: 0 buffers requested.
[0:53:35.300301436] [6962] DEBUG Request request.cpp:361 Created request - cookie: 0
[0:53:35.300951263] [6962] DEBUG Request request.cpp:361 Created request - cookie: 0
[0:53:35.301078428] [6962] DEBUG Request request.cpp:361 Created request - cookie: 0
[0:53:35.301166464] [6962] DEBUG Request request.cpp:361 Created request - cookie: 0
[New Thread 0x7fcfa0e8e0 (LWP 6978)]
[New Thread 0x7fcf1fe8e0 (LWP 6979)]
[New Thread 0x7fce9ee8e0 (LWP 6980)]
[New Thread 0x7fce1de8e0 (LWP 6981)]
[0:53:35.304819408] [6962] DEBUG Camera camera.cpp:1341 Starting capture
[New Thread 0x7fcd9ce8e0 (LWP 6982)]
[0:53:35.307453565] [6982] DEBUG RPiAf af.cpp:760 setMode: 0
[0:53:35.307594897] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: Brightness = 0.000000
[0:53:35.307778525] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: HdrMode = 0
[0:53:35.307957467] [6982] DEBUG RPiAgc agc.cpp:203 setActiveChannels { 0 }
[0:53:35.308073114] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: AfTrigger = 0
[0:53:35.308111910] [6982]  WARN IPARPI ipa_base.cpp:1167 Could not set AF_TRIGGER - no AF algorithm or not Auto
[0:53:35.308134188] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: AfSpeed = 0
[0:53:35.308249242] [6982] DEBUG RPiAf af.cpp:683 setSpeed: 0
[0:53:35.308323760] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: AeConstraintMode = 0
[0:53:35.308581831] [6982] DEBUG RPiAgc agc.cpp:175 setConstraintMode normal
[0:53:35.308765107] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: AfRange = 0
[0:53:35.308937365] [6982] DEBUG RPiAf af.cpp:676 setRange: 0
[0:53:35.309032253] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: AeMeteringMode = 0
[0:53:35.309302453] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: AfPause = 0
[0:53:35.309395786] [6982]  WARN IPARPI ipa_base.cpp:1150 Could not set AF_PAUSE - no AF algorithm or not Continuous
[0:53:35.309443859] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: Sharpness = 1.000000
[0:53:35.309881688] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: ScalerCrop = (0, 0)/4608x2592
[0:53:35.309985335] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: AeFlickerMode = 0
[0:53:35.310465812] [6982] DEBUG RPiAgc agc.cpp:123 setFlickerPeriod 0.00us
[0:53:35.310748623] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: LensPosition = 1.000000
[0:53:35.310963084] [6982] DEBUG RPiAf af.cpp:723 setLensPosition: 1
[0:53:35.311129231] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: StatsOutputEnable = false
[0:53:35.311264359] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: Saturation = 1.000000
[0:53:35.311415431] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: Contrast = 1.000000
[0:53:35.311537911] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: AfMode = 0
[0:53:35.311592522] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: AfWindows = (0, 0)/0x0
camera_node: ../include/libcamera/controls.h:167: T libcamera::ControlValue::get() const [with T = libcamera::Span<const libcamera::Rectangle>; typename std::enable_if<(libcamera::details::is_span<U>::value || std::is_same<std::__cxx11::basic_string<char>, typename std::remove_cv< <template-parameter-1-1> >::type>::value), std::nullptr_t>::type <anonymous> = nullptr]: Assertion `isArray_' failed.

Thread 20 "camera_node" received signal SIGABRT, Aborted.

of intrest are:

[DEBUG] [1719912488.019194244] [camera]: declare AfWindows with default [0, 0, 0, 0]
[DEBUG] [1719912488.032466142] [camera]: setting integer_array parameter AfWindows to [0, 0, 0, 0]
[0:53:35.311592522] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: AfWindows = (0, 0)/0x0

How is AfWindows = (0, 0)/0x0 to be understood?
0x0 pixels?

I'll take another look at where the rectangle is supposed to come from tonight
I also think it's a conversion error that fails to count a single emement as a Vector

@christianrauch
Copy link
Owner

camera_node: ../include/libcamera/controls.h:167: T libcamera::ControlValue::get() const [with T = libcamera::Span<const libcamera::Rectangle>; typename std::enable_if<(libcamera::details::is_span<U>::value || std::is_same<std::__cxx11::basic_string<char>, typename std::remove_cv< <template-parameter-1-1> >::type>::value), std::nullptr_t>::type <anonymous> = nullptr]: Assertion `isArray_' failed.

Thread 20 "camera_node" received signal SIGABRT, Aborted.

Can you get a backtrace in gdb of this? I would like to see where the assert is and how it is caused.

[DEBUG] [1719912488.019194244] [camera]: declare AfWindows with default [0, 0, 0, 0]
[DEBUG] [1719912488.032466142] [camera]: setting integer_array parameter AfWindows to [0, 0, 0, 0]

Those messages come from the ROS node.

The only usage of AfWindows I can find is in ipa_base.cpp where it is setting the min/max/def control info:

{ &controls::AfWindows, ControlInfo(Rectangle{}, Rectangle(65535, 65535, 65535, 65535), Rectangle{}) },

meaning, minimum and default Rectangle are default constructed and a default constructed Rectangle is initialised with all 0. I think this is causing the assertion, since AfWindows is supposed to be a Span of Rectangle and not just a Rectangle.

[0:53:35.311592522] [6982] DEBUG IPARPI ipa_base.cpp:747 Request ctrl: AfWindows = (0, 0)/0x0

This is then coming from the library.

How is AfWindows = (0, 0)/0x0 to be understood? 0x0 pixels?

Looking at the definition of Rectangle that means that the "top left" coordinate (x,y) and its size are all 0. I guess some sections of the code are supposed to check isNull() and ignore that Rectangle for focus.

@snaens
Copy link

snaens commented Jul 2, 2024

Here's the backtrace:

Thread 20 (Thread 0x7fcdcc68e0 (LWP 332) "camera_node"):
#0  __pthread_kill_implementation (threadid=548913572064, signo=signo@entry=6, no_tid=no_tid@entry=0) at ./nptl/pthread_kill.c:44
#1  0x0000007ff79bf254 in __pthread_kill_internal (signo=6, threadid=<optimized out>) at ./nptl/pthread_kill.c:78
#2  0x0000007ff797a67c in __GI_raise (sig=sig@entry=6) at ../sysdeps/posix/raise.c:26
#3  0x0000007ff7967130 in __GI_abort () at ./stdlib/abort.c:79
#4  0x0000007ff7973fd0 in __assert_fail_base (fmt=0x7ff7a8c550 "%s%s%s:%u: %s%sAssertion `%s' failed.\n%n", assertion=assertion@entry=0x7fe1d4e230 "isArray_", file=file@entry=0x7fe1d4de28 "../include/libcamera/controls.h", line=line@entry=167, function=function@entry=0x7fe1d4e378 "T libcamera::ControlValue::get() const [with T = libcamera::Span<const libcamera::Rectangle>; typename std::enable_if<(libcamera::details::is_span<U>::value || std::is_same<std::__cxx11::basic_string<"...) at ./assert/assert.c:92
#5  0x0000007ff7974040 in __GI___assert_fail (assertion=0x7fe1d4e230 "isArray_", file=0x7fe1d4de28 "../include/libcamera/controls.h", line=167, function=0x7fe1d4e378 "T libcamera::ControlValue::get() const [with T = libcamera::Span<const libcamera::Rectangle>; typename std::enable_if<(libcamera::details::is_span<U>::value || std::is_same<std::__cxx11::basic_string<"...) at ./assert/assert.c:101
#6  0x0000007fe1cd5e64 in libcamera::ControlValue::get<libcamera::Span<libcamera::Rectangle const, 18446744073709551615ul>, decltype(nullptr)>() const (this=0x7fd4047810) at ../include/libcamera/controls.h:167
#7  0x0000007fe1ccc154 in libcamera::ipa::RPi::IpaBase::applyControls (this=0x7fd400a9a0, controls=...) at ../src/ipa/rpi/common/ipa_base.cpp:1143
#8  0x0000007fe1cc829c in libcamera::ipa::RPi::IpaBase::start (this=0x7fd400a9a0, controls=..., result=0x7fe25cd4b0) at ../src/ipa/rpi/common/ipa_base.cpp:279
#9  0x0000007ff5ae09d8 in libcamera::ipa::RPi::IPAProxyRPi::ThreadProxy::start (this=0x7fd4001ce0, controls=..., result=0x7fe25cd4b0) at include/libcamera/ipa/raspberrypi_ipa_proxy.h:209
#10 0x0000007ff5aeaf20 in libcamera::BoundMethodMember<libcamera::ipa::RPi::IPAProxyRPi::ThreadProxy, void, libcamera::ControlList const&, libcamera::ipa::RPi::StartResult*>::invoke (this=0x5555e691c0, args#0=..., args#1=0x7fe25cd4b0) at ../include/libcamera/base/bound_method.h:191
#11 0x0000007ff5aebef0 in libcamera::BoundMethodArgs<void, libcamera::ControlList const&, libcamera::ipa::RPi::StartResult*>::invokePack<0ul, 1ul, void> (this=0x5555e691c0, pack=0x7fd4047490) at ../include/libcamera/base/bound_method.h:115
#12 0x0000007ff5aeae84 in libcamera::BoundMethodArgs<void, libcamera::ControlList const&, libcamera::ipa::RPi::StartResult*>::invokePack (this=0x5555e691c0, pack=0x7fd4047490) at ../include/libcamera/base/bound_method.h:124
#13 0x0000007ff55faadc in libcamera::InvokeMessage::invoke (this=0x7fd40468d0) at ../src/libcamera/base/message.cpp:153
#14 0x0000007ff55fb224 in libcamera::Object::message (this=0x7fd4001ce0, msg=0x7fd40468d0) at ../src/libcamera/base/object.cpp:211
#15 0x0000007ff56023bc in libcamera::Thread::dispatchMessages (this=0x7fd4001cb0, type=libcamera::Message::None) at ../src/libcamera/base/thread.cpp:638
#16 0x0000007ff55eb4cc in libcamera::EventDispatcherPoll::processEvents (this=0x7fc8000ba0) at ../src/libcamera/base/event_dispatcher_poll.cpp:147
#17 0x0000007ff5601854 in libcamera::Thread::exec (this=0x7fd4001cb0) at ../src/libcamera/base/thread.cpp:342
#18 0x0000007ff56018f8 in libcamera::Thread::run (this=0x7fd4001cb0) at ../src/libcamera/base/thread.cpp:369
#19 0x0000007ff56017e0 in libcamera::Thread::startThread (this=0x7fd4001cb0) at ../src/libcamera/base/thread.cpp:320
#20 0x0000007ff56061e8 in std::__invoke_impl<void, void (libcamera::Thread::*)(), libcamera::Thread*> (__f=@0x7fd40471e0: (void (libcamera::Thread::*)(libcamera::Thread * const)) 0x7ff56016e0 <libcamera::Thread::startThread()>, __t=@0x7fd40471d8: 0x7fd4001cb0) at /usr/include/c++/11/bits/invoke.h:74
#21 0x0000007ff5606128 in std::__invoke<void (libcamera::Thread::*)(), libcamera::Thread*> (__fn=@0x7fd40471e0: (void (libcamera::Thread::*)(libcamera::Thread * const)) 0x7ff56016e0 <libcamera::Thread::startThread()>) at /usr/include/c++/11/bits/invoke.h:96
#22 0x0000007ff560608c in std::thread::_Invoker<std::tuple<void (libcamera::Thread::*)(), libcamera::Thread*> >::_M_invoke<0ul, 1ul> (this=0x7fd40471d8) at /usr/include/c++/11/bits/std_thread.h:259
#23 0x0000007ff5606044 in std::thread::_Invoker<std::tuple<void (libcamera::Thread::*)(), libcamera::Thread*> >::operator() (this=0x7fd40471d8) at /usr/include/c++/11/bits/std_thread.h:266
#24 0x0000007ff5606024 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (libcamera::Thread::*)(), libcamera::Thread*> > >::_M_run (this=0x7fd40471d0) at /usr/include/c++/11/bits/std_thread.h:211
#25 0x0000007ff7bf31fc in ?? () from /lib/aarch64-linux-gnu/libstdc++.so.6
#26 0x0000007ff79bd5c8 in start_thread (arg=0x0) at ./nptl/pthread_create.c:442
#27 0x0000007ff7a25edc in thread_start () at ../sysdeps/unix/sysv/linux/aarch64/clone.S:79

@christianrauch
Copy link
Owner

Thanks. So this is happening in af->setWindows(ctrl.second.get<Span<const Rectangle>>()); where it tries to read a Span<const Rectangle> for the single Rectangle that we set from the [0,0,0,0] default. Because the get version for Span expects assert(isArray_); but a single Rectangle is not an array, this fails. Essentially, this breaks because the node is directly setting the default provided by the IPA. I am not sure how this should be handled. I think libcamera should make sure that the defaults have the same type as the Control.

@snaens
Copy link

snaens commented Jul 2, 2024

I believe the error stems from here:

case libcamera::ControlTypeRectangle:
return {libcamera::Rectangle(values[0], values[1], values[2], values[3])};

If I change the conversion to output an array-type (such as libcamera::Span<CTInteger64>) the error is fixed
(As I did a few comments earlier #50 (comment))

Something like this:

  case libcamera::ControlTypeRectangle:
    return {libcamera::Span<const CTInteger64>(values)};

If i am not mistaken, pv_to_cv should output an array-type containing rectangles, not a single rectangle, right?
In principal like so:

return {libcamera::Span<libcamera::Rectangle>(libcamera::Rectangle(values[0], values[1], values[2], values[3]))};

This line is definitely wrong though, this goes waaay beyond my c++ knowledge


So this is happening in af->setWindows(ctrl.second.get<Span>());

precisely, i showed this here #50 (comment)

That gets called coming from this for loop:

libcamera::ControlList controls_ = camera->controls();
for (const auto &[id, value] : parameters)
controls_.set(id, value);

Which already has the incorrect _isArray set in it's parameters.
The source, as I said, seems to be in pv_to_cv

@christianrauch
Copy link
Owner

I believe the error stems from here:

case libcamera::ControlTypeRectangle:
return {libcamera::Rectangle(values[0], values[1], values[2], values[3])};

We are turning in circles here. In the response #50 (comment) I told you that pv_to_cv returns a libcamera::ControlValue which can hold any supported control value (int, float, Rectangle) and spns / arrays of these.

Why are you still thinking that libcamera::ControlValue should only contain spans / arrays?

That gets called coming from this for loop:

libcamera::ControlList controls_ = camera->controls();
for (const auto &[id, value] : parameters)
controls_.set(id, value);

pv_to_cv is returning a single Rectangle because this is the type of the default value. The _isArray is therefore correctly set to false. The problem is that in
https://github.com/raspberrypi/libcamera/blob/6ddd79b5bdbedc1f61007aed35391f1559f9e29a/src/ipa/rpi/common/ipa_base.cpp#L1136-L1145
the function setWindows is expecting a Span<const Rectangle>.

@snaens
Copy link

snaens commented Jul 3, 2024

no, no
AfWindows is an array of rectangles
However, pv_to_cv returns a singular rectangle, which of course isn't an array
From my debugging this is where the error originated

No errors occur immediately, as the ControlValue is first saved in parameters.
That for loop in CameraNode.cpp then uses those values, and then creates the assertion error

@christianrauch
Copy link
Owner

no, no AfWindows is an array of rectangles

The AfWindows Control is of type Span<const Rectangle> but the default value in the ControlInfo that is set by the Raspberry Pi IPA is Rectangle{} (https://github.com/raspberrypi/libcamera/blob/6ddd79b5bdbedc1f61007aed35391f1559f9e29a/src/ipa/rpi/common/ipa_base.cpp#L93).

However, pv_to_cv returns a singular rectangle, which of course isn't an array From my debugging this is where the error originated

True, but this is expected as the conversion is supposed to convert to the type of the original default value. pv_to_cv / pv_to_cv_int_array is trying to convert multiple int to the same type as the default value. In the case of AfWindows, the type of the default value is Rectangle (https://github.com/raspberrypi/libcamera/blob/6ddd79b5bdbedc1f61007aed35391f1559f9e29a/src/ipa/rpi/common/ipa_base.cpp#L93) and not Span<const Rectangle> as the Control.

@snaens
Copy link

snaens commented Jul 3, 2024

Ah, ok, thanks for clarifying!
then it must be further down the line
I'll take another look tomorrow 👍

@christianrauch
Copy link
Owner

I changed the way how the ROS parameter type is determined from the libcamera control id in #15. It should now ignore control ids where the control id itself cannot be converted to a ROS parameter type, independently of the default control value.

Can you check this again please to see if it correctly ignores the AfWindows control? The node should print a warning unsupported control 'AfWindows' in the terminal.

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 a pull request may close this issue.

3 participants