mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-01 09:24:10 +01:00
OP-1370 - Add an option to store the configuration onto GPS
This commit is contained in:
parent
5bf866c96e
commit
5a3ea5fde0
@ -443,7 +443,8 @@ void updateGpsSettings(__attribute__((unused)) UAVObjEvent *ev)
|
||||
GPSSettingsUBXRateGet(&newconfig.navRate);
|
||||
GPSSettingsUBXDynamicModelGet(&ubxDynamicModel);
|
||||
|
||||
newconfig.autoconfigEnabled = ubxAutoConfig == GPSSETTINGS_UBXAUTOCONFIG_TRUE ? true : false;
|
||||
newconfig.autoconfigEnabled = ubxAutoConfig == GPSSETTINGS_UBXAUTOCONFIG_FALSE ? false : true;
|
||||
newconfig.storeSettings = ubxAutoConfig == GPSSETTINGS_UBXAUTOCONFIG_STORE;
|
||||
newconfig.dynamicModel = ubxDynamicModel == GPSSETTINGS_UBXDYNAMICMODEL_PORTABLE ? UBX_DYNMODEL_PORTABLE :
|
||||
ubxDynamicModel == GPSSETTINGS_UBXDYNAMICMODEL_STATIONARY ? UBX_DYNMODEL_STATIONARY :
|
||||
ubxDynamicModel == GPSSETTINGS_UBXDYNAMICMODEL_PEDESTRIAN ? UBX_DYNMODEL_PEDESTRIAN :
|
||||
|
@ -36,11 +36,11 @@
|
||||
#include "auxmagsensor.h"
|
||||
#include "GPS.h"
|
||||
|
||||
#define UBX_HW_VERSION_8 80000
|
||||
#define UBX_HW_VERSION_7 70000
|
||||
#define UBX_HW_VERSION_8 80000
|
||||
#define UBX_HW_VERSION_7 70000
|
||||
|
||||
#define UBX_SYNC1 0xb5 // UBX protocol synchronization characters
|
||||
#define UBX_SYNC2 0x62
|
||||
#define UBX_SYNC1 0xb5 // UBX protocol synchronization characters
|
||||
#define UBX_SYNC2 0x62
|
||||
|
||||
// From u-blox6 receiver protocol specification
|
||||
|
||||
@ -79,6 +79,7 @@ typedef enum {
|
||||
UBX_ID_CFG_NAV5 = 0x24,
|
||||
UBX_ID_CFG_RATE = 0x08,
|
||||
UBX_ID_CFG_MSG = 0x01,
|
||||
UBX_ID_CFG_CFG = 0x09,
|
||||
} ubx_class_cfg_id;
|
||||
|
||||
typedef enum {
|
||||
|
@ -61,11 +61,17 @@ typedef enum {
|
||||
|
||||
typedef struct {
|
||||
bool autoconfigEnabled;
|
||||
bool storeSettings;
|
||||
int8_t navRate;
|
||||
ubx_config_dynamicmodel_t dynamicModel;
|
||||
} ubx_autoconfig_settings_t;
|
||||
|
||||
// Sent messages for configuration support
|
||||
typedef struct {
|
||||
uint32_t clearMask;
|
||||
uint32_t saveMask;
|
||||
uint32_t loadMask;
|
||||
} __attribute__((packed)) ubx_cfg_cfg_t;
|
||||
|
||||
typedef struct {
|
||||
uint16_t mask;
|
||||
@ -112,9 +118,10 @@ typedef union {
|
||||
struct {
|
||||
UBXSentHeader_t header;
|
||||
union {
|
||||
ubx_cfg_cfg_t cfg_cfg;
|
||||
ubx_cfg_msg_t cfg_msg;
|
||||
ubx_cfg_nav5_t cfg_nav5;
|
||||
ubx_cfg_rate_t cfg_rate;
|
||||
ubx_cfg_msg_t cfg_msg;
|
||||
} payload;
|
||||
uint8_t resvd[2]; // added space for checksum bytes
|
||||
} message;
|
||||
|
@ -35,10 +35,10 @@ typedef enum {
|
||||
INIT_STEP_START,
|
||||
INIT_STEP_ASK_VER,
|
||||
INIT_STEP_WAIT_VER,
|
||||
INIT_STEP_CONFIGURE,
|
||||
INIT_STEP_CONFIGURE_WAIT_ACK,
|
||||
INIT_STEP_ENABLE_SENTENCES,
|
||||
INIT_STEP_ENABLE_SENTENCES_WAIT_ACK,
|
||||
INIT_STEP_CONFIGURE,
|
||||
INIT_STEP_CONFIGURE_WAIT_ACK,
|
||||
INIT_STEP_DONE,
|
||||
INIT_STEP_ERROR,
|
||||
} initSteps_t;
|
||||
@ -155,6 +155,15 @@ void config_nav(uint16_t *bytes_to_send)
|
||||
status->requiredAck.msgID = UBX_ID_CFG_NAV5;
|
||||
}
|
||||
|
||||
void config_save(uint16_t *bytes_to_send)
|
||||
{
|
||||
memset(status->working_packet.buffer, 0, sizeof(UBXSentHeader_t) + sizeof(ubx_cfg_cfg_t));
|
||||
// mask LSB=ioPort|msgConf|infMsg|navConf|rxmConf|||||rinvConf|antConf|....|= MSB
|
||||
status->working_packet.message.payload.cfg_cfg.saveMask = 0x01 | 0x08; // msgConf + navConf
|
||||
*bytes_to_send = prepare_packet(&status->working_packet, UBX_CLASS_CFG, UBX_ID_CFG_CFG, sizeof(ubx_cfg_cfg_t));
|
||||
status->requiredAck.clsID = UBX_CLASS_CFG;
|
||||
status->requiredAck.msgID = UBX_ID_CFG_CFG;
|
||||
}
|
||||
static void configure(uint16_t *bytes_to_send)
|
||||
{
|
||||
switch (status->lastConfigSent) {
|
||||
@ -163,6 +172,13 @@ static void configure(uint16_t *bytes_to_send)
|
||||
break;
|
||||
case LAST_CONFIG_SENT_START + 1:
|
||||
config_nav(bytes_to_send);
|
||||
if (!status->currentSettings.storeSettings) {
|
||||
// skips saving
|
||||
status->lastConfigSent = LAST_CONFIG_SENT_COMPLETED;
|
||||
}
|
||||
break;
|
||||
case LAST_CONFIG_SENT_START + 2:
|
||||
config_save(bytes_to_send);
|
||||
status->lastConfigSent = LAST_CONFIG_SENT_COMPLETED;
|
||||
return;
|
||||
|
||||
@ -190,6 +206,7 @@ static void enable_sentences(__attribute__((unused)) uint16_t *bytes_to_send)
|
||||
status->lastConfigSent = LAST_CONFIG_SENT_COMPLETED;
|
||||
}
|
||||
}
|
||||
|
||||
void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send)
|
||||
{
|
||||
*bytes_to_send = 0;
|
||||
@ -213,7 +230,7 @@ void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send)
|
||||
case INIT_STEP_WAIT_VER:
|
||||
if (ubxHwVersion > 0) {
|
||||
status->lastConfigSent = LAST_CONFIG_SENT_START;
|
||||
status->currentStep = INIT_STEP_CONFIGURE;
|
||||
status->currentStep = INIT_STEP_ENABLE_SENTENCES;
|
||||
status->lastStepTimestampRaw = PIOS_DELAY_GetRaw();
|
||||
return;
|
||||
}
|
||||
@ -236,7 +253,7 @@ void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send)
|
||||
status->lastStepTimestampRaw = PIOS_DELAY_GetRaw();
|
||||
if (status->lastConfigSent == LAST_CONFIG_SENT_COMPLETED) {
|
||||
status->lastConfigSent = LAST_CONFIG_SENT_START;
|
||||
status->currentStep = step_configure ? INIT_STEP_ENABLE_SENTENCES : INIT_STEP_DONE;
|
||||
status->currentStep = step_configure ? INIT_STEP_DONE : INIT_STEP_CONFIGURE;
|
||||
} else {
|
||||
status->currentStep = step_configure ? INIT_STEP_CONFIGURE_WAIT_ACK : INIT_STEP_ENABLE_SENTENCES_WAIT_ACK;
|
||||
}
|
||||
@ -288,20 +305,23 @@ void ubx_autoconfig_set(ubx_autoconfig_settings_t config)
|
||||
}
|
||||
}
|
||||
|
||||
int32_t ubx_autoconfig_get_status(){
|
||||
if(!status){
|
||||
int32_t ubx_autoconfig_get_status()
|
||||
{
|
||||
if (!status) {
|
||||
return UBX_AUTOCONFIG_STATUS_DISABLED;
|
||||
}
|
||||
switch (status->currentStep) {
|
||||
case INIT_STEP_ERROR:
|
||||
return UBX_AUTOCONFIG_STATUS_ERROR;
|
||||
case INIT_STEP_DISABLED:
|
||||
return UBX_AUTOCONFIG_STATUS_DISABLED;
|
||||
case INIT_STEP_DONE:
|
||||
return UBX_AUTOCONFIG_STATUS_DONE;
|
||||
default:
|
||||
break;
|
||||
case INIT_STEP_ERROR:
|
||||
return UBX_AUTOCONFIG_STATUS_ERROR;
|
||||
|
||||
case INIT_STEP_DISABLED:
|
||||
return UBX_AUTOCONFIG_STATUS_DISABLED;
|
||||
|
||||
case INIT_STEP_DONE:
|
||||
return UBX_AUTOCONFIG_STATUS_DONE;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
return UBX_AUTOCONFIG_STATUS_RUNNING;
|
||||
}
|
||||
|
||||
|
@ -4,8 +4,9 @@
|
||||
<field name="DataProtocol" units="" type="enum" elements="1" options="NMEA,UBX" defaultvalue="UBX"/>
|
||||
<field name="MinSattelites" units="" type="uint8" elements="1" defaultvalue="7"/>
|
||||
<field name="MaxPDOP" units="" type="float" elements="1" defaultvalue="3.5"/>
|
||||
<!-- ubx self configuration. Enable to allow the flight board to auto configure ubx GPS options -->
|
||||
<field name="UBXAutoConfig" units="" type="enum" elements="1" options="FALSE,TRUE" defaultvalue="FALSE"/>
|
||||
<!-- ubx self configuration. Enable to allow the flight board to auto configure ubx GPS options,
|
||||
store does AutoConfig and save GPS settings (i.e. to prevent issues if gps is power cycled) -->
|
||||
<field name="UBXAutoConfig" units="" type="enum" elements="1" options="FALSE,TRUE,STORE" defaultvalue="FALSE"/>
|
||||
<!-- ubx position rate, -1 for auto -->
|
||||
<field name="UBXRate" units="Hz" type="int8" elements="1" defaultvalue="5" />
|
||||
<!-- Ubx dynamic model, see UBX datasheet for more details -->
|
||||
|
Loading…
Reference in New Issue
Block a user