mirror of https://github.com/ArduPilot/ardupilot
59 lines
1.9 KiB
C++
59 lines
1.9 KiB
C++
#pragma once
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
|
|
|
class GCS_MAVLINK_Sub : public GCS_MAVLINK {
|
|
|
|
public:
|
|
|
|
protected:
|
|
|
|
uint32_t telem_delay() const override {
|
|
return 0;
|
|
};
|
|
|
|
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
|
|
|
|
uint8_t sysid_my_gcs() const override;
|
|
|
|
bool set_mode(uint8_t mode) override;
|
|
bool should_zero_rc_outputs_on_reboot() const override { return true; }
|
|
|
|
MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
|
|
MAV_RESULT _handle_command_preflight_calibration_baro() override;
|
|
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override;
|
|
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
|
|
|
|
// override sending of scaled_pressure3 to send on-board temperature:
|
|
void send_scaled_pressure3() override;
|
|
|
|
int32_t global_position_int_alt() const override;
|
|
int32_t global_position_int_relative_alt() const override;
|
|
|
|
bool vehicle_initialised() const override;
|
|
|
|
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
|
|
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
|
|
|
void send_nav_controller_output() const override;
|
|
uint64_t capabilities() 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;
|
|
void handle_rc_channels_override(const mavlink_message_t *msg) override;
|
|
bool try_send_message(enum ap_message id) override;
|
|
|
|
bool send_info(void);
|
|
|
|
MAV_TYPE frame_type() const override;
|
|
MAV_MODE base_mode() const override;
|
|
uint32_t custom_mode() const override;
|
|
MAV_STATE system_status() const override;
|
|
|
|
int16_t vfr_hud_throttle() const override;
|
|
|
|
};
|