mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Camera: fix altitude units in CAMERA_FOV_STATUS
This commit is contained in:
parent
b6426516b8
commit
078a86ad96
@ -280,10 +280,10 @@ void AP_Camera_Backend::send_camera_fov_status(mavlink_channel_t chan) const
|
||||
AP_HAL::millis(),
|
||||
loc.lat,
|
||||
loc.lng,
|
||||
loc.alt,
|
||||
loc.alt * 10,
|
||||
poi_loc.lat,
|
||||
poi_loc.lng,
|
||||
poi_loc.alt,
|
||||
poi_loc.alt * 10,
|
||||
quat_array,
|
||||
horizontal_fov() > 0 ? horizontal_fov() : NaN,
|
||||
vertical_fov() > 0 ? vertical_fov() : NaN
|
||||
|
Loading…
Reference in New Issue
Block a user