mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Undo the ^M nonsense that CodeLite pulled.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1349 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
22aa34c8b0
commit
4dfd88f287
@ -14,15 +14,33 @@
|
||||
|
||||
#include <GPS.h>
|
||||
|
||||
class AP_GPS_Shim : public GPS
{
|
||||
class AP_GPS_Shim : public GPS
|
||||
{
|
||||
public:
|
||||
AP_GPS_Shim() : GPS(NULL) {}
|
||||
AP_GPS_Shim() : GPS(NULL) {}
|
||||
|
||||
virtual void init(void) {};
|
||||
virtual bool read(void) {
bool updated = _updated;
_updated = false;
return _updated;
}
|
||||
virtual bool read(void) {
|
||||
bool updated = _updated;
|
||||
_updated = false;
|
||||
return _updated;
|
||||
}
|
||||
|
||||
/// Set-and-mark-updated macro for the public member variables; each instance
|
||||
/// defines a member function set_<variable>(<type>)
|
||||
///
#define __GPS_SHIM_SET(__type, __name) void set_##__name(__type v) { __name = v; _updated = true; }
__GPS_SHIM_SET(long, time);
__GPS_SHIM_SET(long, latitude);
__GPS_SHIM_SET(long, longitude);
__GPS_SHIM_SET(long, altitude);
__GPS_SHIM_SET(long, ground_speed);
__GPS_SHIM_SET(long, ground_course);
__GPS_SHIM_SET(long, speed_3d);
__GPS_SHIM_SET(int, hdop);
#undef __GPS_SHIM_SET
private:
|
||||
///
|
||||
#define __GPS_SHIM_SET(__type, __name) void set_##__name(__type v) { __name = v; _updated = true; }
|
||||
__GPS_SHIM_SET(long, time);
|
||||
__GPS_SHIM_SET(long, latitude);
|
||||
__GPS_SHIM_SET(long, longitude);
|
||||
__GPS_SHIM_SET(long, altitude);
|
||||
__GPS_SHIM_SET(long, ground_speed);
|
||||
__GPS_SHIM_SET(long, ground_course);
|
||||
__GPS_SHIM_SET(long, speed_3d);
|
||||
__GPS_SHIM_SET(int, hdop);
|
||||
#undef __GPS_SHIM_SET
|
||||
|
||||
private:
|
||||
bool _updated; ///< set anytime a member is updated, cleared when read() returns true
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user