From b3ec5187f20a89f4d9d55dcbe04d169bd3c816e6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 17 Apr 2013 23:00:19 +1000 Subject: [PATCH] AP_GPS: fixed uninitialied variable bugs found with valgrind --- libraries/AP_GPS/AP_GPS_406.cpp | 2 -- libraries/AP_GPS/AP_GPS_Auto.cpp | 1 - libraries/AP_GPS/AP_GPS_HIL.cpp | 1 - libraries/AP_GPS/AP_GPS_MTK.cpp | 2 -- libraries/AP_GPS/AP_GPS_MTK19.cpp | 1 - libraries/AP_GPS/AP_GPS_NMEA.cpp | 2 -- libraries/AP_GPS/AP_GPS_SIRF.cpp | 1 - libraries/AP_GPS/AP_GPS_UBLOX.cpp | 1 - libraries/AP_GPS/GPS.cpp | 8 +++++--- libraries/AP_GPS/GPS.h | 8 -------- 10 files changed, 5 insertions(+), 22 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_406.cpp b/libraries/AP_GPS/AP_GPS_406.cpp index c439339241..917ff9d6c3 100644 --- a/libraries/AP_GPS/AP_GPS_406.cpp +++ b/libraries/AP_GPS/AP_GPS_406.cpp @@ -24,8 +24,6 @@ void AP_GPS_406::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting _configure_gps(); // Function to configure GPS, to output only the desired msg's AP_GPS_SIRF::init(s, nav_setting); // let the superclass do anything it might need here - - idleTimeout = 1200; } // Private Methods ////////////////////////////////////////////////////////////// diff --git a/libraries/AP_GPS/AP_GPS_Auto.cpp b/libraries/AP_GPS/AP_GPS_Auto.cpp index 7fcc162fab..3574698b8a 100644 --- a/libraries/AP_GPS/AP_GPS_Auto.cpp +++ b/libraries/AP_GPS/AP_GPS_Auto.cpp @@ -28,7 +28,6 @@ void AP_GPS_Auto::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting) { _port = s; - idleTimeout = 1200; _nav_setting = nav_setting; } diff --git a/libraries/AP_GPS/AP_GPS_HIL.cpp b/libraries/AP_GPS/AP_GPS_HIL.cpp index 6ac6a5316a..2ae409e5a4 100644 --- a/libraries/AP_GPS/AP_GPS_HIL.cpp +++ b/libraries/AP_GPS/AP_GPS_HIL.cpp @@ -18,7 +18,6 @@ void AP_GPS_HIL::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting) { _port = s; - idleTimeout = 1200; } bool AP_GPS_HIL::read(void) diff --git a/libraries/AP_GPS/AP_GPS_MTK.cpp b/libraries/AP_GPS/AP_GPS_MTK.cpp index 3df0d66d3b..8b2314e549 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK.cpp @@ -43,8 +43,6 @@ AP_GPS_MTK::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting) // set initial epoch code _epoch = TIME_OF_DAY; - - idleTimeout = 1200; } // Process bytes available from the stream diff --git a/libraries/AP_GPS/AP_GPS_MTK19.cpp b/libraries/AP_GPS/AP_GPS_MTK19.cpp index bb538d8c33..3912a7a44a 100644 --- a/libraries/AP_GPS/AP_GPS_MTK19.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK19.cpp @@ -44,7 +44,6 @@ AP_GPS_MTK19::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting) _epoch = TIME_OF_DAY; _time_offset = 0; _offset_calculated = false; - idleTimeout = 1200; } // Process bytes available from the stream diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index 6e2ac54956..a437317cc0 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -103,8 +103,6 @@ void AP_GPS_NMEA::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_settin // send the ublox init strings _port->print_P((const prog_char_t *)_ublox_init_string); - - idleTimeout = 1200; } bool AP_GPS_NMEA::read(void) diff --git a/libraries/AP_GPS/AP_GPS_SIRF.cpp b/libraries/AP_GPS/AP_GPS_SIRF.cpp index acddc9f0d9..a64eb14aab 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.cpp +++ b/libraries/AP_GPS/AP_GPS_SIRF.cpp @@ -37,7 +37,6 @@ AP_GPS_SIRF::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting) // send SiRF binary setup messages _write_progstr_block(_port, (const prog_char *)init_messages, sizeof(init_messages)); - idleTimeout = 1200; } // Process bytes available from the stream diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 31e713dc03..7639ba653a 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -44,7 +44,6 @@ AP_GPS_UBLOX::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting) _port->flush(); _epoch = TIME_OF_WEEK; - idleTimeout = 1200; // configure the GPS for the messages we want _configure_gps(); diff --git a/libraries/AP_GPS/GPS.cpp b/libraries/AP_GPS/GPS.cpp index ea4a9d521b..e4dee11a8e 100644 --- a/libraries/AP_GPS/GPS.cpp +++ b/libraries/AP_GPS/GPS.cpp @@ -19,17 +19,19 @@ extern const AP_HAL::HAL& hal; GPS::GPS(void) : // ensure all the inherited fields are zeroed + time(0), num_sats(0), new_data(false), fix(FIX_NONE), valid_read(false), last_fix_time(0), _have_raw_velocity(false), + _idleTimer(0), _status(GPS::NO_FIX), _last_ground_speed_cm(0), _velocity_north(0), _velocity_east(0), - _velocity_down(0) + _velocity_down(0) { } @@ -44,9 +46,9 @@ GPS::update(void) tnow = hal.scheduler->millis(); - // if we did not get a message, and the idle timer has expired, re-init + // if we did not get a message, and the idle timer of 1.2 seconds has expired, re-init if (!result) { - if ((tnow - _idleTimer) > idleTimeout) { + if ((tnow - _idleTimer) > 1200) { Debug("gps read timeout %lu %lu", (unsigned long)tnow, (unsigned long)_idleTimer); _status = NO_GPS; diff --git a/libraries/AP_GPS/GPS.h b/libraries/AP_GPS/GPS.h index 20f65fb21a..0b66a63a0f 100644 --- a/libraries/AP_GPS/GPS.h +++ b/libraries/AP_GPS/GPS.h @@ -125,14 +125,6 @@ public: virtual void setHIL(uint32_t time, float latitude, float longitude, float altitude, float ground_speed, float ground_course, float speed_3d, uint8_t num_sats); - /// Time in milliseconds after which we will assume the GPS is no longer - /// sending us updates and attempt a re-init. - /// - /// 1200ms allows a small amount of slack over the worst-case 1Hz update - /// rate. - /// - uint32_t idleTimeout; - // components of velocity in 2D, in m/s float velocity_north(void) { return _status >= GPS_OK_FIX_2D ? _velocity_north : 0;