mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: dynamically allocate config_GNSS
This commit is contained in:
parent
90f7222f98
commit
2af6358c07
|
@ -273,8 +273,6 @@ const AP_GPS_UBLOX::config_list AP_GPS_UBLOX::config_L5_ovrd_dis[] {
|
|||
{ConfigKey::CFG_SIGNAL_L5_HEALTH_OVRD, 0},
|
||||
};
|
||||
|
||||
AP_GPS_UBLOX::config_list AP_GPS_UBLOX::config_GNSS[UBLOX_MAX_GNSS_CONFIG_BLOCKS*3] {};
|
||||
|
||||
void
|
||||
AP_GPS_UBLOX::_request_next_config(void)
|
||||
{
|
||||
|
@ -469,6 +467,7 @@ AP_GPS_UBLOX::_request_next_config(void)
|
|||
// special handling of F9 config
|
||||
if (cfg_count > 0) {
|
||||
CFG_Debug("Sending F9 settings, GNSS=%u", params.gnss_mode);
|
||||
|
||||
if (!_configure_list_valset(config_GNSS, cfg_count, UBX_VALSET_LAYER_RAM | UBX_VALSET_LAYER_BBR)) {
|
||||
_next_message--;
|
||||
break;
|
||||
|
@ -2314,6 +2313,14 @@ uint8_t AP_GPS_UBLOX::populate_F9_gnss(void)
|
|||
// GPS and QZSS should be enabled/disabled together, but we will leave them alone
|
||||
// QZSS and SBAS can only be enabled if GPS is enabled
|
||||
|
||||
if (config_GNSS == nullptr) {
|
||||
config_GNSS = (config_list*)calloc(UBLOX_MAX_GNSS_CONFIG_BLOCKS*3, sizeof(config_list));
|
||||
}
|
||||
|
||||
if (config_GNSS == nullptr) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t gnss_mode = params.gnss_mode;
|
||||
gnss_mode |= 1U<<GNSS_GPS;
|
||||
gnss_mode |= 1U<<GNSS_QZSS;
|
||||
|
|
|
@ -906,7 +906,7 @@ private:
|
|||
static const config_list config_L5_ovrd_ena[];
|
||||
static const config_list config_L5_ovrd_dis[];
|
||||
// scratch space for GNSS config
|
||||
static config_list config_GNSS[UBLOX_MAX_GNSS_CONFIG_BLOCKS*3];
|
||||
config_list* config_GNSS;
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue