Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AC_PrecLand/AC_PrecLand_StateMachine.cpp
Views: 1798
#include "AC_PrecLand_config.h"12#if AC_PRECLAND_ENABLED34#include <AC_PrecLand/AC_PrecLand.h>5#include "AC_PrecLand_StateMachine.h"6#include <AP_AHRS/AP_AHRS.h>7#include <GCS_MAVLink/GCS.h>89static const float MAX_POS_ERROR_M = 0.75f; // Maximum position error for retry locations10static const uint32_t FAILSAFE_INIT_TIMEOUT_MS = 7000; // Timeout in ms before failsafe measures are started. During this period vehicle is completely stopped to give user the time to take over11static const float RETRY_OFFSET_ALT_M = 1.5f; // This gets added to the altitude of the retry location1213// Initialize the state machine. This is called every time vehicle switches mode14void AC_PrecLand_StateMachine::init()15{16AC_PrecLand *_precland = AP::ac_precland();17if (_precland == nullptr) {18// precland not enabled19return;20}2122if (!_precland->enabled()) {23// precland is not enabled, prec land state machine methods should not be called!24return;25}26// init is only called ONCE per mode change. So in a particular mode we can retry only a finite times.27// The counter will be reset if the statemachine is called from a different mode28_retry_count = 0;29// reset every other statemachine30reset_failed_landing_statemachine();31}3233// Reset the landing statemachines. This needs to be called every time the landing target is back in sight.34// So that if the landing target goes out of sight again, we can start the failed landing procedure back from the beginning stage35void AC_PrecLand_StateMachine::reset_failed_landing_statemachine()36{37landing_target_lost_action = TargetLostAction::INIT;38_retry_state = RetryLanding::INIT;39failsafe_initialized = false;40}4142// Run Prec Land State Machine. During Prec Landing, we might encounter four scenarios:43// 1. We had the target in sight, but have lost it now. 2. We never had the target in sight and user wants to land.44// 3. We have the target in sight and can continue landing. 4. The sensor is out of range45// This method deals with all of these scenarios46// Returns the action needed to be done by the vehicle.47// Parameters: Vector3f "retry_pos_m" is filled with the required location if we need to retry landing.48AC_PrecLand_StateMachine::Status AC_PrecLand_StateMachine::update(Vector3f &retry_pos_m)49{5051// grab the current status of Landing Target52AC_PrecLand *_precland = AP::ac_precland();53if (_precland == nullptr) {54// should never happen55return Status::ERROR;56}5758if (!_precland->enabled()) {59// precland is not enabled, prec land state machine should not be called!60return Status::ERROR;61}6263AC_PrecLand::TargetState precland_target_state = _precland->get_target_state();6465switch (precland_target_state) {66case AC_PrecLand::TargetState::TARGET_RECENTLY_LOST:67// we have lost the target but had it in sight at least once recently68// action will depend on what user wants69return get_target_lost_actions(retry_pos_m);7071case AC_PrecLand::TargetState::TARGET_NEVER_SEEN:72// we have no clue where we are supposed to be landing73// let user decide how strict our failsafe actions need to be74return Status::FAILSAFE;7576case AC_PrecLand::TargetState::TARGET_OUT_OF_RANGE:77// The target isn't in sight, but we can't run any fail safe measures or do landing retry78// Therefore just descend for now, and check again later if retry is allowed79case AC_PrecLand::TargetState::TARGET_FOUND:80// no action required, target is in sight81reset_failed_landing_statemachine();82return Status::DESCEND;83}8485// should never reach here, all values are handled above86return Status::ERROR;87}888990// Target is lost (i.e we had it in sight some time back), this method helps decide on what needs to be done next91// The chosen action depends on user set landing strictness and will be returned by this function92// Parameters: Vector3f "retry_pos_m" is filled with the required location if we need to retry landing.93AC_PrecLand_StateMachine::Status AC_PrecLand_StateMachine::get_target_lost_actions(Vector3f &retry_pos_m)94{95AC_PrecLand *_precland = AP::ac_precland();96if (_precland == nullptr) {97// should never happen98return Status::ERROR;99}100101switch (landing_target_lost_action) {102case TargetLostAction::INIT: {103// figure out how strict the user is with the landing104const RetryStrictness strictness =_precland->get_retry_strictness();105switch (strictness) {106case RetryStrictness::NORMAL:107case RetryStrictness::VERY_STRICT:108// We eventually want to retry landing, but lets descend for some time and hope the target gets in sight109// If not, we will retry landing110landing_target_lost_action = TargetLostAction::DESCEND;111break;112case RetryStrictness::NOT_STRICT:113// User just wants to land, prec land isn't a priority114landing_target_lost_action = TargetLostAction::LAND_VERTICALLY;115break;116}117// at this stage we will be descending no matter what118// so no special action required119return Status::DESCEND;120}121122case TargetLostAction::DESCEND:123if (AP_HAL::millis() - _precland->get_last_valid_target_ms() >=_precland->get_min_retry_time_sec() * 1000) {124// we have descended for some time and the target still isn't in sight125// lets retry126landing_target_lost_action = TargetLostAction::RETRY_LANDING;127_retry_state = RetryLanding::INIT;128}129// still descending, no other action130return Status::DESCEND;131132case TargetLostAction::RETRY_LANDING:133// retry the landing by going to another position134return retry_landing(retry_pos_m);135136case TargetLostAction::LAND_VERTICALLY:137// Just land vertically138// we will not be retrying to any location here on, so return false139return Status::DESCEND;140}141142// should never reach here, all cases are handled above143return Status::ERROR;144}145146// Retry landing based on a previously known location of the landing target147// Returns the action that should be taken by the vehicle148// Vector3f "retry_pos_m" is filled with the required location.149AC_PrecLand_StateMachine::Status AC_PrecLand_StateMachine::retry_landing(Vector3f &retry_pos_m)150{151AC_PrecLand *_precland = AP::ac_precland();152if (_precland == nullptr) {153// should never happen154return Status::ERROR;155}156157if (_precland->get_max_retry_allowed() == 0) {158// user does not want retry159return Status::FAILSAFE;160}161162if (_retry_count > _precland->get_max_retry_allowed()) {163// we have exhausted the amount of times vehicle was allowed to retry landing164// do failsafe measure so the vehicle isn't stuck in a constant loop165return Status::FAILSAFE;166}167168// get the retry position. This depends on what retry behavior has been set by user169Vector3f go_to_pos;170const RetryAction retry_action = _precland->get_retry_behaviour();171if (retry_action == RetryAction::GO_TO_TARGET_LOC) {172_precland->get_last_detected_landing_pos(go_to_pos);173} else if (retry_action == RetryAction::GO_TO_LAST_LOC) {174_precland->get_last_vehicle_pos_when_target_detected(go_to_pos);175}176177// add a little bit offset so the vehicle climbs slightly higher than where it was178// remember this is "D" frame and in meters's179go_to_pos.z -= RETRY_OFFSET_ALT_M;180181switch (_retry_state) {182case RetryLanding::INIT:183// Init the Retry184_retry_count ++;185_retry_state = RetryLanding::IN_PROGRESS;186// inform the user what we are doing187if (_retry_count <= _precland->get_max_retry_allowed()) {188GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Retrying");189}190retry_pos_m = go_to_pos;191return Status::RETRYING;192193case RetryLanding::IN_PROGRESS: {194// continue converging towards the target till we are close by195retry_pos_m = go_to_pos;196Vector3f pos;197if (!AP::ahrs().get_relative_position_NED_origin(pos)) {198return Status::ERROR;199}200const float dist_to_target = (go_to_pos-pos).length();201if ((dist_to_target < MAX_POS_ERROR_M)) {202// we have approx reached landing location previously detected203_retry_state = RetryLanding::DESCEND;204}205return Status::RETRYING;206}207208case RetryLanding::DESCEND: {209// descend a little bit before completing the retry210// This will descend to the original height of where landing target was first detected211Vector3f pos;212if (!AP::ahrs().get_relative_position_NED_origin(pos)) {213return Status::ERROR;214}215// z_target is in "D" frame216const float z_target = go_to_pos.z + RETRY_OFFSET_ALT_M;217retry_pos_m = Vector3f{pos.x, pos.y, z_target};218if (fabsf(pos.z - retry_pos_m.z) < MAX_POS_ERROR_M) {219// we have descended to the original height where we started the climb from220_retry_state = RetryLanding::COMPLETE;221GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Retry Completed");222}223return Status::RETRYING;224}225226case RetryLanding::COMPLETE:227// Vehicle has completed a retry, and most likely the landing location still isn't sight228// we have no choice but to force a failsafe action229return Status::FAILSAFE;230}231232// should never reach here233return Status::ERROR;234}235236// This is only called when the current status of the state machine returns "failsafe" and will return the action that the vehicle should do237// At the moment this method only allows you to stop in air permanently, or land vertically238// Failsafe will only trigger as a last resort239AC_PrecLand_StateMachine::FailSafeAction AC_PrecLand_StateMachine::get_failsafe_actions()240{241AC_PrecLand *_precland = AP::ac_precland();242if (_precland == nullptr) {243// should never happen, just descend244return FailSafeAction::DESCEND;245}246247if (!failsafe_initialized) {248// start the timer249failsafe_start_ms = AP_HAL::millis();250failsafe_initialized = true;251GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PrecLand: Failsafe Measures");252}253254// Depending on the strictness we will either land vertically, wait for some time and then land vertically, not land at all255const RetryStrictness strictness= _precland->get_retry_strictness();256switch (strictness) {257case RetryStrictness::VERY_STRICT:258// user does not want to land on anything but the target259// stop landing (hover)260return FailSafeAction::HOLD_POS;261262case RetryStrictness::NORMAL:263if (AP_HAL::millis() - failsafe_start_ms < FAILSAFE_INIT_TIMEOUT_MS) {264// stop the vehicle for at least a few seconds before descending265// this might give user the chance to take over266// we do not want to be too linent in landing vertically because of the strictness set by the user267return FailSafeAction::HOLD_POS;268}269// land the vehicle vertically270return FailSafeAction::DESCEND;271272case RetryStrictness::NOT_STRICT:273// User wants to prioritize landing over staying in the air274return FailSafeAction::DESCEND;275}276277// should never reach here278return FailSafeAction::DESCEND;279}280281#endif // AC_PRECLAND_ENABLED282283284