mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_GPS: add SAVE_CFG parameter make ublox config saving optional
This commit is contained in:
parent
e82df48631
commit
bc708f9808
@ -108,6 +108,13 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
// @RebootRequired: True
|
||||
AP_GROUPINFO("GNSS_MODE", 10, AP_GPS, _gnss_mode, 0),
|
||||
|
||||
// @Param: SAVE_CFG
|
||||
// @DisplayName: Save GPS configuration
|
||||
// @Description: Determines whether the configuration for this GPS should be written to non-volatile memory on the GPS. Currently working for UBlox.
|
||||
// @Values: 0:Do not save config,1:Save config
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SAVE_CFG", 11, AP_GPS, _save_config, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -317,6 +317,7 @@ public:
|
||||
AP_Int8 _min_elevation;
|
||||
AP_Int8 _raw_data;
|
||||
AP_Int8 _gnss_mode;
|
||||
AP_Int8 _save_config;
|
||||
|
||||
// handle sending of initialisation strings to the GPS
|
||||
void send_blob_start(uint8_t instance, const char *_blob, uint16_t size);
|
||||
|
@ -157,7 +157,7 @@ AP_GPS_UBLOX::read(void)
|
||||
|
||||
if (need_rate_update) {
|
||||
send_next_rate_update();
|
||||
}else if(!_cfg_saved) { //save the configuration sent until now
|
||||
}else if(!_cfg_saved && gps._save_config) { //save the configuration sent until now
|
||||
_save_cfg();
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user