mission_result: remove unused fields

This commit is contained in:
Beat Küng 2022-09-08 21:04:22 +02:00 committed by Daniel Agar
parent 455b885f86
commit ae6377dfa0
4 changed files with 0 additions and 29 deletions

View File

@ -14,9 +14,6 @@ bool warning # true if mission is valid, but has potentially problematic items
bool finished # true if mission has been completed
bool failure # true if the mission cannot continue or be completed for some reason
bool stay_in_failsafe # true if the commander should not switch out of the failsafe mode
bool flight_termination # true if the navigator demands a flight termination from the commander app
bool item_do_jump_changed # true if the number of do jumps remaining has changed
uint16 item_changed_index # indicate which item has changed
uint16 item_do_jump_remaining # set to the number of do jumps remaining for that item

View File

@ -1904,29 +1904,6 @@ void Commander::checkForMissionUpdate()
_user_mode_intention.change(vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER);
}
}
// Check for mission flight termination
if (_arm_state_machine.isArmed() && mission_result.flight_termination &&
!_circuit_breaker_flight_termination_disabled) {
if (!_flight_termination_triggered && !_lockdown_triggered) {
// navigator only requests flight termination on GPS failure
mavlink_log_critical(&_mavlink_log_pub, "GPS failure: Flight terminated\t");
events::send(events::ID("commander_mission_termination"), {events::Log::Alert, events::LogInternal::Warning},
"GPS failure: Flight terminated");
_flight_termination_triggered = true;
_actuator_armed.force_failsafe = true;
_status_changed = true;
send_parachute_command();
}
if (hrt_elapsed_time(&_last_termination_message_sent) > 4_s) {
_last_termination_message_sent = hrt_absolute_time();
mavlink_log_critical(&_mavlink_log_pub, "Flight termination active\t");
events::send(events::ID("commander_mission_termination_active"), {events::Log::Alert, events::LogInternal::Warning},
"Flight termination active");
}
}
}
}

View File

@ -231,7 +231,6 @@ private:
ArmStateMachine _arm_state_machine{};
bool _circuit_breaker_flight_termination_disabled{false};
FailureDetector _failure_detector{this};
bool _flight_termination_triggered{false};
bool _lockdown_triggered{false};

View File

@ -55,8 +55,6 @@ NavigatorMode::run(bool active)
{
if (active) {
if (!_active) {
/* first run, reset stay in failsafe flag */
_navigator->get_mission_result()->stay_in_failsafe = false;
_navigator->set_mission_result_updated();
on_activation();