You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
 
 
 
 
 
 

27 lines
691 B

#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;
bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) 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;
};