mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mount: use NaN in place of 0 for camera information message
Co-authored-by: muramura <ma2maru@gmail.com>
This commit is contained in:
parent
06b763ca94
commit
decf484702
@ -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
|
||||
|
@ -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
|
||||
|
@ -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)
|
||||
|
Loading…
Reference in New Issue
Block a user