Browse Source

Copter: log and notify when manual land repositionning is active

master
Pierre Kancir 6 years ago committed by Randy Mackay
parent
commit
c50eed5e9a
  1. 1
      ArduCopter/defines.h
  2. 3
      ArduCopter/mode.cpp
  3. 3
      ArduCopter/mode_rtl.cpp

1
ArduCopter/defines.h

@ -335,6 +335,7 @@ enum LoggingParameters { @@ -335,6 +335,7 @@ enum LoggingParameters {
#define DATA_WINCH_RATE_CONTROL 70
#define DATA_ZIGZAG_STORE_A 71
#define DATA_ZIGZAG_STORE_B 72
#define DATA_LAND_REPO_ACTIVE 73
// Error message sub systems and error codes
#define ERROR_SUBSYSTEM_MAIN 1

3
ArduCopter/mode.cpp

@ -478,6 +478,9 @@ void Copter::Mode::land_run_horizontal_control() @@ -478,6 +478,9 @@ void Copter::Mode::land_run_horizontal_control()
// record if pilot has overriden roll or pitch
if (!is_zero(target_roll) || !is_zero(target_pitch)) {
if (!ap.land_repo_active) {
copter.Log_Write_Event(DATA_LAND_REPO_ACTIVE);
}
ap.land_repo_active = true;
}
}

3
ArduCopter/mode_rtl.cpp

@ -289,6 +289,9 @@ void Copter::ModeRTL::descent_run() @@ -289,6 +289,9 @@ void Copter::ModeRTL::descent_run()
// record if pilot has overriden roll or pitch
if (!is_zero(target_roll) || !is_zero(target_pitch)) {
if (!ap.land_repo_active) {
copter.Log_Write_Event(DATA_LAND_REPO_ACTIVE);
}
ap.land_repo_active = true;
}
}

Loading…
Cancel
Save