From 3e9f470bfbf2dbc7dcd0b927465934f09fa424aa Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 9 Sep 2019 18:50:53 +1000 Subject: [PATCH] AP_L1_Control: wrap_180_cd no longer solely returns floats --- libraries/AP_L1_Control/AP_L1_Control.cpp | 2 +- libraries/AP_L1_Control/AP_L1_Control.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_L1_Control/AP_L1_Control.cpp b/libraries/AP_L1_Control/AP_L1_Control.cpp index 6faed10461..2664d86466 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.cpp +++ b/libraries/AP_L1_Control/AP_L1_Control.cpp @@ -64,7 +64,7 @@ float AP_L1_Control::get_yaw() /* Wrap AHRS yaw sensor if in reverse - centi-degress */ -float AP_L1_Control::get_yaw_sensor() +int32_t AP_L1_Control::get_yaw_sensor() const { if (_reverse) { return wrap_180_cd(18000 + _ahrs.yaw_sensor); diff --git a/libraries/AP_L1_Control/AP_L1_Control.h b/libraries/AP_L1_Control/AP_L1_Control.h index 8e85cd97f2..458fe98b2b 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.h +++ b/libraries/AP_L1_Control/AP_L1_Control.h @@ -128,5 +128,5 @@ private: bool _reverse = false; float get_yaw(); - float get_yaw_sensor(); + int32_t get_yaw_sensor() const; };