diff --git a/libraries/AP_Camera/AP_Camera_Backend.cpp b/libraries/AP_Camera/AP_Camera_Backend.cpp index 40731a6385ed4..516d418684bef 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.cpp +++ b/libraries/AP_Camera/AP_Camera_Backend.cpp @@ -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