Skip to content

Commit

Permalink
AP_Mount: use NaN in place of 0 for camera information message
Browse files Browse the repository at this point in the history
Co-authored-by: muramura <[email protected]>
  • Loading branch information
peterbarker and muramura committed Sep 26, 2024
1 parent 06b763c commit decf484
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 6 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_Mount/AP_Mount_Siyi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Mount/AP_Mount_Topotek.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Mount/AP_Mount_Viewpro.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down

0 comments on commit decf484

Please sign in to comment.