#pragma once #include class GCS_MAVLINK_Rover : public GCS_MAVLINK { public: using GCS_MAVLINK::GCS_MAVLINK; protected: uint32_t telem_delay() const override; uint8_t sysid_my_gcs() const override; bool sysid_enforce() const override; MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override; MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override; MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override; MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet); void send_position_target_global_int() override; virtual bool in_hil_mode() const override; bool persist_streamrates() const override { return true; } bool set_home_to_current_location(bool lock) override; bool set_home(const Location& loc, bool lock) override; uint64_t capabilities() const override; void send_nav_controller_output() const override; void send_pid_tuning() override; private: void handleMessage(const mavlink_message_t &msg) override; bool handle_guided_request(AP_Mission::Mission_Command &cmd) override; void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override; void handle_rc_channels_override(const mavlink_message_t &msg) override; bool try_send_message(enum ap_message id) override; void handle_manual_control(const mavlink_message_t &msg); void handle_heartbeat(const mavlink_message_t &msg); void handle_set_attitude_target(const mavlink_message_t &msg); void handle_set_position_target_local_ned(const mavlink_message_t &msg); void handle_set_position_target_global_int(const mavlink_message_t &msg); void handle_hil_state(const mavlink_message_t &msg); void handle_radio(const mavlink_message_t &msg); 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; int16_t vfr_hud_throttle() const override; void send_rangefinder() const override; };