mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
84bda4e893
fix follow endless loop on enter pass mavlink messages to AP_Follow separate follow from guided follow slows based on yaw error check follow is enabled before entering follow mode fix order in switch statement when converting from mode number to mode object remove unused last_log_ms from follow mode
53 lines
2.1 KiB
C++
53 lines
2.1 KiB
C++
#pragma once
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
|
|
|
// default sensors are present and healthy: gyro, accelerometer, rate_control, attitude_stabilization, yaw_position, altitude control, x/y position control, motor_control
|
|
#define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION | MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS | MAV_SYS_STATUS_AHRS | MAV_SYS_STATUS_SENSOR_BATTERY)
|
|
|
|
class GCS_MAVLINK_Rover : public GCS_MAVLINK
|
|
{
|
|
public:
|
|
|
|
protected:
|
|
|
|
uint32_t telem_delay() const override;
|
|
bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) override;
|
|
|
|
Compass *get_compass() const override;
|
|
AP_Mission *get_mission() override;
|
|
AP_Rally *get_rally() const override { return nullptr; };
|
|
AP_Camera *get_camera() const override;
|
|
AP_AdvancedFailsafe *get_advanced_failsafe() const override;
|
|
AP_VisualOdom *get_visual_odom() const override;
|
|
|
|
uint8_t sysid_my_gcs() const override;
|
|
|
|
bool set_mode(uint8_t mode) 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;
|
|
|
|
virtual bool in_hil_mode() const override;
|
|
|
|
bool persist_streamrates() const override { return true; }
|
|
|
|
private:
|
|
|
|
void handleMessage(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;
|
|
bool try_send_message(enum ap_message id) override;
|
|
|
|
void packetReceived(const mavlink_status_t &status, mavlink_message_t &msg) override;
|
|
|
|
MAV_TYPE frame_type() const override;
|
|
MAV_MODE base_mode() const override;
|
|
uint32_t custom_mode() const override;
|
|
MAV_STATE system_status() const override;
|
|
|
|
int16_t vfr_hud_throttle() const override;
|
|
|
|
};
|