From 05925b57ad86f6de13a01bec5ec2fda3c767895f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 5 Jul 2019 10:12:57 +1000 Subject: [PATCH] Copter: mark position_ok methods as const --- ArduCopter/Copter.h | 6 +++--- ArduCopter/system.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 24a29a6446..07cb35bc91 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -839,9 +839,9 @@ private: // system.cpp void init_ardupilot(); void startup_INS_ground(); - bool position_ok(); - bool ekf_position_ok(); - bool optflow_position_ok(); + bool position_ok() const; + bool ekf_position_ok() const; + bool optflow_position_ok() const; void update_auto_armed(); bool should_log(uint32_t mask); MAV_TYPE get_frame_mav_type(); diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index e45cbb908b..0e12045a48 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -272,7 +272,7 @@ void Copter::startup_INS_ground() } // position_ok - returns true if the horizontal absolute position is ok and home position is set -bool Copter::position_ok() +bool Copter::position_ok() const { // return false if ekf failsafe has triggered if (failsafe.ekf) { @@ -284,7 +284,7 @@ bool Copter::position_ok() } // ekf_position_ok - returns true if the ekf claims it's horizontal absolute position estimate is ok and home position is set -bool Copter::ekf_position_ok() +bool Copter::ekf_position_ok() const { if (!ahrs.have_inertial_nav()) { // do not allow navigation with dcm position @@ -304,7 +304,7 @@ bool Copter::ekf_position_ok() } // optflow_position_ok - returns true if optical flow based position estimate is ok -bool Copter::optflow_position_ok() +bool Copter::optflow_position_ok() const { #if OPTFLOW != ENABLED && VISUAL_ODOMETRY_ENABLED != ENABLED return false;