From 53c66106d63ff710de7f24972945e64586a5100d Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Wed, 16 May 2018 00:26:53 -0700 Subject: [PATCH] AP_GPS: Remove unneeded intilizers saves 160 bytes on make px4-v2 --- libraries/AP_GPS/AP_GPS_ERB.cpp | 7 ------- libraries/AP_GPS/AP_GPS_MAV.cpp | 1 - libraries/AP_GPS/AP_GPS_NMEA.cpp | 8 +------- libraries/AP_GPS/AP_GPS_NOVA.cpp | 4 +--- libraries/AP_GPS/AP_GPS_SBP.cpp | 8 +------- libraries/AP_GPS/AP_GPS_SIRF.cpp | 7 +------ libraries/AP_GPS/AP_GPS_UAVCAN.cpp | 1 - libraries/AP_GPS/AP_GPS_UBLOX.cpp | 18 +----------------- 8 files changed, 5 insertions(+), 49 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_ERB.cpp b/libraries/AP_GPS/AP_GPS_ERB.cpp index ab789c432b..90a7399fde 100644 --- a/libraries/AP_GPS/AP_GPS_ERB.cpp +++ b/libraries/AP_GPS/AP_GPS_ERB.cpp @@ -34,13 +34,6 @@ extern const AP_HAL::HAL& hal; AP_GPS_ERB::AP_GPS_ERB(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : AP_GPS_Backend(_gps, _state, _port), - _step(0), - _msg_id(0), - _payload_length(0), - _payload_counter(0), - _fix_count(0), - _new_position(0), - _new_speed(0), next_fix(AP_GPS::NO_FIX) { } diff --git a/libraries/AP_GPS/AP_GPS_MAV.cpp b/libraries/AP_GPS/AP_GPS_MAV.cpp index 92fb607948..9b186be826 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.cpp +++ b/libraries/AP_GPS/AP_GPS_MAV.cpp @@ -22,7 +22,6 @@ AP_GPS_MAV::AP_GPS_MAV(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : AP_GPS_Backend(_gps, _state, _port) { - _new_data = false; } // Reading does nothing in this class; we simply return whether or not diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index 7890e1d65a..e6524f50a6 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -51,13 +51,7 @@ extern const AP_HAL::HAL& hal; #define hexdigit(x) ((x)>9?'A'+((x)-10):'0'+(x)) AP_GPS_NMEA::AP_GPS_NMEA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : - AP_GPS_Backend(_gps, _state, _port), - _parity(0), - _is_checksum_term(false), - _sentence_type(0), - _term_number(0), - _term_offset(0), - _gps_data_good(false) + AP_GPS_Backend(_gps, _state, _port) { // this guarantees that _term is always nul terminated memset(_term, 0, sizeof(_term)); diff --git a/libraries/AP_GPS/AP_GPS_NOVA.cpp b/libraries/AP_GPS/AP_GPS_NOVA.cpp index 33d6dae3bf..bd7c3293e5 100644 --- a/libraries/AP_GPS/AP_GPS_NOVA.cpp +++ b/libraries/AP_GPS/AP_GPS_NOVA.cpp @@ -40,9 +40,7 @@ do { \ AP_GPS_NOVA::AP_GPS_NOVA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : - AP_GPS_Backend(_gps, _state, _port), - _new_position(0), - _new_speed(0) + AP_GPS_Backend(_gps, _state, _port) { nova_msg.nova_state = nova_msg_parser::PREAMBLE1; diff --git a/libraries/AP_GPS/AP_GPS_SBP.cpp b/libraries/AP_GPS/AP_GPS_SBP.cpp index 536e0f81c2..ec271d3b1b 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.cpp +++ b/libraries/AP_GPS/AP_GPS_SBP.cpp @@ -46,13 +46,7 @@ do { \ AP_GPS_SBP::AP_GPS_SBP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : - AP_GPS_Backend(_gps, _state, _port), - - last_injected_data_ms(0), - last_iar_num_hypotheses(0), - last_full_update_tow(0), - last_full_update_cpu_ms(0), - crc_error_counter(0) + AP_GPS_Backend(_gps, _state, _port) { Debug("SBP Driver Initialized"); diff --git a/libraries/AP_GPS/AP_GPS_SIRF.cpp b/libraries/AP_GPS/AP_GPS_SIRF.cpp index f70b631a31..ef1e4b4559 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.cpp +++ b/libraries/AP_GPS/AP_GPS_SIRF.cpp @@ -33,12 +33,7 @@ const uint8_t AP_GPS_SIRF::_initialisation_blob[] = { }; AP_GPS_SIRF::AP_GPS_SIRF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : - AP_GPS_Backend(_gps, _state, _port), - _step(0), - _gather(false), - _payload_length(0), - _payload_counter(0), - _msg_id(0) + AP_GPS_Backend(_gps, _state, _port) { gps.send_blob_start(state.instance, (const char *)_initialisation_blob, sizeof(_initialisation_blob)); } diff --git a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp b/libraries/AP_GPS/AP_GPS_UAVCAN.cpp index 6fe1b8b41b..cb7f6879f6 100644 --- a/libraries/AP_GPS/AP_GPS_UAVCAN.cpp +++ b/libraries/AP_GPS/AP_GPS_UAVCAN.cpp @@ -31,7 +31,6 @@ extern const AP_HAL::HAL& hal; AP_GPS_UAVCAN::AP_GPS_UAVCAN(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : AP_GPS_Backend(_gps, _state, _port) { - _new_data = false; _sem_gnss = hal.util->new_semaphore(); } diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 3ffdf2d22f..8a012d1551 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -45,28 +45,12 @@ extern const AP_HAL::HAL& hal; AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : AP_GPS_Backend(_gps, _state, _port), - _step(0), - _msg_id(0), - _payload_length(0), - _payload_counter(0), - _class(0), - _cfg_saved(false), - _last_cfg_sent_time(0), - _num_cfg_save_tries(0), - _last_config_time(0), - _delay_time(0), _next_message(STEP_PVT), _ublox_port(255), - _have_version(false), _unconfigured_messages(CONFIG_ALL), _hardware_generation(UBLOX_UNKNOWN_HARDWARE_GENERATION), - _new_position(0), - _new_speed(0), - _disable_counter(0), next_fix(AP_GPS::NO_FIX), - _cfg_needs_save(false), - noReceivedHdop(true), - havePvtMsg(false) + noReceivedHdop(true) { // stop any config strings that are pending gps.send_blob_start(state.instance, nullptr, 0);