2021-03-18 00:12:54 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
|
|
|
|
|
|
|
class GCS_MAVLINK_Blimp : public GCS_MAVLINK
|
|
|
|
{
|
|
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
using GCS_MAVLINK::GCS_MAVLINK;
|
|
|
|
|
|
|
|
protected:
|
|
|
|
|
|
|
|
uint32_t telem_delay() const override;
|
|
|
|
|
2023-09-26 03:25:02 -03:00
|
|
|
MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet) override;
|
2021-03-18 00:12:54 -03:00
|
|
|
|
|
|
|
uint8_t sysid_my_gcs() const override;
|
|
|
|
bool sysid_enforce() const override;
|
|
|
|
|
|
|
|
bool params_ready() const override;
|
|
|
|
void send_banner() override;
|
|
|
|
|
2023-09-07 07:13:30 -03:00
|
|
|
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
|
2021-03-18 00:12:54 -03:00
|
|
|
|
|
|
|
void send_position_target_global_int() override;
|
|
|
|
|
|
|
|
MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;
|
2023-08-17 04:53:03 -03:00
|
|
|
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;
|
2021-03-18 00:12:54 -03:00
|
|
|
MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);
|
|
|
|
|
2023-11-08 06:31:04 -04:00
|
|
|
#if AP_MAVLINK_COMMAND_LONG_ENABLED
|
2023-10-18 03:30:32 -03:00
|
|
|
bool mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const override;
|
2023-11-08 06:31:04 -04:00
|
|
|
#endif
|
2021-03-18 00:12:54 -03:00
|
|
|
|
|
|
|
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
|
|
|
|
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
|
2021-03-29 11:43:54 -03:00
|
|
|
void send_nav_controller_output() const override; //TODO Apparently can't remove this or the build fails.
|
2021-03-18 00:12:54 -03:00
|
|
|
uint64_t capabilities() const override;
|
|
|
|
|
|
|
|
virtual MAV_VTOL_STATE vtol_state() const override
|
|
|
|
{
|
|
|
|
return MAV_VTOL_STATE_MC;
|
|
|
|
};
|
|
|
|
virtual MAV_LANDED_STATE landed_state() const override;
|
|
|
|
|
|
|
|
private:
|
|
|
|
|
2024-01-23 02:41:49 -04:00
|
|
|
void handle_message(const mavlink_message_t &msg) override;
|
2021-03-18 00:12:54 -03:00
|
|
|
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
|
|
|
|
bool try_send_message(enum ap_message id) override;
|
|
|
|
|
|
|
|
void packetReceived(const mavlink_status_t &status,
|
|
|
|
const mavlink_message_t &msg) override;
|
|
|
|
|
|
|
|
MAV_MODE base_mode() const override;
|
|
|
|
MAV_STATE vehicle_system_status() const override;
|
|
|
|
|
|
|
|
float vfr_hud_airspeed() const override;
|
|
|
|
int16_t vfr_hud_throttle() const override;
|
|
|
|
float vfr_hud_alt() const override;
|
|
|
|
|
|
|
|
void send_pid_tuning() override;
|
|
|
|
|
|
|
|
void send_wind() const;
|
2021-06-23 23:26:56 -03:00
|
|
|
|
|
|
|
//This is 1-indexed, unlike most enums for consistency with the mavlink PID_TUNING enums.
|
|
|
|
enum PID_SEND : uint8_t {
|
2021-06-22 03:36:11 -03:00
|
|
|
VELX = 1,
|
|
|
|
VELY = 2,
|
2021-06-23 23:26:56 -03:00
|
|
|
VELZ = 3,
|
2021-06-22 03:36:11 -03:00
|
|
|
VELYAW = 4,
|
2021-06-23 23:26:56 -03:00
|
|
|
POSX = 5,
|
|
|
|
POSY = 6,
|
|
|
|
POSZ = 7,
|
|
|
|
POSYAW = 8,
|
|
|
|
};
|
2023-07-27 02:06:32 -03:00
|
|
|
|
2021-07-06 07:53:53 -03:00
|
|
|
#if HAL_HIGH_LATENCY2_ENABLED
|
|
|
|
uint8_t high_latency_wind_speed() const override;
|
|
|
|
uint8_t high_latency_wind_direction() const override;
|
|
|
|
#endif // HAL_HIGH_LATENCY2_ENABLED
|
2021-03-18 00:12:54 -03:00
|
|
|
};
|