mirror of https://github.com/ArduPilot/ardupilot
AP_L1_Control: wrap_180_cd no longer solely returns floats
This commit is contained in:
parent
7c2c809b06
commit
3e9f470bfb
|
@ -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);
|
||||
|
|
|
@ -128,5 +128,5 @@ private:
|
|||
|
||||
bool _reverse = false;
|
||||
float get_yaw();
|
||||
float get_yaw_sensor();
|
||||
int32_t get_yaw_sensor() const;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue