Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
42 changes: 22 additions & 20 deletions ArduCopter/AP_Arming_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -354,15 +354,16 @@ bool AP_Arming_Copter::rc_calibration_checks(bool display_failure)
// performs pre_arm gps related checks and returns true if passed
bool AP_Arming_Copter::gps_checks(bool display_failure)
{
// check if fence requires GPS
bool fence_requires_gps = false;
// check if fence requires position
bool fence_requires_position = false;
#if AP_FENCE_ENABLED
// if circular or polygon fence is enabled we need GPS
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
// if circular or polygon fence is enabled we need position
fence_requires_position = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
#endif

// check if flight mode requires GPS
bool mode_requires_gps = copter.flightmode->requires_GPS() || fence_requires_gps || (copter.simple_mode == Copter::SimpleMode::SUPERSIMPLE);
const bool mode_requires_position = copter.flightmode->requires_position() || fence_requires_position || (copter.simple_mode == Copter::SimpleMode::SUPERSIMPLE);
const bool mode_requires_gps = AP::ahrs().using_gps() && mode_requires_position;

// call parent gps checks
if (mode_requires_gps) {
Expand All @@ -372,8 +373,8 @@ bool AP_Arming_Copter::gps_checks(bool display_failure)
}
}

// run mandatory gps checks first
if (!mandatory_gps_checks(display_failure)) {
// run mandatory position checks first
if (!mandatory_position_checks(display_failure)) {
AP_Notify::flags.pre_arm_gps_check = false;
return false;
}
Expand Down Expand Up @@ -439,34 +440,34 @@ bool AP_Arming_Copter::proximity_checks(bool display_failure) const
}
#endif // HAL_PROXIMITY_ENABLED

// performs mandatory gps checks. returns true if passed
bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
// performs mandatory position checks. returns true if passed
bool AP_Arming_Copter::mandatory_position_checks(bool display_failure)
{
// check if flight mode requires GPS
bool mode_requires_gps = copter.flightmode->requires_GPS();
// check if flight mode requires position
bool mode_requires_position = copter.flightmode->requires_position();

// always check if inertial nav has started and is ready
const auto &ahrs = AP::ahrs();
char failure_msg[100] = {};
if (!ahrs.pre_arm_check(mode_requires_gps, failure_msg, sizeof(failure_msg))) {
if (!ahrs.pre_arm_check(mode_requires_position, failure_msg, sizeof(failure_msg))) {
check_failed(display_failure, "AHRS: %s", failure_msg);
return false;
}

// check if fence requires GPS
bool fence_requires_gps = false;
// check if fence requires position estimate
bool fence_requires_position = false;
#if AP_FENCE_ENABLED
// if circular or polygon fence is enabled we need GPS
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
// if circular or polygon fence is enabled we need position estimate
fence_requires_position = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
#endif

if (mode_requires_gps || require_location == RequireLocation::YES) {
if (mode_requires_position || require_location == RequireLocation::YES) {
if (!copter.position_ok()) {
// vehicle level position estimate checks
check_failed(display_failure, "Need Position Estimate");
return false;
}
} else if (fence_requires_gps) {
} else if (fence_requires_position) {
if (!copter.position_ok()) {
// clarify to user why they need GPS in non-GPS flight mode
check_failed(display_failure, "Fence enabled, need position estimate");
Expand All @@ -478,6 +479,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
}

// check for GPS glitch (as reported by EKF)
// this can only be true if the EKF is using the GPS
nav_filter_status filt_status;
if (ahrs.get_filter_status(filt_status)) {
if (filt_status.flags.gps_glitching) {
Expand Down Expand Up @@ -650,8 +652,8 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
// mandatory checks that will be run if ARMING_SKIPCHK skips all or arming forced
bool AP_Arming_Copter::mandatory_checks(bool display_failure)
{
// call mandatory gps checks and update notify status because regular gps checks will not run
bool result = mandatory_gps_checks(display_failure);
// call mandatory position checks and update notify status because regular position checks will not run
bool result = mandatory_position_checks(display_failure);
AP_Notify::flags.pre_arm_gps_check = result;

// call mandatory alt check
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/AP_Arming_Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ class AP_Arming_Copter : public AP_Arming
// NOTE! the following check functions *DO NOT* call into AP_Arming!
bool parameter_checks(bool display_failure);
bool oa_checks(bool display_failure);
bool mandatory_gps_checks(bool display_failure);
bool mandatory_position_checks(bool display_failure);
bool gcs_failsafe_check(bool display_failure);
bool winch_checks(bool display_failure) const;
bool alt_checks(bool display_failure);
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -691,7 +691,7 @@ void Copter::ten_hz_logging_loop()
if (should_log(MASK_LOG_RCOUT)) {
logger.Write_RCOUT();
}
if (should_log(MASK_LOG_NTUN) && (flightmode->requires_GPS() || landing_with_GPS() || !flightmode->has_manual_throttle())) {
if (should_log(MASK_LOG_NTUN) && (flightmode->requires_position() || landing_with_GPS() || !flightmode->has_manual_throttle())) {
pos_control->write_log();
}
if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ void Copter::Log_Write_PIDS()
logger.Write_PID(LOG_PIDP_MSG, attitude_control->get_rate_pitch_pid().get_pid_info());
logger.Write_PID(LOG_PIDY_MSG, attitude_control->get_rate_yaw_pid().get_pid_info());
logger.Write_PID(LOG_PIDA_MSG, pos_control->D_get_accel_pid().get_pid_info() );
if (should_log(MASK_LOG_NTUN) && (flightmode->requires_GPS() || landing_with_GPS())) {
if (should_log(MASK_LOG_NTUN) && (flightmode->requires_position() || landing_with_GPS())) {
logger.Write_PID(LOG_PIDN_MSG, pos_control->NE_get_vel_pid().get_pid_info_x());
logger.Write_PID(LOG_PIDE_MSG, pos_control->NE_get_vel_pid().get_pid_info_y());
}
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/ekf_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,7 @@ void Copter::failsafe_ekf_event()
}

// does this mode require position?
const bool no_action_in_current_mode = !copter.flightmode->requires_GPS() && (g.fs_ekf_action != FS_EKF_ACTION_LAND_EVEN_STABILIZE);
const bool no_action_in_current_mode = !copter.flightmode->requires_position() && (g.fs_ekf_action != FS_EKF_ACTION_LAND_EVEN_STABILIZE);

if (report_only || landing_with_position || no_action_in_current_mode) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "EKF Failsafe");
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -367,7 +367,7 @@ void Copter::failsafe_deadreckon_check()
failsafe.deadreckon = ekf_dead_reckoning;

// only take action in modes requiring position estimate
if (failsafe.deadreckon && copter.flightmode->requires_GPS()) {
if (failsafe.deadreckon && copter.flightmode->requires_position()) {

// log error
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_DEADRECKON, LogErrorCode::FAILSAFE_OCCURRED);
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -302,7 +302,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
#endif

if (!ignore_checks &&
new_flightmode->requires_GPS() &&
new_flightmode->requires_position() &&
!copter.position_ok()) {
mode_change_failed(new_flightmode, "requires position");
return false;
Expand Down
52 changes: 26 additions & 26 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,7 @@ class Mode {
}
virtual void exit() {};
virtual void run() = 0;
virtual bool requires_GPS() const = 0;
virtual bool requires_position() const = 0;
virtual bool has_manual_throttle() const = 0;
virtual bool allows_arming(AP_Arming::Method method) const = 0;
virtual bool is_autopilot() const = 0;
Expand Down Expand Up @@ -446,7 +446,7 @@ class ModeAcro : public Mode {

virtual void run() override;

bool requires_GPS() const override { return false; }
bool requires_position() const override { return false; }
bool has_manual_throttle() const override { return true; }
bool allows_arming(AP_Arming::Method method) const override { return true; };
bool is_autopilot() const override { return false; }
Expand Down Expand Up @@ -502,7 +502,7 @@ class ModeAltHold : public Mode {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return false; }
bool requires_position() const override { return false; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return true; };
bool is_autopilot() const override { return false; }
Expand Down Expand Up @@ -538,7 +538,7 @@ class ModeAuto : public Mode {
void exit() override;
void run() override;

bool requires_GPS() const override;
bool requires_position() const override;
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override;
bool is_autopilot() const override { return true; }
Expand Down Expand Up @@ -848,7 +848,7 @@ class ModeAutoTune : public Mode {
void exit() override;
void run() override;

bool requires_GPS() const override { return false; }
bool requires_position() const override { return false; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return false; }
bool is_autopilot() const override { return false; }
Expand All @@ -873,7 +873,7 @@ class ModeBrake : public Mode {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return true; }
bool requires_position() const override { return true; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return false; };
bool is_autopilot() const override { return true; }
Expand Down Expand Up @@ -903,7 +903,7 @@ class ModeCircle : public Mode {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return true; }
bool requires_position() const override { return true; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return false; };
bool is_autopilot() const override { return true; }
Expand Down Expand Up @@ -933,7 +933,7 @@ class ModeDrift : public Mode {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return true; }
bool requires_position() const override { return true; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return true; };
bool is_autopilot() const override { return false; }
Expand Down Expand Up @@ -961,7 +961,7 @@ class ModeFlip : public Mode {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return false; }
bool requires_position() const override { return false; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return false; };
bool is_autopilot() const override { return false; }
Expand Down Expand Up @@ -1008,7 +1008,7 @@ class ModeFlowHold : public Mode {
bool init(bool ignore_checks) override;
void run(void) override;

bool requires_GPS() const override { return false; }
bool requires_position() const override { return false; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return true; };
bool is_autopilot() const override { return false; }
Expand Down Expand Up @@ -1096,7 +1096,7 @@ class ModeGuided : public Mode {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return true; }
bool requires_position() const override { return true; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override;
bool is_autopilot() const override { return true; }
Expand Down Expand Up @@ -1273,7 +1273,7 @@ class ModeGuidedNoGPS : public ModeGuided {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return false; }
bool requires_position() const override { return false; }
bool has_manual_throttle() const override { return false; }
bool is_autopilot() const override { return true; }

Expand All @@ -1297,7 +1297,7 @@ class ModeLand : public Mode {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return false; }
bool requires_position() const override { return false; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return false; };
bool is_autopilot() const override { return true; }
Expand Down Expand Up @@ -1358,7 +1358,7 @@ class ModeLoiter : public Mode {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return true; }
bool requires_position() const override { return true; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return true; };
bool is_autopilot() const override { return false; }
Expand Down Expand Up @@ -1408,7 +1408,7 @@ class ModePosHold : public Mode {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return true; }
bool requires_position() const override { return true; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return true; };
bool is_autopilot() const override { return false; }
Expand Down Expand Up @@ -1496,7 +1496,7 @@ class ModeRTL : public Mode {
}
void run(bool disarm_on_land);

bool requires_GPS() const override { return true; }
bool requires_position() const override { return true; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return false; };
bool is_autopilot() const override { return true; }
Expand Down Expand Up @@ -1630,7 +1630,7 @@ class ModeSmartRTL : public ModeRTL {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return true; }
bool requires_position() const override { return true; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return false; }
bool is_autopilot() const override { return true; }
Expand Down Expand Up @@ -1690,7 +1690,7 @@ class ModeSport : public Mode {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return false; }
bool requires_position() const override { return false; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return true; };
bool is_autopilot() const override { return false; }
Expand All @@ -1717,7 +1717,7 @@ class ModeStabilize : public Mode {

virtual void run() override;

bool requires_GPS() const override { return false; }
bool requires_position() const override { return false; }
bool has_manual_throttle() const override { return true; }
bool allows_arming(AP_Arming::Method method) const override { return true; };
bool is_autopilot() const override { return false; }
Expand Down Expand Up @@ -1765,7 +1765,7 @@ class ModeSystemId : public Mode {
void run() override;
void exit() override;

bool requires_GPS() const override { return false; }
bool requires_position() const override { return false; }
bool has_manual_throttle() const override { return true; }
bool allows_arming(AP_Arming::Method method) const override { return false; };
bool is_autopilot() const override { return false; }
Expand Down Expand Up @@ -1844,7 +1844,7 @@ class ModeThrow : public Mode {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return true; }
bool requires_position() const override { return true; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return true; };
bool is_autopilot() const override { return false; }
Expand Down Expand Up @@ -1902,7 +1902,7 @@ class ModeTurtle : public Mode {
void run() override;
void exit() override;

bool requires_GPS() const override { return false; }
bool requires_position() const override { return false; }
bool has_manual_throttle() const override { return true; }
bool allows_arming(AP_Arming::Method method) const override;
bool is_autopilot() const override { return false; }
Expand Down Expand Up @@ -1941,7 +1941,7 @@ class ModeAvoidADSB : public ModeGuided {
bool init(bool ignore_checks) override;
void run() override;

bool requires_GPS() const override { return true; }
bool requires_position() const override { return true; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return false; }
bool is_autopilot() const override { return true; }
Expand Down Expand Up @@ -1971,7 +1971,7 @@ class ModeFollow : public ModeGuided {
void exit() override;
void run() override;

bool requires_GPS() const override { return true; }
bool requires_position() const override { return true; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return false; }
bool is_autopilot() const override { return true; }
Expand Down Expand Up @@ -2020,7 +2020,7 @@ class ModeZigZag : public Mode {
void suspend_auto();
void init_auto();

bool requires_GPS() const override { return true; }
bool requires_position() const override { return true; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return true; }
bool is_autopilot() const override { return true; }
Expand Down Expand Up @@ -2100,7 +2100,7 @@ class ModeAutorotate : public Mode {
void run() override;

bool is_autopilot() const override { return true; }
bool requires_GPS() const override { return false; }
bool requires_position() const override { return false; }
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return false; };

Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,7 @@ void ModeAuto::run()
}

// return true if a position estimate is required
bool ModeAuto::requires_GPS() const
bool ModeAuto::requires_position() const
{
// position estimate is required in all sub modes except attitude control
return _mode != SubMode::NAV_ATTITUDE_TIME;
Expand Down
Loading
Loading