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/Rover/GCS_MAVLink_Rover.h
Views: 1798
#pragma once12#include <GCS_MAVLink/GCS.h>34// set 0 in 4.6, remove feature in 4.7:5#ifndef AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED6#define AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED 07#endif89#include "defines.h"1011class GCS_MAVLINK_Rover : public GCS_MAVLINK12{13public:1415using GCS_MAVLINK::GCS_MAVLINK;1617protected:1819uint32_t telem_delay() const override;2021uint8_t sysid_my_gcs() const override;22bool sysid_enforce() const override;2324MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;25MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override;26MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet);27MAV_RESULT handle_command_nav_set_yaw_speed(const mavlink_command_int_t &packet, const mavlink_message_t &msg);2829void send_position_target_global_int() override;3031uint64_t capabilities() const override;3233void send_nav_controller_output() const override;34void send_pid_tuning() override;3536#if HAL_LOGGING_ENABLED37uint32_t log_radio_bit() const override { return MASK_LOG_PM; }38#endif3940// Send the mode with the given index (not mode number!) return the total number of modes41// Index starts at 142uint8_t send_available_mode(uint8_t index) const override;4344private:4546void handle_message(const mavlink_message_t &msg) override;47bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;48bool try_send_message(enum ap_message id) override;4950void handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow) override;51void handle_set_attitude_target(const mavlink_message_t &msg);52void handle_set_position_target_local_ned(const mavlink_message_t &msg);53void handle_set_position_target_global_int(const mavlink_message_t &msg);54void handle_radio(const mavlink_message_t &msg);55void handle_landing_target(const mavlink_landing_target_t &msg, uint32_t timestamp_ms) override;5657void send_servo_out();5859void packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) override;6061MAV_MODE base_mode() const override;62MAV_STATE vehicle_system_status() const override;6364int16_t vfr_hud_throttle() const override;6566#if AP_RANGEFINDER_ENABLED67void send_rangefinder() const override;6869// send WATER_DEPTH - metres and temperature70void send_water_depth();71// state variable for the last rangefinder we sent a WATER_DEPTH72// message for. We cycle through the rangefinder backends to73// limit the amount of telemetry bandwidth we consume.74uint8_t last_WATER_DEPTH_index;75#endif7677#if HAL_HIGH_LATENCY2_ENABLED78uint8_t high_latency_tgt_heading() const override;79uint16_t high_latency_tgt_dist() const override;80uint8_t high_latency_tgt_airspeed() const override;81uint8_t high_latency_wind_speed() const override;82uint8_t high_latency_wind_direction() const override;83#endif // HAL_HIGH_LATENCY2_ENABLED84};858687