From f8ed279b1484c69323f685929dbd5cacf20edfe9 Mon Sep 17 00:00:00 2001 From: DrZiplok Date: Tue, 28 Dec 2010 23:50:50 +0000 Subject: [PATCH] Fix over-clever macro. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1344 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/AP_GPS/AP_GPS_Shim.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_Shim.h b/libraries/AP_GPS/AP_GPS_Shim.h index 9e402698b6..41646a0d6e 100644 --- a/libraries/AP_GPS/AP_GPS_Shim.h +++ b/libraries/AP_GPS/AP_GPS_Shim.h @@ -18,11 +18,11 @@ class AP_GPS_Shim : public GPS { public: 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_() - /// #define __GPS_SHIM_SET(__name) void set_##__name(typeof(GPS::__name) v) { __name = v; _updated = true; } __GPS_SHIM_SET(time); __GPS_SHIM_SET(latitude); __GPS_SHIM_SET(longitude); __GPS_SHIM_SET(altitude); __GPS_SHIM_SET(ground_speed); __GPS_SHIM_SET(ground_course); __GPS_SHIM_SET(speed_3d); __GPS_SHIM_SET(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 };