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/ArduSub/GCS_MAVLink_Sub.h
Views: 1798
#pragma once12#include <GCS_MAVLink/GCS.h>34class GCS_MAVLINK_Sub : public GCS_MAVLINK {56public:78using GCS_MAVLINK::GCS_MAVLINK;910uint8_t sysid_my_gcs() const override;11protected:1213uint32_t telem_delay() const override {14return 0;15};1617MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet) override;1819MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;20MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg) override;21MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;2223MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;24MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);2526// override sending of scaled_pressure3 to send on-board temperature:27void send_scaled_pressure3() override;2829int32_t global_position_int_alt() const override;30int32_t global_position_int_relative_alt() const override;3132void send_banner() override;3334void send_nav_controller_output() const override;35void send_pid_tuning() override;3637uint64_t capabilities() const override;3839// Send the mode with the given index (not mode number!) return the total number of modes40// Index starts at 141uint8_t send_available_mode(uint8_t index) const override;4243private:4445void handle_message(const mavlink_message_t &msg) override;46bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;47bool try_send_message(enum ap_message id) override;4849bool send_info(void);5051MAV_MODE base_mode() const override;52MAV_STATE vehicle_system_status() const override;5354int16_t vfr_hud_throttle() const override;55float vfr_hud_alt() const override;5657MAV_RESULT handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet);58MAV_RESULT handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet);59MAV_RESULT handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet);60MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet);61MAV_RESULT handle_MAV_CMD_NAV_LOITER_UNLIM(const mavlink_command_int_t &packet);62MAV_RESULT handle_MAV_CMD_NAV_LAND(const mavlink_command_int_t &packet);6364#if HAL_HIGH_LATENCY2_ENABLED65int16_t high_latency_target_altitude() const override;66uint8_t high_latency_tgt_heading() const override;67uint16_t high_latency_tgt_dist() const override;68uint8_t high_latency_tgt_airspeed() const override;69#endif // HAL_HIGH_LATENCY2_ENABLED70};717273