Browse Source

AP_L1_Control: wrap_180_cd no longer solely returns floats

mission-4.1.18
Peter Barker 5 years ago committed by Peter Barker
parent
commit
8ee411e998
  1. 2
      libraries/AP_L1_Control/AP_L1_Control.cpp
  2. 2
      libraries/AP_L1_Control/AP_L1_Control.h

2
libraries/AP_L1_Control/AP_L1_Control.cpp

@ -64,7 +64,7 @@ float AP_L1_Control::get_yaw() @@ -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);

2
libraries/AP_L1_Control/AP_L1_Control.h

@ -128,5 +128,5 @@ private: @@ -128,5 +128,5 @@ private:
bool _reverse = false;
float get_yaw();
float get_yaw_sensor();
int32_t get_yaw_sensor() const;
};

Loading…
Cancel
Save