mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: initialise _step to zero in all drivers
new() does not zero-fill memory
This commit is contained in:
parent
64734dc51c
commit
252d11ccfa
|
@ -23,6 +23,8 @@ AP_GPS_MTK::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting)
|
|||
{
|
||||
_port = s;
|
||||
_port->flush();
|
||||
_step = 0;
|
||||
|
||||
// initialize serial port for binary protocol use
|
||||
// XXX should assume binary, let GPS_AUTO handle dynamic config?
|
||||
_port->print(MTK_SET_BINARY);
|
||||
|
|
|
@ -22,6 +22,7 @@ AP_GPS_MTK16::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting)
|
|||
{
|
||||
_port = s;
|
||||
_port->flush();
|
||||
_step = 0;
|
||||
|
||||
// initialize serial port for binary protocol use
|
||||
// XXX should assume binary, let GPS_AUTO handle dynamic config?
|
||||
|
|
|
@ -18,6 +18,7 @@
|
|||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
AP_GPS_MTK19::AP_GPS_MTK19() : GPS()
|
||||
{
|
||||
_step = 0;
|
||||
}
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -29,6 +29,7 @@ AP_GPS_SIRF::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting)
|
|||
{
|
||||
_port = s;
|
||||
_port->flush();
|
||||
_step = 0;
|
||||
|
||||
// For modules that default to something other than SiRF binary,
|
||||
// the module-specific subclass should take care of switching to binary mode
|
||||
|
|
|
@ -50,6 +50,7 @@ AP_GPS_UBLOX::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting)
|
|||
_configure_gps();
|
||||
|
||||
_nav_setting = nav_setting;
|
||||
_step = 0;
|
||||
}
|
||||
|
||||
// Process bytes available from the stream
|
||||
|
|
Loading…
Reference in New Issue