AP_GPS: use const structure for saving GPS config

This commit is contained in:
Peter Barker 2022-01-10 09:38:04 +11:00 committed by Andrew Tridgell
parent 1943de9016
commit 8d17b8dbe7
2 changed files with 7 additions and 6 deletions

View File

@ -1552,7 +1552,7 @@ AP_GPS_UBLOX::_update_checksum(uint8_t *data, uint16_t len, uint8_t &ck_a, uint8
* send a ublox message * send a ublox message
*/ */
bool bool
AP_GPS_UBLOX::_send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint16_t size) AP_GPS_UBLOX::_send_message(uint8_t msg_class, uint8_t msg_id, const void *msg, uint16_t size)
{ {
if (port->txspace() < (sizeof(struct ubx_header) + 2 + size)) { if (port->txspace() < (sizeof(struct ubx_header) + 2 + size)) {
return false; return false;
@ -1697,10 +1697,11 @@ AP_GPS_UBLOX::_configure_config_set(const config_list *list, uint8_t count, uint
void void
AP_GPS_UBLOX::_save_cfg() AP_GPS_UBLOX::_save_cfg()
{ {
ubx_cfg_cfg save_cfg; static const ubx_cfg_cfg save_cfg {
save_cfg.clearMask = 0; clearMask: 0,
save_cfg.saveMask = SAVE_CFG_ALL; saveMask: SAVE_CFG_ALL,
save_cfg.loadMask = 0; loadMask: 0
};
_send_message(CLASS_CFG, MSG_CFG_CFG, &save_cfg, sizeof(save_cfg)); _send_message(CLASS_CFG, MSG_CFG_CFG, &save_cfg, sizeof(save_cfg));
_last_cfg_sent_time = AP_HAL::millis(); _last_cfg_sent_time = AP_HAL::millis();
_num_cfg_save_tries++; _num_cfg_save_tries++;

View File

@ -715,7 +715,7 @@ private:
void _configure_rate(void); void _configure_rate(void);
void _configure_sbas(bool enable); void _configure_sbas(bool enable);
void _update_checksum(uint8_t *data, uint16_t len, uint8_t &ck_a, uint8_t &ck_b); void _update_checksum(uint8_t *data, uint16_t len, uint8_t &ck_a, uint8_t &ck_b);
bool _send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint16_t size); bool _send_message(uint8_t msg_class, uint8_t msg_id, const void *msg, uint16_t size);
void send_next_rate_update(void); void send_next_rate_update(void);
bool _request_message_rate(uint8_t msg_class, uint8_t msg_id); bool _request_message_rate(uint8_t msg_class, uint8_t msg_id);
void _request_next_config(void); void _request_next_config(void);