mirror of https://github.com/ArduPilot/ardupilot
Copter: mark position_ok methods as const
This commit is contained in:
parent
c8353c1c13
commit
05925b57ad
|
@ -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();
|
||||
|
|
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue