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/ArduPlane/avoidance_adsb.cpp
Views: 1798
1#include <stdio.h>2#include "Plane.h"34#if HAL_ADSB_ENABLED5void Plane::avoidance_adsb_update(void)6{7adsb.update();8avoidance_adsb.update();9}101112MAV_COLLISION_ACTION AP_Avoidance_Plane::handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action)13{14MAV_COLLISION_ACTION actual_action = requested_action;15bool failsafe_state_change = false;1617// check for changes in failsafe18if (!plane.failsafe.adsb) {19plane.failsafe.adsb = true;20failsafe_state_change = true;21// record flight mode in case it's required for the recovery22prev_control_mode_number = plane.control_mode->mode_number();23}2425// take no action in some flight modes26bool flightmode_prohibits_action = false;27if (plane.control_mode == &plane.mode_manual ||28(plane.control_mode == &plane.mode_auto && !plane.auto_state.takeoff_complete) ||29(plane.flight_stage == AP_FixedWing::FlightStage::LAND) || // TODO: consider allowing action during approach30plane.control_mode == &plane.mode_autotune) {31flightmode_prohibits_action = true;32}33#if HAL_QUADPLANE_ENABLED34if (plane.control_mode == &plane.mode_qland) {35flightmode_prohibits_action = true;36}37#endif38if (flightmode_prohibits_action) {39actual_action = MAV_COLLISION_ACTION_NONE;40}4142// take action based on requested action43switch (actual_action) {4445case MAV_COLLISION_ACTION_RTL:46if (failsafe_state_change) {47plane.set_mode(plane.mode_rtl, ModeReason::AVOIDANCE);48}49break;5051case MAV_COLLISION_ACTION_HOVER:52if (failsafe_state_change) {53#if HAL_QUADPLANE_ENABLED54if (plane.quadplane.is_flying()) {55plane.set_mode(plane.mode_qloiter, ModeReason::AVOIDANCE);56break;57}58#endif59plane.set_mode(plane.mode_loiter, ModeReason::AVOIDANCE);60}61break;6263case MAV_COLLISION_ACTION_ASCEND_OR_DESCEND: {64// climb or descend to avoid obstacle65Location loc = plane.next_WP_loc;66if (handle_avoidance_vertical(obstacle, failsafe_state_change, loc)) {67plane.set_guided_WP(loc);68} else {69actual_action = MAV_COLLISION_ACTION_NONE;70}71break;72}73case MAV_COLLISION_ACTION_MOVE_HORIZONTALLY: {74// move horizontally to avoid obstacle75Location loc = plane.next_WP_loc;76if (handle_avoidance_horizontal(obstacle, failsafe_state_change, loc)) {77plane.set_guided_WP(loc);78} else {79actual_action = MAV_COLLISION_ACTION_NONE;80}81break;82}83case MAV_COLLISION_ACTION_MOVE_PERPENDICULAR:84{85// move horizontally and vertically to avoid obstacle86Location loc = plane.next_WP_loc;87const bool success_vert = handle_avoidance_vertical(obstacle, failsafe_state_change, loc);88const bool success_hor = handle_avoidance_horizontal(obstacle, failsafe_state_change, loc);89if (success_vert || success_hor) {90plane.set_guided_WP(loc);91} else {92actual_action = MAV_COLLISION_ACTION_NONE;93}94}95break;9697// unsupported actions and those that require no response98case MAV_COLLISION_ACTION_NONE:99return actual_action;100case MAV_COLLISION_ACTION_REPORT:101default:102break;103}104105if (failsafe_state_change) {106gcs().send_text(MAV_SEVERITY_ALERT, "Avoid: Performing action: %d", actual_action);107}108109// return with action taken110return actual_action;111}112113void AP_Avoidance_Plane::handle_recovery(RecoveryAction recovery_action)114{115// check we are coming out of failsafe116if (plane.failsafe.adsb) {117plane.failsafe.adsb = false;118gcs().send_text(MAV_SEVERITY_INFO, "Avoid: Resuming with action: %u", (unsigned)recovery_action);119120// restore flight mode if requested and user has not changed mode since121if (plane.control_mode_reason == ModeReason::AVOIDANCE) {122switch (recovery_action) {123124case RecoveryAction::REMAIN_IN_AVOID_ADSB:125// do nothing, we'll stay in the AVOID_ADSB mode which is guided which will loiter126break;127128case RecoveryAction::RESUME_PREVIOUS_FLIGHTMODE:129plane.set_mode_by_number(prev_control_mode_number, ModeReason::AVOIDANCE_RECOVERY);130break;131132case RecoveryAction::RTL:133plane.set_mode(plane.mode_rtl, ModeReason::AVOIDANCE_RECOVERY);134break;135136case RecoveryAction::RESUME_IF_AUTO_ELSE_LOITER:137if (prev_control_mode_number == Mode::Number::AUTO) {138plane.set_mode(plane.mode_auto, ModeReason::AVOIDANCE_RECOVERY);139} else {140// let ModeAvoidADSB continue in its guided141// behaviour, but reset the loiter location,142// rather than where the avoidance location was143plane.set_guided_WP(plane.current_loc);144}145break;146147default:148// user has specified an invalid recovery action;149// loiter where we are150plane.set_guided_WP(plane.current_loc);151break;152} // switch153}154}155}156157// check flight mode is avoid_adsb158bool AP_Avoidance_Plane::check_flightmode(bool allow_mode_change)159{160// ensure plane is in avoid_adsb mode161if (allow_mode_change && plane.control_mode != &plane.mode_avoidADSB) {162plane.set_mode(plane.mode_avoidADSB, ModeReason::AVOIDANCE);163}164165// check flight mode166return (plane.control_mode == &plane.mode_avoidADSB);167}168169bool AP_Avoidance_Plane::handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change, Location &new_loc)170{171// ensure copter is in avoid_adsb mode172if (!check_flightmode(allow_mode_change)) {173return false;174}175176// get best vector away from obstacle177if (plane.current_loc.alt > obstacle->_location.alt) {178// should climb179new_loc.alt = plane.current_loc.alt + 1000; // set alt demand to be 10m above us, climb rate will be TECS_CLMB_MAX180return true;181182} else if (plane.current_loc.alt > plane.g.RTL_altitude*100) {183// should descend while above RTL alt184// TODO: consider using a lower altitude than RTL_altitude since it's default (100m) is quite high185new_loc.alt = plane.current_loc.alt - 1000; // set alt demand to be 10m below us, sink rate will be TECS_SINK_MAX186return true;187}188189return false;190}191192bool AP_Avoidance_Plane::handle_avoidance_horizontal(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change, Location &new_loc)193{194// ensure plane is in avoid_adsb mode195if (!check_flightmode(allow_mode_change)) {196return false;197}198199// get best vector away from obstacle200Vector3f velocity_neu;201if (get_vector_perpendicular(obstacle, velocity_neu)) {202// remove vertical component203velocity_neu.z = 0.0f;204205// check for divide by zero206if (is_zero(velocity_neu.x) && is_zero(velocity_neu.y)) {207return false;208}209210// re-normalize211velocity_neu.normalize();212213// push vector further away.214velocity_neu *= 10000;215216// set target217new_loc.offset(velocity_neu.x, velocity_neu.y);218return true;219}220221// if we got this far we failed to set the new target222return false;223}224225#endif // HAL_ADSB_ENABLED226227228229