mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
AP_GPS_UBlox: remove unused member
This commit is contained in:
parent
2c33250bee
commit
7d2fe3cc2b
@ -67,8 +67,7 @@ AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UART
|
|||||||
_disable_counter(0),
|
_disable_counter(0),
|
||||||
next_fix(AP_GPS::NO_FIX),
|
next_fix(AP_GPS::NO_FIX),
|
||||||
rate_update_step(0),
|
rate_update_step(0),
|
||||||
_last_5hz_time(0),
|
_last_5hz_time(0)
|
||||||
_last_hw_status(0)
|
|
||||||
{
|
{
|
||||||
// stop any config strings that are pending
|
// stop any config strings that are pending
|
||||||
gps.send_blob_start(state.instance, NULL, 0);
|
gps.send_blob_start(state.instance, NULL, 0);
|
||||||
|
@ -358,7 +358,6 @@ private:
|
|||||||
|
|
||||||
uint8_t rate_update_step;
|
uint8_t rate_update_step;
|
||||||
uint32_t _last_5hz_time;
|
uint32_t _last_5hz_time;
|
||||||
uint32_t _last_hw_status;
|
|
||||||
|
|
||||||
void _configure_navigation_rate(uint16_t rate_ms);
|
void _configure_navigation_rate(uint16_t rate_ms);
|
||||||
void _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
|
void _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
|
||||||
|
Loading…
Reference in New Issue
Block a user