32 #define AP_AVOIDANCE_RECOVERY_REMAIN_IN_AVOID_ADSB 0 33 #define AP_AVOIDANCE_RECOVERY_RESUME_PREVIOUS_FLIGHTMODE 1 34 #define AP_AVOIDANCE_RECOVERY_RTL 2 35 #define AP_AVOIDANCE_RECOVERY_RESUME_IF_AUTO_ELSE_LOITER 3 37 #define AP_AVOIDANCE_STATE_RECOVERY_TIME_MS 2000 // we will not downgrade state any faster than this (2 seconds) 39 #define AP_AVOIDANCE_ESCAPE_TIME_SEC 2 // vehicle runs from thread for 2 seconds 46 MAV_COLLISION_SRC
src;
65 const MAV_COLLISION_SRC
src,
71 const MAV_COLLISION_SRC
src,
206 uint8_t time_horizon);
212 uint8_t time_horizon);
AP_Avoidance::Obstacle * most_serious_threat()
virtual MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action)=0
uint32_t _last_state_change_ms
static const struct AP_Param::GroupInfo var_info[]
AP_Int8 _warn_time_horizon
const uint32_t MAX_OBSTACLE_AGE_MS
const uint8_t _low_velocity_threshold
MAV_COLLISION_ACTION _latest_action
float distance_to_closest_approach
uint32_t last_gcs_report_time
uint32_t _gcs_cleared_messages_first_sent
MAV_COLLISION_THREAT_LEVEL current_threat_level() const
AP_Int8 _fail_time_horizon
float closest_distance_between_radial_and_point(const Vector2f &w, const Vector2f &p)
void handle_threat_gcs_notify(AP_Avoidance::Obstacle *threat)
void handle_avoidance_local(AP_Avoidance::Obstacle *threat)
float time_to_closest_approach
uint8_t _obstacles_allocated
AP_Int16 _fail_altitude_minimum
static DummyVehicle vehicle
bool 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)
MAV_COLLISION_THREAT_LEVEL _threat_level
AP_Int16 _fail_distance_xy
virtual void handle_recovery(uint8_t recovery_action)=0
uint32_t src_id_for_adsb_vehicle(AP_ADSB::adsb_vehicle_t vehicle) const
static Vector2f perpendicular_xy(const Location &p1, const Vector3f &v1, const Location &p2)
MAV_COLLISION_THREAT_LEVEL threat_level
float closest_approach_xy
static const uint8_t _gcs_cleared_messages_duration
bool get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu)
static const uint8_t _gcs_notify_interval
AP_Int16 _fail_distance_z
bool obstacle_is_more_serious_threat(const AP_Avoidance::Obstacle &obstacle) const
static Vector3f perpendicular_xyz(const Location &p1, const Vector3f &v1, const Location &p2)
MAV_COLLISION_ACTION mav_avoidance_action()
AP_Float _warn_distance_xy
AP_Float _warn_distance_z
void update_threat_level(const Location &my_loc, const Vector3f &my_vel, AP_Avoidance::Obstacle &obstacle)
AP_Avoidance(AP_AHRS &ahrs, class AP_ADSB &adsb)
void handle_msg(const mavlink_message_t &msg)
void add_obstacle(uint32_t obstacle_timestamp_ms, const MAV_COLLISION_SRC src, uint32_t src_id, const Location &loc, const Vector3f &vel_ned)
AP_Avoidance::Obstacle * _obstacles
int8_t _current_most_serious_threat