uncrustify libraries/AP_GPS/AP_GPS_Shim.h

This commit is contained in:
uncrustify 2012-08-16 23:19:44 -07:00 committed by Pat Hickey
parent cdaf2f923d
commit 5c24c373d0
1 changed files with 9 additions and 7 deletions

View File

@ -17,11 +17,13 @@
class AP_GPS_Shim : public GPS class AP_GPS_Shim : public GPS
{ {
public: public:
AP_GPS_Shim() : GPS(NULL) {} AP_GPS_Shim() : GPS(NULL) {
}
virtual void init(enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE) {}; virtual void init(enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE) {
virtual bool read(void) { };
bool updated = _updated; virtual bool read(void) {
bool updated = _updated;
_updated = false; _updated = false;
return updated; return updated;
} }
@ -29,7 +31,7 @@ public:
/// Set-and-mark-updated macro for the public member variables; each instance /// Set-and-mark-updated macro for the public member variables; each instance
/// defines a member function set_<variable>(<type>) /// defines a member function set_<variable>(<type>)
/// ///
#define __GPS_SHIM_SET(__type, __name) void set_##__name(__type v) { __name = v; _updated = true; } #define __GPS_SHIM_SET(__type, __name) void set_ ## __name(__type v) { __name = v; _updated = true; }
__GPS_SHIM_SET(uint32_t, time); __GPS_SHIM_SET(uint32_t, time);
__GPS_SHIM_SET(long, latitude); __GPS_SHIM_SET(long, latitude);
__GPS_SHIM_SET(long, longitude); __GPS_SHIM_SET(long, longitude);
@ -41,7 +43,7 @@ public:
#undef __GPS_SHIM_SET #undef __GPS_SHIM_SET
private: private:
bool _updated; ///< set anytime a member is updated, cleared when read() returns true bool _updated; ///< set anytime a member is updated, cleared when read() returns true
}; };
#endif // AP_GPS_HIL_H #endif // AP_GPS_HIL_H