mirror of https://github.com/ArduPilot/ardupilot
52 lines
1.3 KiB
C++
52 lines
1.3 KiB
C++
/*
|
|
This program is free software: you can redistribute it and/or modify
|
|
it under the terms of the GNU General Public License as published by
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
(at your option) any later version.
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
GNU General Public License for more details.
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
*/
|
|
|
|
//
|
|
// Mavlink GPS driver which accepts gps position data from an external
|
|
// companion computer
|
|
//
|
|
#pragma once
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include "AP_GPS.h"
|
|
#include "GPS_Backend.h"
|
|
|
|
#ifndef AP_GPS_MAV_ENABLED
|
|
#define AP_GPS_MAV_ENABLED 1
|
|
#endif
|
|
|
|
#if AP_GPS_MAV_ENABLED
|
|
class AP_GPS_MAV : public AP_GPS_Backend {
|
|
public:
|
|
|
|
using AP_GPS_Backend::AP_GPS_Backend;
|
|
|
|
bool read() override;
|
|
|
|
static bool _detect(struct MAV_detect_state &state, uint8_t data);
|
|
|
|
void handle_msg(const mavlink_message_t &msg) override;
|
|
|
|
const char *name() const override { return "MAV"; }
|
|
|
|
private:
|
|
bool _new_data;
|
|
uint32_t first_week;
|
|
JitterCorrection jitter{2000};
|
|
};
|
|
#endif
|