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

Parameter {feature/BalanceRatio} doesn't comply with floating point range. #127

Open
jmtatsch opened this issue Oct 18, 2023 · 2 comments
Open

Comments

@jmtatsch
Copy link

When trying to get my Alvium G1-319c with VimbaX working the following error occurs:

[INFO] [mono_camera_exec-1]: process started with pid [1200797]
[mono_camera_exec-1] [INFO] [1697613333.013449207] [camera]: Parameters loaded
[mono_camera_exec-1] [INFO] [1697613333.043608947] [camera]: [Vimba System]: AVT Vimba System initialized successfully
[mono_camera_exec-1] [INFO] [1697613333.043645734] [camera]: Searching for cameras ...
[mono_camera_exec-1] [INFO] [1697613333.197734071] [camera]: Found camera named Alvium:
[mono_camera_exec-1] [INFO] [1697613333.197776668] [camera]:  - Model Name     : Alvium G1-319c
[mono_camera_exec-1] [INFO] [1697613333.197789216] [camera]:  - Camera ID      : DEV_000A47344617
[mono_camera_exec-1] [INFO] [1697613333.197793857] [camera]:  - Serial Number  : 04W3N
[mono_camera_exec-1] [INFO] [1697613333.197798467] [camera]:  - Interface ID   : enp0s31f6
[mono_camera_exec-1] [INFO] [1697613333.197803280] [camera]:  - Interface type : GigE
[mono_camera_exec-1] [INFO] [1697613333.197808006] [camera]:  - Access type    : Read and write access
[mono_camera_exec-1] [INFO] [1697613333.198205201] [camera]: Trying to open camera by ID: DEV_000A47344617
[mono_camera_exec-1] [INFO] [1697613333.650265648] [camera]: Opened connection to camera named Alvium with ID DEV_000A47344617
[mono_camera_exec-1] [WARN] [1697613335.650740956] [camera]: Feature DeviceTemperatureSelector: value unavailable
[mono_camera_exec-1] 	ERROR Invalid value.
[mono_camera_exec-1] [WARN] [1697613335.650871760] [camera]: Could not get feature GevTimestampTickFrequency
[mono_camera_exec-1] [INFO] [1697613335.669301761] [camera]: Ready to receive frames triggered by Software
[mono_camera_exec-1] [WARN] [1697613335.669371466] [camera]: Feature DeviceTemperatureSelector: value unavailable
[mono_camera_exec-1] 	ERROR Invalid value.
[mono_camera_exec-1] [INFO] [1697613335.690463129] [camera]: Configuring camera:
[mono_camera_exec-1] [INFO] [1697613335.697134292] [camera]:  - AcquisitionFrameRateEnable set to 0
[mono_camera_exec-1] [INFO] [1697613335.699890673] [camera]:  - AcquisitionMode set to Continuous
[mono_camera_exec-1] [INFO] [1697613335.700667675] [camera]:  - AcquisitionStatusSelector set to AcquisitionActive
[mono_camera_exec-1] [WARN] [1697613335.702087643] [camera]: Feature ActionDeviceKey is not readable.
[mono_camera_exec-1] [WARN] [1697613335.702104788] [camera]:  - Tried to set ActionDeviceKey to 0 but the camera used 94741620188288 instead
[mono_camera_exec-1] [INFO] [1697613335.703377700] [camera]:  - ActionGroupKey set to 0
[mono_camera_exec-1] [INFO] [1697613335.705137214] [camera]:  - ActionGroupMask set to 0
[mono_camera_exec-1] [INFO] [1697613335.705744584] [camera]:  - ActionSelector set to 0
[mono_camera_exec-1] [INFO] [1697613335.708584453] [camera]:  - AdaptiveNoiseSuppressionFactor set to 1
[mono_camera_exec-1] [INFO] [1697613335.712210351] [camera]:  - AutoModeRegionHeight set to 770
[mono_camera_exec-1] [INFO] [1697613335.716811827] [camera]:  - AutoModeRegionOffsetX set to 0
[mono_camera_exec-1] [INFO] [1697613335.720914623] [camera]:  - AutoModeRegionOffsetY set to 388
[mono_camera_exec-1] [INFO] [1697613335.721224537] [camera]:  - AutoModeRegionSelector set to AutoModeRegion1
[mono_camera_exec-1] [INFO] [1697613335.724907148] [camera]:  - AutoModeRegionWidth set to 2064
[mono_camera_exec-1] terminate called after throwing an instance of 'rclcpp::exceptions::InvalidParameterValueException'
[mono_camera_exec-1]   what():  parameter 'feature/BalanceRatio' could not be set: Parameter {feature/BalanceRatio} doesn't comply with floating point range.
[ERROR] [mono_camera_exec-1]: process has died [pid 1200797, exit code -6, cmd '/opt/ros/iron/lib/avt_vimba_camera/mono_camera_exec --ros-args -r __node:=camera --params-file /tmp/launch_params_ix354pz1 --params-file /tmp/launch_params_ulgps_3z --params-file /tmp/launch_params_faya3s9p --params-file /tmp/launch_params_myyyw841 --params-file /tmp/launch_params_6fjqytwk --params-file /tmp/launch_params_6pqvw80r --params-file /tmp/launch_params_77bacti0 --params-file /opt/ros/iron/share/avt_vimba_camera/config/Mako_G-319.yaml'].

In the config file
/opt/ros/iron/share/avt_vimba_camera/config/Mako_G-319.yaml
there is no mention of feature/BalanceRatio only

feature/BalanceRatioAbs: 2.33
feature/BalanceRatioSelector: Red

According to Alvium Features Reference BalanceRatio should be supported and be a float

Can someone please give me a hint?

@jmtatsch
Copy link
Author

jmtatsch commented Oct 19, 2023

Tried with VimbaX and Vimba 6.0. Same.
Tried removing params completely. Same.
Tried setting feature/BalanceRatio: 2.33 (float and within allowed range) Same.
If I set an integer it complains about:
parameter 'feature/BalanceRatio' has invalid type: Wrong parameter type, parameter {feature/BalanceRatio} is of type {double}, setting it to {int} is not allowed.
This seems to hint that there is a double expected instead of a float. How can I set a parameter explicitly as double?

@icolwell-as
Copy link
Member

Hi @jmtatsch, for the ROS2 driver, we were able to do something kinda fancy with ROS2 parameters.
We loop over all the "features" provided by the camera and create ROS2 params automatically.

Based on this:

Parameter {feature/BalanceRatio} doesn't comply with floating point range.

I'm guessing the parameter reported by the camera firmware falls outside of the range that the camera also reports.
See the code here:
https://github.com/astuff/avt_vimba_camera/blob/ros2_master/avt_vimba_camera/src/avt_vimba_camera.cpp#L810-L818

If you add some debug prints to print out the min, max, and initial value, then I'm willing to bet the camera is telling us the initial value is outside the min/max range.

Maybe a bug in the camera's firmware?
If you set the 'feature/BalanceRatio' values from Vimba viewer, save them to the camera, then close vimba viewer and launch the ROS node, does it work?

We should add a check to the code to catch this scenario and Error out with a better msg.

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

No branches or pull requests

2 participants