Path: blob/master/libraries/AP_Avoidance/AP_Avoidance.h
9573 views
#pragma once12/*3This program is free software: you can redistribute it and/or modify4it under the terms of the GNU General Public License as published by5the Free Software Foundation, either version 3 of the License, or6(at your option) any later version.78This program is distributed in the hope that it will be useful,9but WITHOUT ANY WARRANTY; without even the implied warranty of10MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the11GNU General Public License for more details.1213You should have received a copy of the GNU General Public License14along with this program. If not, see <http://www.gnu.org/licenses/>.15*/16/*17Situational awareness for ArduPilot1819- record a series of moving points in space which should be avoided20- produce messages for GCS if a collision risk is detected2122Peter Barker, May 20162324based on AP_ADSB, Tom Pittenger, November 201525*/2627#include "AP_Avoidance_config.h"2829#if AP_ADSB_AVOIDANCE_ENABLED3031#include <AP_ADSB/AP_ADSB.h>3233#define AP_AVOIDANCE_STATE_RECOVERY_TIME_MS 2000 // we will not downgrade state any faster than this (2 seconds)3435#define AP_AVOIDANCE_ESCAPE_TIME_SEC 2 // vehicle runs from thread for 2 seconds3637class AP_Avoidance {38public:3940// constructor41AP_Avoidance(class AP_ADSB &adsb);4243/* Do not allow copies */44CLASS_NO_COPY(AP_Avoidance);4546// get singleton instance47static AP_Avoidance *get_singleton() {48return _singleton;49}5051// F_RCVRY possible parameter values:52enum class RecoveryAction {53REMAIN_IN_AVOID_ADSB = 0,54RESUME_PREVIOUS_FLIGHTMODE = 1,55RTL = 2,56RESUME_IF_AUTO_ELSE_LOITER = 3,57};5859// obstacle class to hold latest information for a known obstacles60class Obstacle {61public:62MAV_COLLISION_SRC src;63uint32_t src_id;64uint32_t timestamp_ms;6566Location _location;67Vector3f _velocity_ned_ms;6869// fields relating to this being a threat. These would be the reason to have a separate list of threats:70MAV_COLLISION_THREAT_LEVEL threat_level;71float closest_approach_ne_m; // metres72float closest_approach_d_m; // metres73float time_to_closest_approach_s; // seconds, 3D approach74float distance_to_closest_approach_ned_m; // metres, 3D75uint32_t last_gcs_report_time; // millis76};777879// add obstacle to the list of known obstacles80void add_obstacle(uint32_t obstacle_timestamp_ms,81const MAV_COLLISION_SRC src,82uint32_t src_id,83const Location &loc,84const Vector3f &vel_ned_ms);8586void add_obstacle(uint32_t obstacle_timestamp_ms,87const MAV_COLLISION_SRC src,88uint32_t src_id,89const Location &loc,90float cog,91float hspeed,92float vspeed);9394// update should be called at 10hz or higher95void update();9697// enable or disable avoidance98void enable() { _enabled.set(true); };99void disable() { _enabled.set(false); };100101// current overall threat level102MAV_COLLISION_THREAT_LEVEL current_threat_level() const;103104// add obstacles into the Avoidance system from MAVLink messages105void handle_msg(const mavlink_message_t &msg);106107// for holding parameters108static const struct AP_Param::GroupInfo var_info[];109110protected:111112// top level avoidance handler. This calls the vehicle specific handle_avoidance with requested action113void handle_avoidance_local(AP_Avoidance::Obstacle *threat);114115// avoid the most significant threat. child classes must override this method116// function returns the action that it is actually taking117virtual MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action) = 0;118119// recover after all threats have cleared. child classes must override this method120// recovery_action is from F_RCVRY parameter121virtual void handle_recovery(RecoveryAction recovery_action) = 0;122123uint32_t _last_state_change_ms = 0;124MAV_COLLISION_THREAT_LEVEL _threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;125126// gcs notification127// specifies how long we should continue sending messages about a threat after it has cleared128static const uint8_t _gcs_cleared_messages_duration = 5; // seconds129uint32_t _gcs_cleared_messages_first_sent;130131void handle_threat_gcs_notify(AP_Avoidance::Obstacle *threat);132133AP_Avoidance::Obstacle *most_serious_threat();134135// returns an entry from the MAV_COLLISION_ACTION representative136// of what the current avoidance handler is up to.137MAV_COLLISION_ACTION mav_avoidance_action() { return _latest_action; }138139// get target destination that best gets vehicle away from the nearest obstacle140bool get_destination_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &newdest_neu, const float wp_speed_xy, const float wp_speed_z, const uint8_t _minimum_avoid_height);141142// get unit vector away from the nearest obstacle143bool get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu_unit) const;144145// helper functions to calculate destination to get us away from obstacle146// Note: v1 is NED147static Vector3f perpendicular_neu_m(const Location &p1, const Vector3f &v1, const Location &p2);148149private:150151void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour) const;152153// constants154const uint32_t MAX_OBSTACLE_AGE_MS = 5000; // obstacles that have not been heard from for 5 seconds are removed from the list155const static uint8_t _gcs_notify_interval = 1; // seconds156157// speed below which we will fly directly away from a threat158// rather than perpendicular to its velocity:159const uint8_t _low_velocity_threshold = 1; // meters/second160161// check to see if we are initialised (and possibly do initialisation)162bool check_startup();163164// initialize _obstacle_list165void init();166167// free _obstacle_list168void deinit();169170// get unique id for adsb171uint32_t src_id_for_adsb_vehicle(const AP_ADSB::adsb_vehicle_t &vehicle) const;172173void check_for_threats();174void update_threat_level(const Location &my_loc,175const Vector3f &my_vel,176AP_Avoidance::Obstacle &obstacle);177178// calls into the AP_ADSB library to retrieve vehicle data179void get_adsb_samples();180181// returns true if the obstacle should be considered more of a182// threat than the current most serious threat183bool obstacle_is_more_serious_threat(const AP_Avoidance::Obstacle &obstacle) const;184185// internal variables186AP_Avoidance::Obstacle *_obstacles;187uint8_t _obstacles_allocated;188uint8_t _obstacle_count;189int8_t _current_most_serious_threat;190MAV_COLLISION_ACTION _latest_action = MAV_COLLISION_ACTION_NONE;191192// external references193class AP_ADSB &_adsb;194195// parameters196AP_Int8 _enabled;197AP_Int8 _obstacles_max;198199AP_Int8 _fail_action;200AP_Int8 _fail_recovery;201AP_Int8 _fail_time_horizon_s;202AP_Int16 _fail_distance_ne_m;203AP_Int16 _fail_distance_d_m;204AP_Int16 _fail_altitude_min_m;205206AP_Int8 _warn_action;207AP_Int8 _warn_time_horizon_s;208AP_Float _warn_distance_ne_m;209AP_Float _warn_distance_d_m;210211// multi-thread support for avoidance212HAL_Semaphore _rsem;213214static AP_Avoidance *_singleton;215};216217float closest_approach_NE_m(const Location &my_loc,218const Vector3f &my_vel,219const Location &obstacle_loc,220const Vector3f &obstacle_vel,221uint8_t time_horizon);222223float closest_approach_D_m(const Location &my_loc,224const Vector3f &my_vel,225const Location &obstacle_loc,226const Vector3f &obstacle_vel,227uint8_t time_horizon);228229230namespace AP {231AP_Avoidance *ap_avoidance();232};233234#endif // AP_ADSB_AVOIDANCE_ENABLED235236237