From decf484702be14f10b9b4402091c323e9be69092 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Sep 2024 20:39:03 +1000 Subject: [PATCH] AP_Mount: use NaN in place of 0 for camera information message Co-authored-by: muramura --- libraries/AP_Mount/AP_Mount_Siyi.cpp | 4 ++-- libraries/AP_Mount/AP_Mount_Topotek.cpp | 4 ++-- libraries/AP_Mount/AP_Mount_Viewpro.cpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index 33e3534d59..d0e82cd503 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -1092,8 +1092,8 @@ void AP_Mount_Siyi::send_camera_information(mavlink_channel_t chan) const model_name, // model_name uint8_t[32] fw_version, // firmware version uint32_t focal_length_mm, // focal_length float (mm) - 0, // sensor_size_h float (mm) - 0, // sensor_size_v float (mm) + NaNf, // sensor_size_h float (mm) + NaNf, // sensor_size_v float (mm) 0, // resolution_h uint16_t (pix) 0, // resolution_v uint16_t (pix) 0, // lens_id uint8_t diff --git a/libraries/AP_Mount/AP_Mount_Topotek.cpp b/libraries/AP_Mount/AP_Mount_Topotek.cpp index d8992b4876..09682a8429 100755 --- a/libraries/AP_Mount/AP_Mount_Topotek.cpp +++ b/libraries/AP_Mount/AP_Mount_Topotek.cpp @@ -547,8 +547,8 @@ void AP_Mount_Topotek::send_camera_information(mavlink_channel_t chan) const model_name, // model_name uint8_t[32] _firmware_ver, // firmware version uint32_t 0, // focal_length float (mm) - 0, // sensor_size_h float (mm) - 0, // sensor_size_v float (mm) + NaNf, // sensor_size_h float (mm) + NaNf, // sensor_size_v float (mm) 0, // resolution_h uint16_t (pix) 0, // resolution_v uint16_t (pix) 0, // lens_id uint8_t diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.cpp b/libraries/AP_Mount/AP_Mount_Viewpro.cpp index c95abd03b9..f9b06f3b80 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.cpp +++ b/libraries/AP_Mount/AP_Mount_Viewpro.cpp @@ -920,8 +920,8 @@ void AP_Mount_Viewpro::send_camera_information(mavlink_channel_t chan) const vendor_name, // vendor_name uint8_t[32] _model_name, // model_name uint8_t[32] _firmware_version, // firmware version uint32_t - 0, // focal_length float (mm) - 0, // sensor_size_h float (mm) + NaNf, // sensor_size_h float (mm) + NaNf, // sensor_size_v float (mm) 0, // sensor_size_v float (mm) 0, // resolution_h uint16_t (pix) 0, // resolution_v uint16_t (pix)