mirror of https://github.com/ArduPilot/ardupilot
AP_L1_Control: Add missing const in member functions
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
dc6f5aec92
commit
d006012cee
|
@ -53,7 +53,7 @@ const AP_Param::GroupInfo AP_L1_Control::var_info[] = {
|
|||
/*
|
||||
Wrap AHRS yaw if in reverse - radians
|
||||
*/
|
||||
float AP_L1_Control::get_yaw()
|
||||
float AP_L1_Control::get_yaw() const
|
||||
{
|
||||
if (_reverse) {
|
||||
return wrap_PI(M_PI + _ahrs.yaw);
|
||||
|
|
|
@ -127,6 +127,6 @@ private:
|
|||
AP_Float _loiter_bank_limit;
|
||||
|
||||
bool _reverse = false;
|
||||
float get_yaw();
|
||||
float get_yaw() const;
|
||||
int32_t get_yaw_sensor() const;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue