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/AP_Avoidance/AP_Avoidance.h
Views: 1798
#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_ADSB/AP_ADSB.h>2829#if HAL_ADSB_ENABLED3031#define AP_AVOIDANCE_STATE_RECOVERY_TIME_MS 2000 // we will not downgrade state any faster than this (2 seconds)3233#define AP_AVOIDANCE_ESCAPE_TIME_SEC 2 // vehicle runs from thread for 2 seconds3435class AP_Avoidance {36public:3738// constructor39AP_Avoidance(class AP_ADSB &adsb);4041/* Do not allow copies */42CLASS_NO_COPY(AP_Avoidance);4344// get singleton instance45static AP_Avoidance *get_singleton() {46return _singleton;47}4849// F_RCVRY possible parameter values:50enum class RecoveryAction {51REMAIN_IN_AVOID_ADSB = 0,52RESUME_PREVIOUS_FLIGHTMODE = 1,53RTL = 2,54RESUME_IF_AUTO_ELSE_LOITER = 3,55};5657// obstacle class to hold latest information for a known obstacles58class Obstacle {59public:60MAV_COLLISION_SRC src;61uint32_t src_id;62uint32_t timestamp_ms;6364Location _location;65Vector3f _velocity;6667// fields relating to this being a threat. These would be the reason to have a separate list of threats:68MAV_COLLISION_THREAT_LEVEL threat_level;69float closest_approach_xy; // metres70float closest_approach_z; // metres71float time_to_closest_approach; // seconds, 3D approach72float distance_to_closest_approach; // metres, 3D73uint32_t last_gcs_report_time; // millis74};757677// add obstacle to the list of known obstacles78void add_obstacle(uint32_t obstacle_timestamp_ms,79const MAV_COLLISION_SRC src,80uint32_t src_id,81const Location &loc,82const Vector3f &vel_ned);8384void add_obstacle(uint32_t obstacle_timestamp_ms,85const MAV_COLLISION_SRC src,86uint32_t src_id,87const Location &loc,88float cog,89float hspeed,90float vspeed);9192// update should be called at 10hz or higher93void update();9495// enable or disable avoidance96void enable() { _enabled.set(true); };97void disable() { _enabled.set(false); };9899// current overall threat level100MAV_COLLISION_THREAT_LEVEL current_threat_level() const;101102// add obstacles into the Avoidance system from MAVLink messages103void handle_msg(const mavlink_message_t &msg);104105// for holding parameters106static const struct AP_Param::GroupInfo var_info[];107108protected:109110// top level avoidance handler. This calls the vehicle specific handle_avoidance with requested action111void handle_avoidance_local(AP_Avoidance::Obstacle *threat);112113// avoid the most significant threat. child classes must override this method114// function returns the action that it is actually taking115virtual MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action) = 0;116117// recover after all threats have cleared. child classes must override this method118// recovery_action is from F_RCVRY parameter119virtual void handle_recovery(RecoveryAction recovery_action) = 0;120121uint32_t _last_state_change_ms = 0;122MAV_COLLISION_THREAT_LEVEL _threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;123124// gcs notification125// specifies how long we should continue sending messages about a threat after it has cleared126static const uint8_t _gcs_cleared_messages_duration = 5; // seconds127uint32_t _gcs_cleared_messages_first_sent;128129void handle_threat_gcs_notify(AP_Avoidance::Obstacle *threat);130131AP_Avoidance::Obstacle *most_serious_threat();132133// returns an entry from the MAV_COLLISION_ACTION representative134// of what the current avoidance handler is up to.135MAV_COLLISION_ACTION mav_avoidance_action() { return _latest_action; }136137// get target destination that best gets vehicle away from the nearest obstacle138bool 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);139140// get unit vector away from the nearest obstacle141bool get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu) const;142143// helper functions to calculate destination to get us away from obstacle144// Note: v1 is NED145static Vector3f perpendicular_xyz(const Location &p1, const Vector3f &v1, const Location &p2);146static Vector2f perpendicular_xy(const Location &p1, const Vector3f &v1, const Location &p2);147148private:149150void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour) const;151152// constants153const uint32_t MAX_OBSTACLE_AGE_MS = 5000; // obstacles that have not been heard from for 5 seconds are removed from the list154const static uint8_t _gcs_notify_interval = 1; // seconds155156// speed below which we will fly directly away from a threat157// rather than perpendicular to its velocity:158const uint8_t _low_velocity_threshold = 1; // meters/second159160// check to see if we are initialised (and possibly do initialisation)161bool check_startup();162163// initialize _obstacle_list164void init();165166// free _obstacle_list167void deinit();168169// get unique id for adsb170uint32_t src_id_for_adsb_vehicle(const AP_ADSB::adsb_vehicle_t &vehicle) const;171172void check_for_threats();173void update_threat_level(const Location &my_loc,174const Vector3f &my_vel,175AP_Avoidance::Obstacle &obstacle);176177// calls into the AP_ADSB library to retrieve vehicle data178void get_adsb_samples();179180// returns true if the obstacle should be considered more of a181// threat than the current most serious threat182bool obstacle_is_more_serious_threat(const AP_Avoidance::Obstacle &obstacle) const;183184// internal variables185AP_Avoidance::Obstacle *_obstacles;186uint8_t _obstacles_allocated;187uint8_t _obstacle_count;188int8_t _current_most_serious_threat;189MAV_COLLISION_ACTION _latest_action = MAV_COLLISION_ACTION_NONE;190191// external references192class AP_ADSB &_adsb;193194// parameters195AP_Int8 _enabled;196AP_Int8 _obstacles_max;197198AP_Int8 _fail_action;199AP_Int8 _fail_recovery;200AP_Int8 _fail_time_horizon;201AP_Int16 _fail_distance_xy;202AP_Int16 _fail_distance_z;203AP_Int16 _fail_altitude_minimum;204205AP_Int8 _warn_action;206AP_Int8 _warn_time_horizon;207AP_Float _warn_distance_xy;208AP_Float _warn_distance_z;209210// multi-thread support for avoidance211HAL_Semaphore _rsem;212213static AP_Avoidance *_singleton;214};215216float closest_approach_xy(const Location &my_loc,217const Vector3f &my_vel,218const Location &obstacle_loc,219const Vector3f &obstacle_vel,220uint8_t time_horizon);221222float closest_approach_z(const Location &my_loc,223const Vector3f &my_vel,224const Location &obstacle_loc,225const Vector3f &obstacle_vel,226uint8_t time_horizon);227228229namespace AP {230AP_Avoidance *ap_avoidance();231};232233#endif234235236237