diff --git a/libraries/AP_GPS/AP_GPS_406.h b/libraries/AP_GPS/AP_GPS_406.h index d67f7d2f21..fd2ae258af 100644 --- a/libraries/AP_GPS/AP_GPS_406.h +++ b/libraries/AP_GPS/AP_GPS_406.h @@ -21,6 +21,8 @@ class AP_GPS_406 : public AP_GPS_SIRF { public: + AP_GPS_406() : AP_GPS_SIRF() {} + // Methods virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE); diff --git a/libraries/AP_GPS/AP_GPS_Auto.cpp b/libraries/AP_GPS/AP_GPS_Auto.cpp index 6a753d59fa..374cdf038b 100644 --- a/libraries/AP_GPS/AP_GPS_Auto.cpp +++ b/libraries/AP_GPS/AP_GPS_Auto.cpp @@ -17,6 +17,7 @@ const prog_char AP_GPS_Auto::_sirf_set_binary[] PROGMEM = SIRF_SET_BINARY; AP_GPS_Auto::AP_GPS_Auto(GPS **gps) : + GPS(), _gps(gps) { } diff --git a/libraries/AP_GPS/AP_GPS_HIL.h b/libraries/AP_GPS/AP_GPS_HIL.h index c5cf47f723..0e0b025da4 100644 --- a/libraries/AP_GPS/AP_GPS_HIL.h +++ b/libraries/AP_GPS/AP_GPS_HIL.h @@ -17,6 +17,11 @@ class AP_GPS_HIL : public GPS { public: + AP_GPS_HIL() : + GPS(), + _updated(false) + {} + virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE); virtual bool read(void); diff --git a/libraries/AP_GPS/AP_GPS_MTK.h b/libraries/AP_GPS/AP_GPS_MTK.h index 49c9aa1ffb..b5b1981730 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.h +++ b/libraries/AP_GPS/AP_GPS_MTK.h @@ -20,6 +20,12 @@ class AP_GPS_MTK : public GPS { public: + AP_GPS_MTK() : + GPS(), + _step(0), + _payload_counter(0) + {} + virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE); virtual bool read(void); static bool _detect(uint8_t ); diff --git a/libraries/AP_GPS/AP_GPS_MTK19.cpp b/libraries/AP_GPS/AP_GPS_MTK19.cpp index 34ba3a566b..70f92a087f 100644 --- a/libraries/AP_GPS/AP_GPS_MTK19.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK19.cpp @@ -17,12 +17,6 @@ #include "AP_GPS_MTK19.h" #include -// Constructors //////////////////////////////////////////////////////////////// -AP_GPS_MTK19::AP_GPS_MTK19() : GPS() -{ - _step = 0; -} - // Public Methods ////////////////////////////////////////////////////////////// void AP_GPS_MTK19::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting) diff --git a/libraries/AP_GPS/AP_GPS_MTK19.h b/libraries/AP_GPS/AP_GPS_MTK19.h index e0f05243a8..0e38e08653 100644 --- a/libraries/AP_GPS/AP_GPS_MTK19.h +++ b/libraries/AP_GPS/AP_GPS_MTK19.h @@ -22,7 +22,13 @@ class AP_GPS_MTK19 : public GPS { public: - AP_GPS_MTK19(); + AP_GPS_MTK19() : + GPS(), + _step(0), + _payload_counter(0), + _mtk_revision(0) + {} + virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE); virtual bool read(void); static bool _detect(uint8_t ); diff --git a/libraries/AP_GPS/AP_GPS_NMEA.h b/libraries/AP_GPS/AP_GPS_NMEA.h index 6d3cb2007e..ae513a27a8 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.h +++ b/libraries/AP_GPS/AP_GPS_NMEA.h @@ -52,6 +52,16 @@ class AP_GPS_NMEA : public GPS { public: + AP_GPS_NMEA(void) : + GPS(), + _parity(0), + _is_checksum_term(false), + _sentence_type(0), + _term_number(0), + _term_offset(0), + _gps_data_good(false) + {} + /// Perform a (re)initialisation of the GPS; sends the /// protocol configuration messages. /// diff --git a/libraries/AP_GPS/AP_GPS_None.h b/libraries/AP_GPS/AP_GPS_None.h index 4131bdc0bf..f2d869eadf 100644 --- a/libraries/AP_GPS/AP_GPS_None.h +++ b/libraries/AP_GPS/AP_GPS_None.h @@ -9,6 +9,8 @@ class AP_GPS_None : public GPS { public: + AP_GPS_None() : GPS() {} + virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE) { _port = s; }; diff --git a/libraries/AP_GPS/AP_GPS_SIRF.h b/libraries/AP_GPS/AP_GPS_SIRF.h index 56a785ec53..e6df84c9f6 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.h +++ b/libraries/AP_GPS/AP_GPS_SIRF.h @@ -18,6 +18,15 @@ class AP_GPS_SIRF : public GPS { public: + AP_GPS_SIRF() : + GPS(), + _step(0), + _gather(false), + _payload_length(0), + _payload_counter(0), + _msg_id(0) + {} + virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE); virtual bool read(); static bool _detect(uint8_t data); diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index 2b5676e1d5..58e3196f5a 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -27,6 +27,17 @@ class AP_GPS_UBLOX : public GPS { public: + AP_GPS_UBLOX() : + GPS(), + _step(0), + _msg_id(0), + _payload_length(0), + _payload_counter(0), + _fix_count(0), + _disable_counter(0), + next_fix(false) + {} + // Methods virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE); virtual bool read(); diff --git a/libraries/AP_GPS/GPS.cpp b/libraries/AP_GPS/GPS.cpp index a1618c108d..fcc98fa97c 100644 --- a/libraries/AP_GPS/GPS.cpp +++ b/libraries/AP_GPS/GPS.cpp @@ -17,6 +17,22 @@ extern const AP_HAL::HAL& hal; # define Debug(fmt, args ...) #endif +GPS::GPS(void) : + // ensure all the inherited fields are zeroed + num_sats(0), + new_data(false), + fix(false), + valid_read(false), + last_fix_time(0), + _have_raw_velocity(false), + _status(GPS::NO_FIX), + _last_ground_speed_cm(0), + _velocity_north(0), + _velocity_east(0), + _velocity_down(0) +{ +} + void GPS::update(void) { diff --git a/libraries/AP_GPS/GPS.h b/libraries/AP_GPS/GPS.h index 039b086deb..e34ec10f9f 100644 --- a/libraries/AP_GPS/GPS.h +++ b/libraries/AP_GPS/GPS.h @@ -16,6 +16,7 @@ class GPS { public: + GPS(); /// Update GPS state based on possible bytes received from the module. ///