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/ArduCopter/avoidance_adsb.cpp
Views: 1798
#include "Copter.h"1#include <AP_Notify/AP_Notify.h>23#if HAL_ADSB_ENABLED4void Copter::avoidance_adsb_update(void)5{6adsb.update();7avoidance_adsb.update();8}910#include <stdio.h>1112MAV_COLLISION_ACTION AP_Avoidance_Copter::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 (!copter.failsafe.adsb) {19copter.failsafe.adsb = true;20failsafe_state_change = true;21// record flight mode in case it's required for the recovery22prev_control_mode = copter.flightmode->mode_number();23}2425// take no action in some flight modes26if (copter.flightmode->mode_number() == Mode::Number::LAND ||27#if MODE_THROW_ENABLED28copter.flightmode->mode_number() == Mode::Number::THROW ||29#endif30copter.flightmode->mode_number() == Mode::Number::FLIP) {31actual_action = MAV_COLLISION_ACTION_NONE;32}3334// if landed and we will take some kind of action, just disarm35if ((actual_action > MAV_COLLISION_ACTION_REPORT) && copter.should_disarm_on_failsafe()) {36copter.arming.disarm(AP_Arming::Method::ADSBCOLLISIONACTION);37actual_action = MAV_COLLISION_ACTION_NONE;38} else {3940// take action based on requested action41switch (actual_action) {4243case MAV_COLLISION_ACTION_RTL:44// attempt to switch to RTL, if this fails (i.e. flying in manual mode with bad position) do nothing45if (failsafe_state_change) {46if (!copter.set_mode(Mode::Number::RTL, ModeReason::AVOIDANCE)) {47actual_action = MAV_COLLISION_ACTION_NONE;48}49}50break;5152case MAV_COLLISION_ACTION_HOVER:53// attempt to switch to Loiter, if this fails (i.e. flying in manual mode with bad position) do nothing54if (failsafe_state_change) {55if (!copter.set_mode(Mode::Number::LOITER, ModeReason::AVOIDANCE)) {56actual_action = MAV_COLLISION_ACTION_NONE;57}58}59break;6061case MAV_COLLISION_ACTION_ASCEND_OR_DESCEND:62// climb or descend to avoid obstacle63if (!handle_avoidance_vertical(obstacle, failsafe_state_change)) {64actual_action = MAV_COLLISION_ACTION_NONE;65}66break;6768case MAV_COLLISION_ACTION_MOVE_HORIZONTALLY:69// move horizontally to avoid obstacle70if (!handle_avoidance_horizontal(obstacle, failsafe_state_change)) {71actual_action = MAV_COLLISION_ACTION_NONE;72}73break;7475case MAV_COLLISION_ACTION_MOVE_PERPENDICULAR:76if (!handle_avoidance_perpendicular(obstacle, failsafe_state_change)) {77actual_action = MAV_COLLISION_ACTION_NONE;78}79break;8081// unsupported actions and those that require no response82case MAV_COLLISION_ACTION_NONE:83return actual_action;84case MAV_COLLISION_ACTION_REPORT:85default:86break;87}88}8990#if HAL_LOGGING_ENABLED91if (failsafe_state_change) {92AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_ADSB,93LogErrorCode(actual_action));94}95#endif9697// return with action taken98return actual_action;99}100101void AP_Avoidance_Copter::handle_recovery(RecoveryAction recovery_action)102{103// check we are coming out of failsafe104if (copter.failsafe.adsb) {105copter.failsafe.adsb = false;106LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_ADSB,107LogErrorCode::ERROR_RESOLVED);108109// restore flight mode if requested and user has not changed mode since110if (copter.control_mode_reason == ModeReason::AVOIDANCE) {111switch (recovery_action) {112113case RecoveryAction::REMAIN_IN_AVOID_ADSB:114// do nothing, we'll stay in the AVOID_ADSB mode which is guided which will loiter forever115break;116117case RecoveryAction::RESUME_PREVIOUS_FLIGHTMODE:118set_mode_else_try_RTL_else_LAND(prev_control_mode);119break;120121case RecoveryAction::RTL:122set_mode_else_try_RTL_else_LAND(Mode::Number::RTL);123break;124125case RecoveryAction::RESUME_IF_AUTO_ELSE_LOITER:126if (prev_control_mode == Mode::Number::AUTO) {127set_mode_else_try_RTL_else_LAND(Mode::Number::AUTO);128}129break;130131default:132break;133} // switch134}135}136}137138void AP_Avoidance_Copter::set_mode_else_try_RTL_else_LAND(Mode::Number mode)139{140if (!copter.set_mode(mode, ModeReason::AVOIDANCE_RECOVERY)) {141// on failure RTL or LAND142if (!copter.set_mode(Mode::Number::RTL, ModeReason::AVOIDANCE_RECOVERY)) {143copter.set_mode(Mode::Number::LAND, ModeReason::AVOIDANCE_RECOVERY);144}145}146}147148int32_t AP_Avoidance_Copter::get_altitude_minimum() const149{150#if MODE_RTL_ENABLED151// do not descend if below RTL alt152return copter.g.rtl_altitude;153#else154return 0;155#endif156}157158// check flight mode is avoid_adsb159bool AP_Avoidance_Copter::check_flightmode(bool allow_mode_change)160{161// ensure copter is in avoid_adsb mode162if (allow_mode_change && copter.flightmode->mode_number() != Mode::Number::AVOID_ADSB) {163if (!copter.set_mode(Mode::Number::AVOID_ADSB, ModeReason::AVOIDANCE)) {164// failed to set mode so exit immediately165return false;166}167}168169// check flight mode170return (copter.flightmode->mode_number() == Mode::Number::AVOID_ADSB);171}172173bool AP_Avoidance_Copter::handle_avoidance_vertical(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change)174{175// ensure copter is in avoid_adsb mode176if (!check_flightmode(allow_mode_change)) {177return false;178}179180// decide on whether we should climb or descend181bool should_climb = false;182Location my_loc;183if (AP::ahrs().get_location(my_loc)) {184should_climb = my_loc.alt > obstacle->_location.alt;185}186187// get best vector away from obstacle188Vector3f velocity_neu;189if (should_climb) {190velocity_neu.z = copter.wp_nav->get_default_speed_up();191} else {192velocity_neu.z = -copter.wp_nav->get_default_speed_down();193// do not descend if below minimum altitude194if (copter.current_loc.alt < get_altitude_minimum()) {195velocity_neu.z = 0.0f;196}197}198199// send target velocity200copter.mode_avoid_adsb.set_velocity(velocity_neu);201return true;202}203204bool AP_Avoidance_Copter::handle_avoidance_horizontal(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change)205{206// ensure copter is in avoid_adsb mode207if (!check_flightmode(allow_mode_change)) {208return false;209}210211// get best vector away from obstacle212Vector3f velocity_neu;213if (get_vector_perpendicular(obstacle, velocity_neu)) {214// remove vertical component215velocity_neu.z = 0.0f;216// check for divide by zero217if (is_zero(velocity_neu.x) && is_zero(velocity_neu.y)) {218return false;219}220// re-normalise221velocity_neu.normalize();222// convert horizontal components to velocities223velocity_neu.x *= copter.wp_nav->get_default_speed_xy();224velocity_neu.y *= copter.wp_nav->get_default_speed_xy();225// send target velocity226copter.mode_avoid_adsb.set_velocity(velocity_neu);227return true;228}229230// if we got this far we failed to set the new target231return false;232}233234bool AP_Avoidance_Copter::handle_avoidance_perpendicular(const AP_Avoidance::Obstacle *obstacle, bool allow_mode_change)235{236// ensure copter is in avoid_adsb mode237if (!check_flightmode(allow_mode_change)) {238return false;239}240241// get best vector away from obstacle242Vector3f velocity_neu;243if (get_vector_perpendicular(obstacle, velocity_neu)) {244// convert horizontal components to velocities245velocity_neu.x *= copter.wp_nav->get_default_speed_xy();246velocity_neu.y *= copter.wp_nav->get_default_speed_xy();247// use up and down waypoint speeds248if (velocity_neu.z > 0.0f) {249velocity_neu.z *= copter.wp_nav->get_default_speed_up();250} else {251velocity_neu.z *= copter.wp_nav->get_default_speed_down();252// do not descend if below minimum altitude253if (copter.current_loc.alt < get_altitude_minimum()) {254velocity_neu.z = 0.0f;255}256}257// send target velocity258copter.mode_avoid_adsb.set_velocity(velocity_neu);259return true;260}261262// if we got this far we failed to set the new target263return false;264}265#endif266267268