AP_GPS: Remove unneeded intilizers
saves 160 bytes on make px4-v2
This commit is contained in:
parent
cc931e9a2a
commit
53c66106d6
@ -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)
|
||||
{
|
||||
}
|
||||
|
@ -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
|
||||
|
@ -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));
|
||||
|
@ -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;
|
||||
|
||||
|
@ -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");
|
||||
|
@ -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));
|
||||
}
|
||||
|
@ -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();
|
||||
}
|
||||
|
||||
|
@ -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);
|
||||
|
Loading…
Reference in New Issue
Block a user