diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 10229d42d8..1c89198ad9 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -9,7 +9,6 @@ #include #include #include "MAVLink_routing.h" -#include #include #include #include @@ -435,7 +434,6 @@ public: virtual void send_position_target_global_int() { }; virtual void send_position_target_local_ned() { }; void send_servo_output_raw(); - static void send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour); void send_accelcal_vehicle_position(uint32_t position); void send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)); void send_sys_status(); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 9ccbc47c54..cfff492702 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -2722,27 +2722,6 @@ void GCS_MAVLINK::send_servo_output_raw() } -void GCS_MAVLINK::send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour) -{ - for (uint8_t i=0; i= MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_MSG_ID_COLLISION) { - mavlink_msg_collision_send( - chan, - MAV_COLLISION_SRC_ADSB, - threat.src_id, - behaviour, - threat.threat_level, - threat.time_to_closest_approach, - threat.closest_approach_z, - threat.closest_approach_xy - ); - } - } - } -} - void GCS_MAVLINK::send_accelcal_vehicle_position(uint32_t position) { if (HAVE_PAYLOAD_SPACE(chan, COMMAND_LONG)) {