8 #define AVOIDANCE_DEBUGGING 0 10 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane) 11 #define AP_AVOIDANCE_WARN_TIME_DEFAULT 30 12 #define AP_AVOIDANCE_FAIL_TIME_DEFAULT 30 13 #define AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT 1000 14 #define AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT 300 15 #define AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT 300 16 #define AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT 100 17 #define AP_AVOIDANCE_RECOVERY_DEFAULT AP_AVOIDANCE_RECOVERY_RESUME_IF_AUTO_ELSE_LOITER 18 #define AP_AVOIDANCE_FAIL_ACTION_DEFAULT MAV_COLLISION_ACTION_REPORT 19 #else // APM_BUILD_TYPE(APM_BUILD_ArduCopter), Rover, Boat 20 #define AP_AVOIDANCE_WARN_TIME_DEFAULT 30 21 #define AP_AVOIDANCE_FAIL_TIME_DEFAULT 30 22 #define AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT 300 23 #define AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT 300 24 #define AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT 100 25 #define AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT 100 26 #define AP_AVOIDANCE_RECOVERY_DEFAULT AP_AVOIDANCE_RECOVERY_RTL 27 #define AP_AVOIDANCE_FAIL_ACTION_DEFAULT MAV_COLLISION_ACTION_REPORT 30 #if AVOIDANCE_DEBUGGING 32 #define debug(fmt, args ...) do {::fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) 34 #define debug(fmt, args ...) 146 hal.
console->
printf(
"Unable to initialize Avoidance obstacle list\n");
191 const MAV_COLLISION_SRC src,
192 const uint32_t src_id,
200 uint8_t oldest_index = 255;
210 if (
_obstacles[i].timestamp_ms < oldest_timestamp) {
219 index = _obstacle_count++;
220 }
else if (oldest_timestamp < obstacle_timestamp_ms) {
222 index = oldest_index;
238 const MAV_COLLISION_SRC src,
239 const uint32_t src_id,
246 vel[0] = hspeed * cosf(
radians(cog));
247 vel[1] = hspeed * sinf(
radians(cog));
250 return add_obstacle(obstacle_timestamp_ms, src, src_id, loc, vel);
256 return vehicle.
info.ICAO_address;
266 MAV_COLLISION_SRC_ADSB,
269 vehicle.
info.heading/100.0f,
270 vehicle.
info.hor_velocity/100.0f,
271 -vehicle.
info.ver_velocity/1000.0f);
279 const uint8_t time_horizon)
282 Vector2f delta_vel_ne =
Vector2f(obstacle_vel[0] - my_vel[0], obstacle_vel[1] - my_vel[1]);
285 Vector2f line_segment_ne = delta_vel_ne * time_horizon;
291 debug(
" time_horizon: (%d)", time_horizon);
292 debug(
" delta pos: (y=%f,x=%f)", delta_pos_ne[0], delta_pos_ne[1]);
293 debug(
" delta vel: (y=%f,x=%f)", delta_vel_ne[0], delta_vel_ne[1]);
294 debug(
" line segment: (y=%f,x=%f)", line_segment_ne[0], line_segment_ne[1]);
295 debug(
" closest: (%f)", ret);
305 const uint8_t time_horizon)
308 float delta_vel_d = obstacle_vel[2] - my_vel[2];
309 float delta_pos_d = obstacle_loc.
alt - my_loc.
alt;
312 if (delta_pos_d >= 0 && delta_vel_d >= 0) {
314 }
else if (delta_pos_d <= 0 && delta_vel_d <= 0) {
315 ret = fabsf(delta_pos_d);
317 ret = fabsf(delta_pos_d - delta_vel_d * time_horizon);
320 debug(
" time_horizon: (%d)", time_horizon);
321 debug(
" delta pos: (%f) metres", delta_pos_d/100.0
f);
322 debug(
" delta vel: (%f) m/s", delta_vel_d);
323 debug(
" closest: (%f) metres", ret/100.0
f);
336 obstacle.
threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
341 obstacle.
threat_level = MAV_COLLISION_THREAT_LEVEL_HIGH;
352 if (obstacle.
threat_level != MAV_COLLISION_THREAT_LEVEL_NONE) {
354 obstacle.
threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
365 obstacle.
threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
372 float current_distance =
get_distance(my_loc, obstacle_loc);
374 Vector2f net_velocity_ne =
Vector2f(my_vel[0] - obstacle_vel[0], my_vel[1] - obstacle_vel[1]);
384 return MAV_COLLISION_THREAT_LEVEL_NONE;
387 return MAV_COLLISION_THREAT_LEVEL_NONE;
394 if (threat ==
nullptr) {
399 if (threat->
threat_level == MAV_COLLISION_THREAT_LEVEL_NONE) {
467 if (i == _obstacle_count-1) {
468 _obstacle_count -= 1;
514 MAV_COLLISION_THREAT_LEVEL new_threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
515 MAV_COLLISION_ACTION action = MAV_COLLISION_ACTION_NONE;
517 if (threat !=
nullptr) {
519 if (new_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) {
525 action = MAV_COLLISION_ACTION_REPORT;
548 if ((threat !=
nullptr) && (
_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) && (action > MAV_COLLISION_ACTION_REPORT)) {
561 if (msg.msgid != MAVLINK_MSG_ID_GLOBAL_POSITION_INT) {
572 mavlink_global_position_int_t packet;
573 mavlink_msg_global_position_int_decode(&msg, &packet);
575 loc.
lat = packet.lat;
576 loc.
lng = packet.lon;
577 loc.
alt = packet.alt / 10;
583 MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT,
592 if (obstacle ==
nullptr) {
616 vec_neu = delta_pos_xyz;
AP_Avoidance::Obstacle * most_serious_threat()
virtual MAV_COLLISION_ACTION handle_avoidance(const AP_Avoidance::Obstacle *obstacle, MAV_COLLISION_ACTION requested_action)=0
virtual bool get_velocity_NED(Vector3f &vec) const
Vector2< float > Vector2f
bool next_sample(adsb_vehicle_t &obstacle)
Vector3< float > Vector3f
uint32_t _last_state_change_ms
#define AP_PARAM_FLAG_ENABLE
AP_HAL::UARTDriver * console
#define AP_AVOIDANCE_FAIL_ACTION_DEFAULT
virtual bool get_position(struct Location &loc) const =0
Interface definition for the various Ground Control System.
#define AP_GROUPINFO(name, idx, clazz, element, def)
float get_distance(const struct Location &loc1, const struct Location &loc2)
static int max(int a, int b)
static float closest_distance_between_radial_and_point(const Vector2< T > &w, const Vector2< T > &p)
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
float closest_approach_xy(const Location &my_loc, const Vector3f &my_vel, const Location &obstacle_loc, const Vector3f &obstacle_vel, const uint8_t time_horizon)
MAV_COLLISION_ACTION _latest_action
float distance_to_closest_approach
static Vector2< T > perpendicular(const Vector2< T > &pos_delta, const Vector2< T > &v1)
#define AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT
uint32_t last_gcs_report_time
#define debug(fmt, args ...)
int32_t lat
param 3 - Latitude * 10**7
uint32_t _gcs_cleared_messages_first_sent
MAV_COLLISION_THREAT_LEVEL current_threat_level() const
AP_Int8 _fail_time_horizon
static Vector3< T > perpendicular(const Vector3< T > &p1, const Vector3< T > &v1)
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
void handle_threat_gcs_notify(AP_Avoidance::Obstacle *threat)
void handle_avoidance_local(AP_Avoidance::Obstacle *threat)
virtual void printf(const char *,...) FMT_PRINTF(2
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
bool is_zero(const T fVal1)
#define AP_AVOIDANCE_RECOVERY_RTL
float time_to_closest_approach
uint8_t _obstacles_allocated
mavlink_system_t mavlink_system
MAVLink system definition.
mavlink_adsb_vehicle_t info
AP_Int16 _fail_altitude_minimum
Location_Class get_location(const adsb_vehicle_t &vehicle) const
static DummyVehicle vehicle
MAV_COLLISION_THREAT_LEVEL _threat_level
AP_Int16 _fail_distance_xy
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
virtual void handle_recovery(uint8_t recovery_action)=0
#define AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT
int32_t lng
param 4 - Longitude * 10**7
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
static constexpr float radians(float deg)
#define AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT
#define AP_AVOIDANCE_RECOVERY_DEFAULT
float closest_approach_xy
static const uint8_t _gcs_cleared_messages_duration
bool get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu)
float closest_approach_z(const Location &my_loc, const Vector3f &my_vel, const Location &obstacle_loc, const Vector3f &obstacle_vel, const uint8_t time_horizon)
static const uint8_t _gcs_notify_interval
AP_Int16 _fail_distance_z
#define AP_AVOIDANCE_STATE_RECOVERY_TIME_MS
static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour)
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)
#define AP_AVOIDANCE_WARN_TIME_DEFAULT
AP_Avoidance(AP_AHRS &ahrs, class AP_ADSB &adsb)
#define AP_AVOIDANCE_FAIL_TIME_DEFAULT
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
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
#define AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT
int8_t _current_most_serious_threat