mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 04:45:24 +03:00
main uart baud rate commit before tearing stuff up
git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@134 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
da5ac020e1
commit
c98b6b30af
12 changed files with 2584 additions and 2579 deletions
24
src/cli.c
24
src/cli.c
|
@ -70,7 +70,8 @@ typedef enum {
|
|||
VAR_UINT8,
|
||||
VAR_INT8,
|
||||
VAR_UINT16,
|
||||
VAR_INT16
|
||||
VAR_INT16,
|
||||
VAR_UINT32
|
||||
} vartype_e;
|
||||
|
||||
typedef struct {
|
||||
|
@ -104,7 +105,8 @@ const clivalue_t valueTable[] = {
|
|||
{ "tilt_roll_prop", VAR_INT8, &cfg.tilt_roll_prop, -100, 100 },
|
||||
{ "acc_lpf_factor", VAR_UINT8, &cfg.acc_lpf_factor, 0, 32 },
|
||||
{ "gyro_lpf", VAR_UINT16, &cfg.gyro_lpf, 0, 256 },
|
||||
{ "gps_baudrate", VAR_UINT16, &cfg.gps_baudrate, 1200, 57600 },
|
||||
{ "gps_baudrate", VAR_UINT32, &cfg.gps_baudrate, 1200, 115200 },
|
||||
{ "serial_baudrate", VAR_UINT32, &cfg.serial_baudrate, 1200, 115200 },
|
||||
{ "p_pitch", VAR_UINT8, &cfg.P8[PITCH], 0, 200},
|
||||
{ "i_pitch", VAR_UINT8, &cfg.I8[PITCH], 0, 200},
|
||||
{ "d_pitch", VAR_UINT8, &cfg.D8[PITCH], 0, 200},
|
||||
|
@ -350,7 +352,7 @@ static void cliPrintVar(const clivalue_t *var)
|
|||
case VAR_UINT8:
|
||||
value = *(uint8_t *)var->ptr;
|
||||
break;
|
||||
|
||||
|
||||
case VAR_INT8:
|
||||
value = *(int8_t *)var->ptr;
|
||||
break;
|
||||
|
@ -362,6 +364,10 @@ static void cliPrintVar(const clivalue_t *var)
|
|||
case VAR_INT16:
|
||||
value = *(int16_t *)var->ptr;
|
||||
break;
|
||||
|
||||
case VAR_UINT32:
|
||||
value = *(uint32_t *)var->ptr;
|
||||
break;
|
||||
}
|
||||
itoa(value, buf, 10);
|
||||
uartPrint(buf);
|
||||
|
@ -371,19 +377,17 @@ static void cliSetVar(const clivalue_t *var, const int32_t value)
|
|||
{
|
||||
switch (var->type) {
|
||||
case VAR_UINT8:
|
||||
*(uint8_t *)var->ptr = (uint8_t)value;
|
||||
break;
|
||||
|
||||
case VAR_INT8:
|
||||
*(int8_t *)var->ptr = (int8_t)value;
|
||||
*(char *)var->ptr = (char)value;
|
||||
break;
|
||||
|
||||
case VAR_UINT16:
|
||||
*(uint16_t *)var->ptr = (uint16_t)value;
|
||||
case VAR_INT16:
|
||||
*(short *)var->ptr = (short)value;
|
||||
break;
|
||||
|
||||
case VAR_INT16:
|
||||
*(int16_t *)var->ptr = (int16_t)value;
|
||||
case VAR_UINT32:
|
||||
*(int *)var->ptr = (int)value;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -13,7 +13,7 @@ config_t cfg;
|
|||
const char rcChannelLetters[] = "AERT1234";
|
||||
|
||||
static uint32_t enabledSensors = 0;
|
||||
static uint8_t checkNewConf = 9;
|
||||
static uint8_t checkNewConf = 10;
|
||||
|
||||
void parseRcChannels(const char *input)
|
||||
{
|
||||
|
@ -151,6 +151,9 @@ void checkFirstTime(bool reset)
|
|||
// gps baud-rate
|
||||
cfg.gps_baudrate = 9600;
|
||||
|
||||
// serial(uart1) baudrate
|
||||
cfg.serial_baudrate = 115200;
|
||||
|
||||
writeParams();
|
||||
}
|
||||
|
||||
|
|
|
@ -102,7 +102,6 @@ void systemInit(void)
|
|||
// Configure the rest of the stuff
|
||||
adcInit();
|
||||
i2cInit(I2C2);
|
||||
uartInit();
|
||||
|
||||
// sleep for 100ms
|
||||
delay(100);
|
||||
|
|
|
@ -37,7 +37,7 @@ void DMA1_Channel4_IRQHandler(void)
|
|||
uartTxDMA();
|
||||
}
|
||||
|
||||
void uartInit(void)
|
||||
void uartInit(uint32_t speed)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
USART_InitTypeDef USART_InitStructure;
|
||||
|
@ -63,7 +63,7 @@ void uartInit(void)
|
|||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
USART_InitStructure.USART_BaudRate = 115200;
|
||||
USART_InitStructure.USART_BaudRate = speed;
|
||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||
USART_InitStructure.USART_StopBits = USART_StopBits_1;
|
||||
USART_InitStructure.USART_Parity = USART_Parity_No;
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#pragma once
|
||||
|
||||
void uartInit(void);
|
||||
void uartInit(uint32_t speed);
|
||||
uint16_t uartAvailable(void);
|
||||
uint8_t uartRead(void);
|
||||
uint8_t uartReadPoll(void);
|
||||
|
|
|
@ -11,7 +11,7 @@ static void GPS_distance(int32_t lat1, int32_t lon1, int32_t lat2, int32_t lon2,
|
|||
|
||||
void gpsInit(uint32_t baudrate)
|
||||
{
|
||||
uart2Init(9600, GPS_NewData);
|
||||
uart2Init(cfg.gps_baudrate, GPS_NewData);
|
||||
sensorsSet(SENSOR_GPS);
|
||||
}
|
||||
|
||||
|
|
|
@ -173,14 +173,13 @@ static void getEstimatedAttitude(void)
|
|||
static uint32_t previousT;
|
||||
uint32_t currentT = micros();
|
||||
float scale, deltaGyroAngle[3];
|
||||
|
||||
|
||||
scale = (currentT - previousT) * GYRO_SCALE;
|
||||
previousT = currentT;
|
||||
|
||||
// Initialization
|
||||
for (axis = 0; axis < 3; axis++) {
|
||||
deltaGyroAngle[axis] = gyroADC[axis] * scale;
|
||||
|
||||
if (cfg.acc_lpf_factor > 0) {
|
||||
accTemp[axis] = (accTemp[axis] - (accTemp[axis] >> cfg.acc_lpf_factor)) + accADC[axis];
|
||||
accSmooth[axis] = accTemp[axis] >> cfg.acc_lpf_factor;
|
||||
|
|
|
@ -48,6 +48,8 @@ int main(void)
|
|||
readEEPROM();
|
||||
checkFirstTime(false);
|
||||
|
||||
serialInit(cfg.serial_baudrate);
|
||||
|
||||
// We have these sensors
|
||||
sensorsSet(SENSOR_ACC | SENSOR_BARO | SENSOR_MAG);
|
||||
|
||||
|
|
5
src/mw.h
5
src/mw.h
|
@ -180,8 +180,10 @@ typedef struct config_t {
|
|||
int8_t tilt_roll_prop; // servo proportional (tied to angle) ; can be negative to invert movement
|
||||
|
||||
// gps baud-rate
|
||||
uint16_t gps_baudrate;
|
||||
uint32_t gps_baudrate;
|
||||
|
||||
// serial(uart1) baudrate
|
||||
uint32_t serial_baudrate;
|
||||
} config_t;
|
||||
|
||||
extern int16_t gyroZero[3];
|
||||
|
@ -270,6 +272,7 @@ void writeAllMotors(int16_t mc);
|
|||
void mixTable(void);
|
||||
|
||||
// Serial
|
||||
void serialInit(uint32_t baudrate);
|
||||
void serialCom(void);
|
||||
|
||||
// Config
|
||||
|
|
|
@ -15,6 +15,11 @@ void serialize8(uint8_t a)
|
|||
uartWrite(a);
|
||||
}
|
||||
|
||||
void serialInit(uint32_t baudrate)
|
||||
{
|
||||
uartInit(baudrate);
|
||||
}
|
||||
|
||||
void serialCom(void)
|
||||
{
|
||||
uint8_t i;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue