CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/GCS_MAVLink_Plane.h
Views: 1798
1
#pragma once
2
3
#include <GCS_MAVLink/GCS.h>
4
#include <AP_Logger/AP_Logger.h>
5
#include <AP_Airspeed/AP_Airspeed_config.h>
6
#include "quadplane.h"
7
#include "defines.h"
8
9
class GCS_MAVLINK_Plane : public GCS_MAVLINK
10
{
11
12
public:
13
14
using GCS_MAVLINK::GCS_MAVLINK;
15
16
uint8_t sysid_my_gcs() const override;
17
18
protected:
19
20
uint32_t telem_delay() const override;
21
22
#if HAL_LOGGING_ENABLED
23
uint32_t log_radio_bit() const override { return MASK_LOG_PM; }
24
#endif
25
26
#if AP_MAVLINK_MISSION_SET_CURRENT_ENABLED
27
void handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg) override;
28
#endif
29
30
bool sysid_enforce() const override;
31
32
MAV_RESULT handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
33
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
34
MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_int_t &packet) override;
35
36
void send_position_target_global_int() override;
37
38
void send_aoa_ssa();
39
void send_attitude() const override;
40
void send_attitude_target() override;
41
void send_wind() const;
42
43
bool persist_streamrates() const override { return true; }
44
45
uint64_t capabilities() const override;
46
47
void send_nav_controller_output() const override;
48
void send_pid_tuning() override;
49
50
void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) override;
51
void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;
52
53
// Send the mode with the given index (not mode number!) return the total number of modes
54
// Index starts at 1
55
uint8_t send_available_mode(uint8_t index) const override;
56
57
private:
58
59
void send_pid_info(const struct AP_PIDInfo *pid_info, const uint8_t axis, const float achieved);
60
61
void handle_message(const mavlink_message_t &msg) override;
62
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
63
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
64
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
65
MAV_RESULT handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet);
66
MAV_RESULT handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_command_int_t &packet);
67
MAV_RESULT handle_command_DO_CHANGE_SPEED(const mavlink_command_int_t &packet);
68
MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet);
69
MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet);
70
MAV_RESULT handle_command_DO_VTOL_TRANSITION(const mavlink_command_int_t &packet);
71
72
void handle_set_position_target_global_int(const mavlink_message_t &msg);
73
void handle_set_position_target_local_ned(const mavlink_message_t &msg);
74
void handle_set_attitude_target(const mavlink_message_t &msg);
75
76
#if HAL_QUADPLANE_ENABLED
77
#if AP_MAVLINK_COMMAND_LONG_ENABLED
78
void convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out);
79
void convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame = MAV_FRAME_GLOBAL_RELATIVE_ALT) override;
80
#endif
81
MAV_RESULT handle_command_MAV_CMD_NAV_TAKEOFF(const mavlink_command_int_t &packet);
82
#endif
83
84
bool try_send_message(enum ap_message id) override;
85
void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override;
86
87
MAV_MODE base_mode() const override;
88
MAV_STATE vehicle_system_status() const override;
89
90
float vfr_hud_airspeed() const override;
91
int16_t vfr_hud_throttle() const override;
92
float vfr_hud_climbrate() const override;
93
94
#if HAL_HIGH_LATENCY2_ENABLED
95
int16_t high_latency_target_altitude() const override;
96
uint8_t high_latency_tgt_heading() const override;
97
uint16_t high_latency_tgt_dist() const override;
98
uint8_t high_latency_tgt_airspeed() const override;
99
uint8_t high_latency_wind_speed() const override;
100
uint8_t high_latency_wind_direction() const override;
101
#endif // HAL_HIGH_LATENCY2_ENABLED
102
103
#if AP_AIRSPEED_HYGROMETER_ENABLE
104
void send_hygrometer();
105
uint8_t last_hygrometer_send_idx;
106
#endif
107
108
MAV_VTOL_STATE vtol_state() const override;
109
MAV_LANDED_STATE landed_state() const override;
110
111
};
112
113