Skip to content

Commit

Permalink
AP_Camera: fix altitude units in CAMERA_FOV_STATUS
Browse files Browse the repository at this point in the history
  • Loading branch information
robertlong13 authored and tridge committed Aug 7, 2024
1 parent b642651 commit 078a86a
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_Camera/AP_Camera_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit 078a86a

Please sign in to comment.