mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Copter: log and notify when manual land repositionning is active
This commit is contained in:
parent
e5fa728a28
commit
c50eed5e9a
@ -335,6 +335,7 @@ enum LoggingParameters {
|
|||||||
#define DATA_WINCH_RATE_CONTROL 70
|
#define DATA_WINCH_RATE_CONTROL 70
|
||||||
#define DATA_ZIGZAG_STORE_A 71
|
#define DATA_ZIGZAG_STORE_A 71
|
||||||
#define DATA_ZIGZAG_STORE_B 72
|
#define DATA_ZIGZAG_STORE_B 72
|
||||||
|
#define DATA_LAND_REPO_ACTIVE 73
|
||||||
|
|
||||||
// Error message sub systems and error codes
|
// Error message sub systems and error codes
|
||||||
#define ERROR_SUBSYSTEM_MAIN 1
|
#define ERROR_SUBSYSTEM_MAIN 1
|
||||||
|
@ -478,6 +478,9 @@ void Copter::Mode::land_run_horizontal_control()
|
|||||||
|
|
||||||
// record if pilot has overriden roll or pitch
|
// record if pilot has overriden roll or pitch
|
||||||
if (!is_zero(target_roll) || !is_zero(target_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;
|
ap.land_repo_active = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -289,6 +289,9 @@ void Copter::ModeRTL::descent_run()
|
|||||||
|
|
||||||
// record if pilot has overriden roll or pitch
|
// record if pilot has overriden roll or pitch
|
||||||
if (!is_zero(target_roll) || !is_zero(target_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;
|
ap.land_repo_active = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user