Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduPlane/GCS_MAVLink_Plane.h
Views: 1798
#pragma once12#include <GCS_MAVLink/GCS.h>3#include <AP_Logger/AP_Logger.h>4#include <AP_Airspeed/AP_Airspeed_config.h>5#include "quadplane.h"6#include "defines.h"78class GCS_MAVLINK_Plane : public GCS_MAVLINK9{1011public:1213using GCS_MAVLINK::GCS_MAVLINK;1415uint8_t sysid_my_gcs() const override;1617protected:1819uint32_t telem_delay() const override;2021#if HAL_LOGGING_ENABLED22uint32_t log_radio_bit() const override { return MASK_LOG_PM; }23#endif2425#if AP_MAVLINK_MISSION_SET_CURRENT_ENABLED26void handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg) override;27#endif2829bool sysid_enforce() const override;3031MAV_RESULT handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;32MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;33MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_int_t &packet) override;3435void send_position_target_global_int() override;3637void send_aoa_ssa();38void send_attitude() const override;39void send_attitude_target() override;40void send_wind() const;4142bool persist_streamrates() const override { return true; }4344uint64_t capabilities() const override;4546void send_nav_controller_output() const override;47void send_pid_tuning() override;4849void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) override;50void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;5152// Send the mode with the given index (not mode number!) return the total number of modes53// Index starts at 154uint8_t send_available_mode(uint8_t index) const override;5556private:5758void send_pid_info(const struct AP_PIDInfo *pid_info, const uint8_t axis, const float achieved);5960void handle_message(const mavlink_message_t &msg) override;61bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;62void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;63MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);64MAV_RESULT handle_command_int_guided_slew_commands(const mavlink_command_int_t &packet);65MAV_RESULT handle_MAV_CMD_DO_AUTOTUNE_ENABLE(const mavlink_command_int_t &packet);66MAV_RESULT handle_command_DO_CHANGE_SPEED(const mavlink_command_int_t &packet);67MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet);68MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet);69MAV_RESULT handle_command_DO_VTOL_TRANSITION(const mavlink_command_int_t &packet);7071void handle_set_position_target_global_int(const mavlink_message_t &msg);72void handle_set_position_target_local_ned(const mavlink_message_t &msg);73void handle_set_attitude_target(const mavlink_message_t &msg);7475#if HAL_QUADPLANE_ENABLED76#if AP_MAVLINK_COMMAND_LONG_ENABLED77void convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out);78void 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;79#endif80MAV_RESULT handle_command_MAV_CMD_NAV_TAKEOFF(const mavlink_command_int_t &packet);81#endif8283bool try_send_message(enum ap_message id) override;84void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override;8586MAV_MODE base_mode() const override;87MAV_STATE vehicle_system_status() const override;8889float vfr_hud_airspeed() const override;90int16_t vfr_hud_throttle() const override;91float vfr_hud_climbrate() const override;9293#if HAL_HIGH_LATENCY2_ENABLED94int16_t high_latency_target_altitude() const override;95uint8_t high_latency_tgt_heading() const override;96uint16_t high_latency_tgt_dist() const override;97uint8_t high_latency_tgt_airspeed() const override;98uint8_t high_latency_wind_speed() const override;99uint8_t high_latency_wind_direction() const override;100#endif // HAL_HIGH_LATENCY2_ENABLED101102#if AP_AIRSPEED_HYGROMETER_ENABLE103void send_hygrometer();104uint8_t last_hygrometer_send_idx;105#endif106107MAV_VTOL_STATE vtol_state() const override;108MAV_LANDED_STATE landed_state() const override;109110};111112113