diff --git a/docs/Configuration.md b/docs/Configuration.md index 06e18f448c..72f52a138c 100644 --- a/docs/Configuration.md +++ b/docs/Configuration.md @@ -134,6 +134,16 @@ save ## CLI command differences from baseflight +### gps_baudrate +reason: simplify + +Cleanflight uses normal baud rate values for gps baudrate, baseflight uses an index. + +If an unsupported baud rate value is used the gps code will select 115200 baud. + +example: `set gps_baudrate = 115200` + + ### gps_type reason: renamed to `gps_provider` for consistency @@ -147,9 +157,9 @@ Cleanflight supports using any RX channel for rssi. Baseflight only supports AU In Cleanflight a value of 0 disables the feature, a higher value indicates the channel number to read RSSI information from. -Example, to use RSSI on AUX1 in Cleanflight set the value to 5, since 5 is the first AUX channel. +Example: to use RSSI on AUX1 in Cleanflight use `set rssi_aux_channel = 5`, since 5 is the first AUX channel. ### failsafe_detect_threshold reason: improved functionality -See failsafe_min_usec and failsafe_max_usec in Failsafe documentation. +See `failsafe_min_usec` and `failsafe_max_usec` in Failsafe documentation. diff --git a/src/config.c b/src/config.c index 86818a8412..725f9251f5 100755 --- a/src/config.c +++ b/src/config.c @@ -58,7 +58,7 @@ void mixerUseConfigs(servoParam_t *servoConfToUse, flight3DConfig_t *flight3DCon #define FLASH_WRITE_ADDR (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG)) // use the last flash pages for storage master_t masterConfig; // master config struct with data independent from profiles profile_t currentProfile; // profile config struct -static const uint8_t EEPROM_CONF_VERSION = 67; +static const uint8_t EEPROM_CONF_VERSION = 68; static void resetAccelerometerTrims(int16_flightDynamicsTrims_t *accelerometerTrims) { @@ -153,9 +153,12 @@ void resetSerialConfig(serialConfig_t *serialConfig) serialConfig->serial_port_2_scenario = lookupScenarioIndex(SCENARIO_GPS_ONLY); serialConfig->serial_port_3_scenario = lookupScenarioIndex(SCENARIO_UNUSED); serialConfig->serial_port_4_scenario = lookupScenarioIndex(SCENARIO_UNUSED); + serialConfig->msp_baudrate = 115200; serialConfig->cli_baudrate = 115200; + serialConfig->gps_baudrate = 115200; serialConfig->gps_passthrough_baudrate = 115200; + serialConfig->reboot_character = 'R'; } @@ -215,7 +218,6 @@ static void resetConf(void) masterConfig.servo_pwm_rate = 50; // gps/nav stuff masterConfig.gps_provider = GPS_NMEA; - masterConfig.gps_initial_baudrate_index = GPS_BAUDRATE_115200; resetSerialConfig(&masterConfig.serialConfig); diff --git a/src/config_master.h b/src/config_master.h index b74f6ab377..09884362e7 100644 --- a/src/config_master.h +++ b/src/config_master.h @@ -52,7 +52,6 @@ typedef struct master_t { // gps-related stuff gpsProvider_e gps_provider; - gpsBaudRate_e gps_initial_baudrate_index; serialConfig_t serialConfig; diff --git a/src/gps_common.c b/src/gps_common.c index c621c134a7..e9063deb21 100644 --- a/src/gps_common.c +++ b/src/gps_common.c @@ -89,6 +89,10 @@ static const gpsInitData_t gpsInitData[] = { { GPS_BAUDRATE_9600, 9600, "", "" } }; +#define GPS_INIT_DATA_ENTRY_COUNT (sizeof(gpsInitData) / sizeof(gpsInitData[0])) + +#define DEFAULT_BAUD_RATE_INDEX 0 + static const uint8_t ubloxInit[] = { 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x05, 0x00, 0xFF, 0x19, // VGS: Course over ground and Ground speed 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x03, 0x00, 0xFD, 0x15, // GSV: GNSS Satellites in View @@ -145,17 +149,25 @@ void gpsUseProfile(gpsProfile_t *gpsProfileToUse) } // When using PWM input GPS usage reduces number of available channels by 2 - see pwm_common.c/pwmInit() -void gpsInit(serialConfig_t *initialSerialConfig, uint8_t baudrateIndex, uint8_t initialGpsProvider, gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile) +void gpsInit(serialConfig_t *initialSerialConfig, uint8_t initialGpsProvider, gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile) { serialConfig = initialSerialConfig; + gpsData.baudrateIndex = 0; + while (gpsInitData[gpsData.baudrateIndex].baudrate != serialConfig->gps_baudrate) { + gpsData.baudrateIndex++; + if (gpsData.baudrateIndex >= GPS_INIT_DATA_ENTRY_COUNT) { + gpsData.baudrateIndex = DEFAULT_BAUD_RATE_INDEX; + break; + } + } + gpsProvider = initialGpsProvider; gpsUseProfile(initialGpsProfile); // init gpsData structure. if we're not actually enabled, don't bother doing anything else gpsSetState(GPS_UNKNOWN); - gpsData.baudrateIndex = baudrateIndex; gpsData.lastMessage = millis(); gpsData.errors = 0; @@ -167,7 +179,7 @@ void gpsInit(serialConfig_t *initialSerialConfig, uint8_t baudrateIndex, uint8_t gpsUsePIDs(pidProfile); // no callback - buffer will be consumed in gpsThread() - gpsPort = openSerialPort(FUNCTION_GPS, NULL, gpsInitData[baudrateIndex].baudrate, mode, SERIAL_NOT_INVERTED); + gpsPort = openSerialPort(FUNCTION_GPS, NULL, gpsInitData[gpsData.baudrateIndex].baudrate, mode, SERIAL_NOT_INVERTED); if (!gpsPort) { featureClear(FEATURE_GPS); return; diff --git a/src/main.c b/src/main.c index 69d515cd78..c8f9ff9c17 100755 --- a/src/main.c +++ b/src/main.c @@ -62,7 +62,7 @@ failsafe_t* failsafeInit(rxConfig_t *intialRxConfig); void pwmInit(drv_pwm_config_t *init); void rxInit(rxConfig_t *rxConfig, failsafe_t *failsafe); void buzzerInit(failsafe_t *initialFailsafe); -void gpsInit(serialConfig_t *serialConfig, uint8_t baudrateIndex, uint8_t initialGpsProvider, gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile); +void gpsInit(serialConfig_t *serialConfig, uint8_t initialGpsProvider, gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile); bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint16_t gyroLpf, uint8_t accHardwareToUse, int16_t magDeclinationFromConfig); void imuInit(void); @@ -201,7 +201,6 @@ void init(void) if (feature(FEATURE_GPS)) { gpsInit( &masterConfig.serialConfig, - masterConfig.gps_initial_baudrate_index, masterConfig.gps_provider, ¤tProfile.gpsProfile, ¤tProfile.pidProfile diff --git a/src/serial_cli.c b/src/serial_cli.c index b8661dbb36..88d44c6967 100644 --- a/src/serial_cli.c +++ b/src/serial_cli.c @@ -177,10 +177,10 @@ const clivalue_t valueTable[] = { { "reboot_character", VAR_UINT8, &masterConfig.serialConfig.reboot_character, 48, 126 }, { "msp_baudrate", VAR_UINT32, &masterConfig.serialConfig.msp_baudrate, 1200, 115200 }, { "cli_baudrate", VAR_UINT32, &masterConfig.serialConfig.cli_baudrate, 1200, 115200 }, + { "gps_baudrate", VAR_UINT32, &masterConfig.serialConfig.gps_baudrate, 0, 115200 }, { "gps_passthrough_baudrate", VAR_UINT32, &masterConfig.serialConfig.gps_passthrough_baudrate, 1200, 115200 }, { "gps_provider", VAR_UINT8, &masterConfig.gps_provider, 0, GPS_PROVIDER_MAX }, - { "gps_initial_baudrate_index", VAR_INT8, &masterConfig.gps_initial_baudrate_index, 0, GPS_BAUDRATE_MAX }, { "serialrx_provider", VAR_UINT8, &masterConfig.rxConfig.serialrx_provider, 0, SERIALRX_PROVIDER_MAX }, diff --git a/src/serial_common.c b/src/serial_common.c index 0d055f4ee9..222043fc8a 100644 --- a/src/serial_common.c +++ b/src/serial_common.c @@ -318,6 +318,8 @@ functionConstraint_t *getConfiguredFunctionConstraint(serialPortFunction_e funct updateSerialRxFunctionConstraint(&configuredFunctionConstraint); break; case FUNCTION_GPS: + configuredFunctionConstraint.maxBaudRate = serialConfig->gps_baudrate; + break; default: break; } diff --git a/src/serial_common.h b/src/serial_common.h index c69d10e83e..c698871223 100644 --- a/src/serial_common.h +++ b/src/serial_common.h @@ -91,10 +91,9 @@ typedef struct serialConfig_s { uint32_t msp_baudrate; uint32_t cli_baudrate; + uint32_t gps_baudrate; uint32_t gps_passthrough_baudrate; - uint32_t hott_baudrate; - uint8_t reboot_character; // which byte is used to reboot. Default 'R', could be changed carefully to something else. } serialConfig_t;