AP_GPS: ensure constructors zero all key variables

this prevents a crash on PX4 if a GPS is attached after startup
This commit is contained in:
Andrew Tridgell 2013-02-20 11:32:15 +11:00
parent 93ef403529
commit f67480fa50
12 changed files with 70 additions and 7 deletions

View File

@ -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);

View File

@ -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)
{
}

View File

@ -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);

View File

@ -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 );

View File

@ -17,12 +17,6 @@
#include "AP_GPS_MTK19.h"
#include <stdint.h>
// 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)

View File

@ -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 );

View File

@ -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.
///

View File

@ -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;
};

View File

@ -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);

View File

@ -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();

View File

@ -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)
{

View File

@ -16,6 +16,7 @@
class GPS
{
public:
GPS();
/// Update GPS state based on possible bytes received from the module.
///