mirror of https://github.com/ArduPilot/ardupilot
Jason's GPS_None pointed out a few changes that in turn drastically simplify it.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@431 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
dd8c883995
commit
31ab494aaa
|
@ -1,19 +0,0 @@
|
|||
/*
|
||||
AP_GPS_None.cpp
|
||||
*/
|
||||
|
||||
#include "AP_GPS_None.h"
|
||||
|
||||
AP_GPS_None::AP_GPS_None()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
void AP_GPS_None::init(void)
|
||||
{
|
||||
}
|
||||
|
||||
void AP_GPS_None::update(void)
|
||||
{
|
||||
}
|
||||
|
|
@ -1,3 +1,5 @@
|
|||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||
|
||||
#ifndef AP_GPS_None_h
|
||||
#define AP_GPS_None_h
|
||||
|
||||
|
@ -5,12 +7,5 @@
|
|||
|
||||
class AP_GPS_None : public GPS
|
||||
{
|
||||
public:
|
||||
AP_GPS_None();
|
||||
void init();
|
||||
void update();
|
||||
|
||||
private:
|
||||
|
||||
};
|
||||
#endif
|
||||
|
|
|
@ -3,6 +3,16 @@
|
|||
#include "GPS.h"
|
||||
#include <stdio.h>
|
||||
|
||||
void
|
||||
GPS::init(void)
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
GPS::update(void)
|
||||
{
|
||||
}
|
||||
|
||||
void
|
||||
GPS::_error(const char *fmt, ...)
|
||||
{
|
||||
|
|
|
@ -22,7 +22,7 @@ public:
|
|||
///
|
||||
/// @param port Stream connected to the GPS module.
|
||||
///
|
||||
GPS(Stream *port) : _port(port) {};
|
||||
GPS(Stream *port = NULL) : _port(port) {};
|
||||
|
||||
/// Startup initialisation.
|
||||
///
|
||||
|
|
Loading…
Reference in New Issue