GCS_MAVLink: make Avoidance responsible for sending collision message

This commit is contained in:
Peter Barker 2019-07-09 22:55:22 +10:00 committed by Andrew Tridgell
parent fd61bae0bd
commit 459680e7c8
2 changed files with 0 additions and 23 deletions

View File

@ -9,7 +9,6 @@
#include <AP_Mission/AP_Mission.h>
#include <stdint.h>
#include "MAVLink_routing.h"
#include <AP_Avoidance/AP_Avoidance.h>
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
#include <AP_AdvancedFailsafe/AP_AdvancedFailsafe.h>
#include <AP_RTC/JitterCorrection.h>
@ -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();

View File

@ -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_COMM_NUM_BUFFERS; i++) {
if ((1U<<i) & mavlink_active) {
mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0+i);
if (comm_get_txspace(chan) >= 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)) {