ardupilot/ArduCopter/GCS_Mavlink.h
Randy Mackay f4db4bdb08 Copter: GCS_MAVLink passes packets to AP_Avoidance
This allows treating GLOBAL_POSITION_INT packets from other vehicles in the same way as ADSB packets
2016-07-25 20:24:37 +09:00

26 lines
597 B
C++

#pragma once
#include <GCS_MAVLink/GCS.h>
class GCS_MAVLINK_Copter : public GCS_MAVLINK
{
public:
void data_stream_send(void) override;
protected:
uint32_t telem_delay() const override;
private:
void handleMessage(mavlink_message_t * msg) override;
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
bool try_send_message(enum ap_message id) override;
void packetReceived(const mavlink_status_t &status,
mavlink_message_t &msg) override;
};