ArduCopter
GCS_Mavlink.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <GCS_MAVLink/GCS.h>
4 
5 // default sensors are present and healthy: gyro, accelerometer, barometer, rate_control, attitude_stabilization, yaw_position, altitude control, x/y position control, motor_control
6 #define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE | MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION | MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL | MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS | MAV_SYS_STATUS_AHRS | MAV_SYS_STATUS_SENSOR_BATTERY)
7 
9 {
10 
11 public:
12 
13 protected:
14 
15  uint32_t telem_delay() const override;
16 
17  bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) override;
18 
19  AP_Mission *get_mission() override;
20  AP_Rally *get_rally() const override;
21  Compass *get_compass() const override;
22  AP_Camera *get_camera() const override;
23  MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override;
24  AP_AdvancedFailsafe *get_advanced_failsafe() const override;
25  AP_VisualOdom *get_visual_odom() const override;
26  const AP_FWVersion &get_fwver() const override;
27 
28  uint8_t sysid_my_gcs() const override;
29 
30  bool set_mode(uint8_t mode) override;
31 
32  bool params_ready() const override;
33  void send_banner() override;
34 
35  MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override;
36 
37  void send_position_target_global_int() override;
38 
39 private:
40 
41  void handleMessage(mavlink_message_t * msg) override;
42  void handle_command_ack(const mavlink_message_t* msg) override;
43  bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
44  void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
45  bool try_send_message(enum ap_message id) override;
46 
47  void packetReceived(const mavlink_status_t &status,
48  mavlink_message_t &msg) override;
49 
50  MAV_TYPE frame_type() const override;
51  MAV_MODE base_mode() const override;
52  uint32_t custom_mode() const override;
53  MAV_STATE system_status() const override;
54 };
void send_position_target_global_int() override
Definition: GCS_Mavlink.cpp:101
AP_Camera * get_camera() const override
Definition: GCS_Mavlink.cpp:1679
const AP_FWVersion & get_fwver() const override
Definition: GCS_Mavlink.cpp:1746
uint8_t sysid_my_gcs() const override
Definition: GCS_Mavlink.cpp:262
void send_banner() override
Definition: GCS_Mavlink.cpp:600
uint32_t telem_delay() const override
Definition: GCS_Mavlink.cpp:267
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override
Definition: GCS_Mavlink.cpp:613
AP_Mission * get_mission() override
Definition: GCS_Mavlink.cpp:1665
Compass * get_compass() const override
Definition: GCS_Mavlink.cpp:1674
MAV_RESULT handle_flight_termination(const mavlink_command_long_t &packet) override
Definition: GCS_Mavlink.cpp:1707
bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) override
Definition: GCS_Mavlink.cpp:1654
AP_AdvancedFailsafe * get_advanced_failsafe() const override
Definition: GCS_Mavlink.cpp:1688
Definition: GCS_Mavlink.cpp:540
AP_VisualOdom * get_visual_odom() const override
Definition: GCS_Mavlink.cpp:1697
bool set_mode(uint8_t mode) override
Definition: GCS_Mavlink.cpp:1735
AP_Rally * get_rally() const override
Definition: GCS_Mavlink.cpp:1726
bool params_ready() const override
Definition: GCS_Mavlink.cpp:588
Definition: GCS_Mavlink.h:8