2013-05-29 20:52:21 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
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/>.
|
|
|
|
*/
|
|
|
|
|
2010-11-19 01:42:47 -04:00
|
|
|
//
|
|
|
|
// Hardware in the loop gps class.
|
|
|
|
// Code by James Goppert
|
|
|
|
//
|
|
|
|
//
|
2012-09-27 02:18:44 -03:00
|
|
|
#ifndef __AP_GPS_HIL_H__
|
|
|
|
#define __AP_GPS_HIL_H__
|
2010-11-19 01:42:47 -04:00
|
|
|
|
2012-09-27 02:18:44 -03:00
|
|
|
#include <AP_HAL.h>
|
2011-04-30 23:05:17 -03:00
|
|
|
#include "GPS.h"
|
2010-11-19 01:42:47 -04:00
|
|
|
|
|
|
|
class AP_GPS_HIL : public GPS {
|
|
|
|
public:
|
2013-02-19 20:32:15 -04:00
|
|
|
AP_GPS_HIL() :
|
|
|
|
GPS(),
|
|
|
|
_updated(false)
|
|
|
|
{}
|
|
|
|
|
2012-12-17 22:31:05 -04:00
|
|
|
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE);
|
2012-08-17 03:19:44 -03:00
|
|
|
virtual bool read(void);
|
2010-12-24 02:35:09 -04:00
|
|
|
|
2010-11-19 17:20:49 -04:00
|
|
|
/**
|
|
|
|
* Hardware in the loop set function
|
|
|
|
* @param latitude - latitude in deggrees
|
|
|
|
* @param longitude - longitude in degrees
|
|
|
|
* @param altitude - altitude in degrees
|
|
|
|
* @param ground_speed - ground speed in meters/second
|
|
|
|
* @param ground_course - ground course in degrees
|
|
|
|
* @param speed_3d - ground speed in meters/second
|
|
|
|
* @param altitude - altitude in meters
|
|
|
|
*/
|
2013-10-23 08:13:48 -03:00
|
|
|
virtual void setHIL(uint64_t time_epoch_ms, float latitude, float longitude, float altitude,
|
2012-08-17 03:19:44 -03:00
|
|
|
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
|
2010-12-24 02:35:09 -04:00
|
|
|
|
|
|
|
private:
|
2012-08-17 03:19:44 -03:00
|
|
|
bool _updated;
|
2010-11-19 01:42:47 -04:00
|
|
|
};
|
|
|
|
|
2012-09-27 02:18:44 -03:00
|
|
|
#endif // __AP_GPS_HIL_H__
|