From 6cfe7d5f34965be89f6bc3758cc0dae4a12a76ac Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 4 Apr 2019 16:41:22 +1100 Subject: [PATCH] AP_Beacon: add floating-point-constant designators --- libraries/AP_Beacon/AP_Beacon_SITL.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Beacon/AP_Beacon_SITL.cpp b/libraries/AP_Beacon/AP_Beacon_SITL.cpp index 66ee4d79f8..33c602f1ba 100644 --- a/libraries/AP_Beacon/AP_Beacon_SITL.cpp +++ b/libraries/AP_Beacon/AP_Beacon_SITL.cpp @@ -66,15 +66,15 @@ void AP_Beacon_SITL::update(void) // truth location of the flight vehicle Location current_loc; - current_loc.lat = sitl->state.latitude * 1.0e7; - current_loc.lng = sitl->state.longitude * 1.0e7; - current_loc.alt = sitl->state.altitude * 1.0e2; + current_loc.lat = sitl->state.latitude * 1.0e7f; + current_loc.lng = sitl->state.longitude * 1.0e7f; + current_loc.alt = sitl->state.altitude * 1.0e2f; // where the beacon system origin is located Location beacon_origin; - beacon_origin.lat = get_beacon_origin_lat() * 1.0e7; - beacon_origin.lng = get_beacon_origin_lon() * 1.0e7; - beacon_origin.alt = get_beacon_origin_alt() * 1.0e2; + beacon_origin.lat = get_beacon_origin_lat() * 1.0e7f; + beacon_origin.lng = get_beacon_origin_lon() * 1.0e7f; + beacon_origin.alt = get_beacon_origin_alt() * 1.0e2f; // position of each beacon Location beacon_loc = beacon_origin;