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/ArduCopter/GCS_MAVLink_Copter.h
Views: 1798
#pragma once12#include <GCS_MAVLink/GCS.h>3#include <AP_Winch/AP_Winch_config.h>4#include "defines.h"56#ifndef AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED7#define AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED 18#endif910class GCS_MAVLINK_Copter : public GCS_MAVLINK11{1213public:1415using GCS_MAVLINK::GCS_MAVLINK;1617protected:1819uint32_t telem_delay() const override;2021MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet) override;2223uint8_t sysid_my_gcs() const override;24bool sysid_enforce() const override;2526bool params_ready() const override;27void send_banner() override;2829MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;3031void send_attitude_target() override;32void send_position_target_global_int() override;33void send_position_target_local_ned() override;3435MAV_RESULT handle_command_do_set_roi(const Location &roi_loc) override;36MAV_RESULT handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;37#if HAL_MOUNT_ENABLED38MAV_RESULT handle_command_mount(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;39#endif40MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;41MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);42MAV_RESULT handle_command_pause_continue(const mavlink_command_int_t &packet);4344#if HAL_MOUNT_ENABLED45void handle_mount_message(const mavlink_message_t &msg) override;46#endif4748void handle_message_set_attitude_target(const mavlink_message_t &msg);49void handle_message_set_position_target_global_int(const mavlink_message_t &msg);50void handle_message_set_position_target_local_ned(const mavlink_message_t &msg);5152void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;5354void send_nav_controller_output() const override;55uint64_t capabilities() const override;5657virtual MAV_VTOL_STATE vtol_state() const override { return MAV_VTOL_STATE_MC; };58virtual MAV_LANDED_STATE landed_state() const override;5960void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) override;6162#if HAL_LOGGING_ENABLED63uint32_t log_radio_bit() const override { return MASK_LOG_PM; }64#endif6566// Send the mode with the given index (not mode number!) return the total number of modes67// Index starts at 168uint8_t send_available_mode(uint8_t index) const override;6970private:7172// sanity check velocity or acceleration vector components are numbers73// (e.g. not NaN) and below 1000. vec argument units are in meters/second or74// metres/second/second75bool sane_vel_or_acc_vector(const Vector3f &vec) const;7677MISSION_STATE mission_state(const class AP_Mission &mission) const override;7879void handle_message(const mavlink_message_t &msg) override;80void handle_command_ack(const mavlink_message_t &msg) override;81bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;82bool try_send_message(enum ap_message id) override;8384void packetReceived(const mavlink_status_t &status,85const mavlink_message_t &msg) override;8687MAV_MODE base_mode() const override;88MAV_STATE vehicle_system_status() const override;8990float vfr_hud_airspeed() const override;91int16_t vfr_hud_throttle() const override;92float vfr_hud_alt() const override;9394void send_pid_tuning() override;9596#if AP_WINCH_ENABLED97void send_winch_status() const override;98#endif99100void send_wind() const;101102#if HAL_HIGH_LATENCY2_ENABLED103int16_t high_latency_target_altitude() const override;104uint8_t high_latency_tgt_heading() const override;105uint16_t high_latency_tgt_dist() const override;106uint8_t high_latency_tgt_airspeed() const override;107uint8_t high_latency_wind_speed() const override;108uint8_t high_latency_wind_direction() const override;109#endif // HAL_HIGH_LATENCY2_ENABLED110111112MAV_RESULT handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet);113MAV_RESULT handle_MAV_CMD_DO_CHANGE_SPEED(const mavlink_command_int_t &packet);114MAV_RESULT handle_MAV_CMD_DO_MOTOR_TEST(const mavlink_command_int_t &packet);115MAV_RESULT handle_MAV_CMD_DO_PARACHUTE(const mavlink_command_int_t &packet);116117#if AC_MAVLINK_SOLO_BUTTON_COMMAND_HANDLING_ENABLED118MAV_RESULT handle_MAV_CMD_SOLO_BTN_FLY_CLICK(const mavlink_command_int_t &packet);119MAV_RESULT handle_MAV_CMD_SOLO_BTN_FLY_HOLD(const mavlink_command_int_t &packet);120MAV_RESULT handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(const mavlink_command_int_t &packet);121#endif122123#if AP_MAVLINK_COMMAND_LONG_ENABLED124bool mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const override;125#endif126127MAV_RESULT handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet);128MAV_RESULT handle_MAV_CMD_NAV_TAKEOFF(const mavlink_command_int_t &packet);129130#if AP_WINCH_ENABLED131MAV_RESULT handle_MAV_CMD_DO_WINCH(const mavlink_command_int_t &packet);132#endif133134};135136137