mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_L1_Control: wrap_180_cd no longer solely returns floats
This commit is contained in:
parent
7fbaea7971
commit
8ee411e998
@ -64,7 +64,7 @@ float AP_L1_Control::get_yaw()
|
|||||||
/*
|
/*
|
||||||
Wrap AHRS yaw sensor if in reverse - centi-degress
|
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) {
|
if (_reverse) {
|
||||||
return wrap_180_cd(18000 + _ahrs.yaw_sensor);
|
return wrap_180_cd(18000 + _ahrs.yaw_sensor);
|
||||||
|
@ -128,5 +128,5 @@ private:
|
|||||||
|
|
||||||
bool _reverse = false;
|
bool _reverse = false;
|
||||||
float get_yaw();
|
float get_yaw();
|
||||||
float get_yaw_sensor();
|
int32_t get_yaw_sensor() const;
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user