Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/GCS_MAVLink_Copter.h
9782 views
1
#pragma once
2
3
#include <GCS_MAVLink/GCS.h>
4
#include <AP_Winch/AP_Winch_config.h>
5
#include "defines.h"
6
7
#ifndef AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED
8
#define AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED 1
9
#endif
10
11
class GCS_MAVLINK_Copter : public GCS_MAVLINK
12
{
13
14
public:
15
16
using GCS_MAVLINK::GCS_MAVLINK;
17
18
protected:
19
20
MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet) override;
21
22
bool params_ready() const override;
23
void send_banner() override;
24
25
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
26
27
void send_attitude_target() override;
28
void send_position_target_global_int() override;
29
void send_position_target_local_ned() override;
30
31
MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
32
MAV_RESULT handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
33
#if HAL_MOUNT_ENABLED
34
MAV_RESULT handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
35
#endif
36
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
37
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
38
MAV_RESULT handle_command_pause_continue(const mavlink_command_int_t &packet);
39
40
void handle_message_set_attitude_target(const mavlink_message_t &msg);
41
void handle_message_set_position_target_global_int(const mavlink_message_t &msg);
42
void handle_message_set_position_target_local_ned(const mavlink_message_t &msg);
43
44
void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;
45
46
void send_nav_controller_output() const override;
47
uint64_t capabilities() const override;
48
49
virtual MAV_VTOL_STATE vtol_state() const override { return MAV_VTOL_STATE_MC; };
50
virtual MAV_LANDED_STATE landed_state() const override;
51
52
void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) override;
53
54
#if HAL_LOGGING_ENABLED
55
uint32_t log_radio_bit() const override { return MASK_LOG_PM; }
56
#endif
57
58
// Send the mode with the given index (not mode number!) return the total number of modes
59
// Index starts at 1
60
uint8_t send_available_mode(uint8_t index) const override;
61
62
private:
63
64
// sanity check velocity or acceleration vector components are numbers
65
// (e.g. not NaN) and below 1000. vec argument units are in meters/second or
66
// metres/second/second
67
bool sane_vel_or_acc_vector(const Vector3f &vec) const;
68
69
MISSION_STATE mission_state(const class AP_Mission &mission) const override;
70
71
void handle_message(const mavlink_message_t &msg) override;
72
void handle_command_ack(const mavlink_message_t &msg) override;
73
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
74
bool try_send_message(enum ap_message id) override;
75
76
void packetReceived(const mavlink_status_t &status,
77
const mavlink_message_t &msg) override;
78
79
uint8_t base_mode() const override;
80
MAV_STATE vehicle_system_status() const override;
81
82
float vfr_hud_airspeed() const override;
83
int16_t vfr_hud_throttle() const override;
84
float vfr_hud_alt() const override;
85
86
void send_pid_tuning() override;
87
88
#if AP_WINCH_ENABLED
89
void send_winch_status() const override;
90
#endif
91
92
void send_wind() const;
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
104
MAV_RESULT handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet);
105
MAV_RESULT handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet);
106
MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet);
107
MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet);
108
109
#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED
110
MAV_RESULT handle_MAV_CMD_SOLO_BTN_FLY_CLICK(const mavlink_command_int_t &packet);
111
MAV_RESULT handle_MAV_CMD_SOLO_BTN_FLY_HOLD(const mavlink_command_int_t &packet);
112
MAV_RESULT handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(const mavlink_command_int_t &packet);
113
#endif
114
115
#if AP_MAVLINK_COMMAND_LONG_ENABLED
116
bool mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const override;
117
#endif
118
119
MAV_RESULT handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet);
120
MAV_RESULT handle_MAV_CMD_NAV_TAKEOFF(const mavlink_command_int_t &packet);
121
122
#if AP_WINCH_ENABLED
123
MAV_RESULT handle_MAV_CMD_DO_WINCH(const mavlink_command_int_t &packet);
124
#endif
125
126
};
127
128