added configurable motor and servo period settings (50-498Hz). both set by cli, default is 50 for servo, 400 for motors.
removed feature digital_servo since its now set by cli instead. added proper tx end check into uart, to remove delay inside printing out set values and tx buffer overrun during help() instead of passing a bunch of params to pwm driver, made a config struct fixed a bug in gps baudrate fixed typo in stmloader.c whitespace / indentation cleanups in various drivers git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@137 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
97cdebfb13
commit
58eb2b966f
4986
obj/baseflight.hex
4986
obj/baseflight.hex
File diff suppressed because it is too large
Load Diff
|
@ -27,14 +27,13 @@ typedef enum {
|
|||
FEATURE_PPM = 1 << 0,
|
||||
FEATURE_VBAT = 1 << 1,
|
||||
FEATURE_INFLIGHT_ACC_CAL = 1 << 2,
|
||||
FEATURE_DIGITAL_SERVO = 1 << 3,
|
||||
FEATURE_SPEKTRUM = 1 << 3,
|
||||
FEATURE_MOTOR_STOP = 1 << 4,
|
||||
FEATURE_SERVO_TILT = 1 << 5,
|
||||
FEATURE_CAMTRIG = 1 << 6,
|
||||
FEATURE_GYRO_SMOOTHING = 1 << 7,
|
||||
FEATURE_LED_RING = 1 << 8,
|
||||
FEATURE_GPS = 1 << 9,
|
||||
FEATURE_SPEKTRUM = 1 << 10,
|
||||
FEATURE_GPS = 1 << 9
|
||||
} AvailableFeatures;
|
||||
|
||||
typedef void (* sensorInitFuncPtr)(void); // sensor init prototype
|
||||
|
|
10
src/cli.c
10
src/cli.c
|
@ -34,9 +34,8 @@ const char *mixerNames[] = {
|
|||
|
||||
// sync this with AvailableFeatures enum from board.h
|
||||
const char *featureNames[] = {
|
||||
"PPM", "VBAT", "INFLIGHT_ACC_CAL", "DIGITAL_SERVO", "MOTOR_STOP",
|
||||
"PPM", "VBAT", "INFLIGHT_ACC_CAL", "SPEKTRUM", "MOTOR_STOP",
|
||||
"SERVO_TILT", "CAMTRIG", "GYRO_SMOOTHING", "LED_RING", "GPS",
|
||||
"SPEKTRUM",
|
||||
NULL
|
||||
};
|
||||
|
||||
|
@ -91,6 +90,8 @@ const clivalue_t valueTable[] = {
|
|||
{ "mincommand", VAR_UINT16, &cfg.mincommand, 0, 2000 },
|
||||
{ "mincheck", VAR_UINT16, &cfg.mincheck, 0, 2000 },
|
||||
{ "maxcheck", VAR_UINT16, &cfg.maxcheck, 0, 2000 },
|
||||
{ "motor_pwm_rate", VAR_UINT16, &cfg.motor_pwm_rate, 50, 498 },
|
||||
{ "servo_pwm_rate", VAR_UINT16, &cfg.servo_pwm_rate, 50, 498 },
|
||||
{ "spektrum_hires", VAR_UINT8, &cfg.spektrum_hires, 0, 1 },
|
||||
{ "vbatscale", VAR_UINT8, &cfg.vbatscale, 10, 200 },
|
||||
{ "vbatmaxcellvoltage", VAR_UINT8, &cfg.vbatmaxcellvoltage, 10, 50 },
|
||||
|
@ -261,9 +262,10 @@ static void cliHelp(char *cmdline)
|
|||
|
||||
for (i = 0; i < CMD_COUNT; i++) {
|
||||
uartPrint(cmdTable[i].name);
|
||||
uartWrite(' ');
|
||||
uartWrite('\t');
|
||||
uartPrint(cmdTable[i].param);
|
||||
uartPrint("\r\n");
|
||||
while (!uartTransmitEmpty());
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -410,7 +412,7 @@ static void cliSet(char *cmdline)
|
|||
uartPrint(" = ");
|
||||
cliPrintVar(val);
|
||||
uartPrint("\r\n");
|
||||
delay(10);
|
||||
while (!uartTransmitEmpty());
|
||||
}
|
||||
} else if ((eqptr = strstr(cmdline, "="))) {
|
||||
// has equal, set var
|
||||
|
|
14
src/config.c
14
src/config.c
|
@ -13,12 +13,12 @@ config_t cfg;
|
|||
const char rcChannelLetters[] = "AERT1234";
|
||||
|
||||
static uint32_t enabledSensors = 0;
|
||||
static uint8_t checkNewConf = 10;
|
||||
static uint8_t checkNewConf = 11;
|
||||
|
||||
void parseRcChannels(const char *input)
|
||||
{
|
||||
const char *c, *s;
|
||||
|
||||
|
||||
for (c = input; *c; c++) {
|
||||
s = strchr(rcChannelLetters, *c);
|
||||
if (s)
|
||||
|
@ -39,7 +39,7 @@ void readEEPROM(void)
|
|||
|
||||
for (i = 0; i < 7; i++)
|
||||
lookupRX[i] = (2500 + cfg.rcExpo8 * (i * i - 25)) * i * (int32_t) cfg.rcRate8 / 1250;
|
||||
|
||||
|
||||
cfg.wing_left_mid = constrain(cfg.wing_left_mid, WING_LEFT_MIN, WING_LEFT_MAX); //LEFT
|
||||
cfg.wing_right_mid = constrain(cfg.wing_right_mid, WING_RIGHT_MIN, WING_RIGHT_MAX); //RIGHT
|
||||
cfg.tri_yaw_middle = constrain(cfg.tri_yaw_middle, TRI_YAW_CONSTRAINT_MIN, TRI_YAW_CONSTRAINT_MAX); //REAR
|
||||
|
@ -49,7 +49,7 @@ void writeParams(void)
|
|||
{
|
||||
FLASH_Status status;
|
||||
uint32_t i;
|
||||
|
||||
|
||||
FLASH_Unlock();
|
||||
|
||||
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
|
||||
|
@ -124,7 +124,7 @@ void checkFirstTime(bool reset)
|
|||
cfg.vbatmaxcellvoltage = 43;
|
||||
cfg.vbatmincellvoltage = 33;
|
||||
|
||||
// Radio/ESC
|
||||
// Radio
|
||||
parseRcChannels("AETR1234");
|
||||
cfg.deadband = 0;
|
||||
cfg.yawdeadband = 0;
|
||||
|
@ -132,9 +132,13 @@ void checkFirstTime(bool reset)
|
|||
cfg.midrc = 1500;
|
||||
cfg.mincheck = 1100;
|
||||
cfg.maxcheck = 1900;
|
||||
|
||||
// Motor/ESC/Servo
|
||||
cfg.minthrottle = 1150;
|
||||
cfg.maxthrottle = 1850;
|
||||
cfg.mincommand = 1000;
|
||||
cfg.motor_pwm_rate = 400;
|
||||
cfg.servo_pwm_rate = 50;
|
||||
|
||||
// servos
|
||||
cfg.yaw_direction = 1;
|
||||
|
|
|
@ -6,7 +6,7 @@ void adcInit(void)
|
|||
{
|
||||
ADC_InitTypeDef ADC_InitStructure;
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
|
||||
|
||||
// ADC assumes all the GPIO was already placed in 'AIN' mode
|
||||
|
||||
DMA_DeInit(DMA1_Channel1);
|
||||
|
@ -37,7 +37,7 @@ void adcInit(void)
|
|||
ADC_DMACmd(ADC1, ENABLE);
|
||||
|
||||
ADC_Cmd(ADC1, ENABLE);
|
||||
|
||||
|
||||
// Calibrate ADC
|
||||
ADC_ResetCalibration(ADC1);
|
||||
while(ADC_GetResetCalibrationStatus(ADC1));
|
||||
|
@ -52,4 +52,3 @@ uint16_t adcGetBattery(void)
|
|||
{
|
||||
return adc1Ch4Value;
|
||||
}
|
||||
|
||||
|
|
|
@ -23,11 +23,11 @@ bool adxl345Detect(sensor_t *acc)
|
|||
{
|
||||
bool ack = false;
|
||||
uint8_t sig = 0;
|
||||
|
||||
|
||||
ack = i2cRead(ADXL345_ADDRESS, 0x00, 1, &sig);
|
||||
if (!ack || sig != 0xE5)
|
||||
return false;
|
||||
|
||||
|
||||
acc->init = adxl345Init;
|
||||
acc->read = adxl345Read;
|
||||
acc->align = adxl345Align;
|
||||
|
|
116
src/drv_bmp085.c
116
src/drv_bmp085.c
|
@ -24,55 +24,49 @@ typedef struct {
|
|||
int16_t b2;
|
||||
int16_t mb;
|
||||
int16_t mc;
|
||||
int16_t md;
|
||||
int16_t md;
|
||||
} bmp085_smd500_calibration_param_t;
|
||||
|
||||
typedef struct {
|
||||
bmp085_smd500_calibration_param_t cal_param;
|
||||
uint8_t mode;
|
||||
uint8_t chip_id, ml_version, al_version;
|
||||
uint8_t dev_addr;
|
||||
uint8_t sensortype;
|
||||
|
||||
int32_t param_b5;
|
||||
int16_t oversampling_setting;
|
||||
int16_t smd500_t_resolution, smd500_masterclock;
|
||||
|
||||
// BMP085_BUS_WR_RETURN_TYPE (*bus_write)( BMP085_BUS_WR_PARAM_TYPES );
|
||||
// BMP085_BUS_RD_RETURN_TYPE (*bus_read)( BMP085_BUS_RD_PARAM_TYPES );
|
||||
// BMP085_MDELAY_RETURN_TYPE (*delay_msec)( BMP085_MDELAY_DATA_TYPE );
|
||||
|
||||
typedef struct {
|
||||
bmp085_smd500_calibration_param_t cal_param;
|
||||
uint8_t mode;
|
||||
uint8_t chip_id, ml_version, al_version;
|
||||
uint8_t dev_addr;
|
||||
uint8_t sensortype;
|
||||
int32_t param_b5;
|
||||
int16_t oversampling_setting;
|
||||
int16_t smd500_t_resolution, smd500_masterclock;
|
||||
} bmp085_t;
|
||||
|
||||
#define BMP085_I2C_ADDR 0x77
|
||||
#define BMP085_CHIP_ID 0x55
|
||||
#define BOSCH_PRESSURE_BMP085 85
|
||||
#define BMP085_CHIP_ID_REG 0xD0
|
||||
#define BMP085_VERSION_REG 0xD1
|
||||
#define BMP085_I2C_ADDR 0x77
|
||||
#define BMP085_CHIP_ID 0x55
|
||||
#define BOSCH_PRESSURE_BMP085 85
|
||||
#define BMP085_CHIP_ID_REG 0xD0
|
||||
#define BMP085_VERSION_REG 0xD1
|
||||
#define E_SENSOR_NOT_DETECTED (char) 0
|
||||
#define BMP085_PROM_START__ADDR 0xaa
|
||||
#define BMP085_PROM_DATA__LEN 22
|
||||
#define BMP085_T_MEASURE 0x2E // temperature measurent
|
||||
#define BMP085_P_MEASURE 0x34 // pressure measurement
|
||||
#define BMP085_CTRL_MEAS_REG 0xF4
|
||||
#define BMP085_ADC_OUT_MSB_REG 0xF6
|
||||
#define BMP085_ADC_OUT_LSB_REG 0xF7
|
||||
#define BMP085_CHIP_ID__POS 0
|
||||
#define BMP085_CHIP_ID__MSK 0xFF
|
||||
#define BMP085_CHIP_ID__LEN 8
|
||||
#define BMP085_CHIP_ID__REG BMP085_CHIP_ID_REG
|
||||
#define BMP085_PROM_START__ADDR 0xaa
|
||||
#define BMP085_PROM_DATA__LEN 22
|
||||
#define BMP085_T_MEASURE 0x2E // temperature measurent
|
||||
#define BMP085_P_MEASURE 0x34 // pressure measurement
|
||||
#define BMP085_CTRL_MEAS_REG 0xF4
|
||||
#define BMP085_ADC_OUT_MSB_REG 0xF6
|
||||
#define BMP085_ADC_OUT_LSB_REG 0xF7
|
||||
#define BMP085_CHIP_ID__POS 0
|
||||
#define BMP085_CHIP_ID__MSK 0xFF
|
||||
#define BMP085_CHIP_ID__LEN 8
|
||||
#define BMP085_CHIP_ID__REG BMP085_CHIP_ID_REG
|
||||
|
||||
#define BMP085_ML_VERSION__POS 0
|
||||
#define BMP085_ML_VERSION__LEN 4
|
||||
#define BMP085_ML_VERSION__MSK 0x0F
|
||||
#define BMP085_ML_VERSION__REG BMP085_VERSION_REG
|
||||
#define BMP085_ML_VERSION__POS 0
|
||||
#define BMP085_ML_VERSION__LEN 4
|
||||
#define BMP085_ML_VERSION__MSK 0x0F
|
||||
#define BMP085_ML_VERSION__REG BMP085_VERSION_REG
|
||||
|
||||
|
||||
|
||||
#define BMP085_AL_VERSION__POS 4
|
||||
#define BMP085_AL_VERSION__LEN 4
|
||||
#define BMP085_AL_VERSION__MSK 0xF0
|
||||
#define BMP085_AL_VERSION__REG BMP085_VERSION_REG
|
||||
#define BMP085_AL_VERSION__POS 4
|
||||
#define BMP085_AL_VERSION__LEN 4
|
||||
#define BMP085_AL_VERSION__MSK 0xF0
|
||||
#define BMP085_AL_VERSION__REG BMP085_VERSION_REG
|
||||
|
||||
#define BMP085_GET_BITSLICE(regvar, bitname) (regvar & bitname##__MSK) >> bitname##__POS
|
||||
#define BMP085_SET_BITSLICE(regvar, bitname, val) (regvar & ~bitname##__MSK) | ((val<<bitname##__POS)&bitname##__MSK)
|
||||
|
@ -93,7 +87,7 @@ bool bmp085Init(void)
|
|||
EXTI_InitTypeDef EXTI_InitStructure;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
uint8_t data;
|
||||
|
||||
|
||||
if (bmp085InitDone)
|
||||
return true;
|
||||
|
||||
|
@ -106,7 +100,7 @@ bool bmp085Init(void)
|
|||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
|
||||
GPIO_Init(GPIOC, &GPIO_InitStructure);
|
||||
BARO_ON;
|
||||
|
||||
|
||||
// EXTI interrupt for barometer EOC
|
||||
GPIO_EXTILineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource14);
|
||||
EXTI_InitStructure.EXTI_Line = EXTI_Line14;
|
||||
|
@ -123,16 +117,16 @@ bool bmp085Init(void)
|
|||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
delay(12); // datasheet says 10ms, we'll be careful and do 12.
|
||||
|
||||
|
||||
p_bmp085->sensortype = E_SENSOR_NOT_DETECTED;
|
||||
p_bmp085->dev_addr = BMP085_I2C_ADDR; /* preset BMP085 I2C_addr */
|
||||
i2cRead(p_bmp085->dev_addr, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */
|
||||
p_bmp085->chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID);
|
||||
p_bmp085->oversampling_setting = 2;
|
||||
|
||||
|
||||
if (p_bmp085->chip_id == BMP085_CHIP_ID) { /* get bitslice */
|
||||
p_bmp085->sensortype = BOSCH_PRESSURE_BMP085;
|
||||
|
||||
|
||||
i2cRead(p_bmp085->dev_addr, BMP085_VERSION_REG, 1, &data); /* read Version reg */
|
||||
p_bmp085->ml_version = BMP085_GET_BITSLICE(data, BMP085_ML_VERSION); /* get ML Version */
|
||||
p_bmp085->al_version = BMP085_GET_BITSLICE(data, BMP085_AL_VERSION); /* get AL Version */
|
||||
|
@ -140,7 +134,7 @@ bool bmp085Init(void)
|
|||
bmp085InitDone = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -191,20 +185,20 @@ int32_t bmp085_get_pressure(uint32_t up)
|
|||
{
|
||||
int32_t pressure, x1, x2, x3, b3, b6;
|
||||
uint32_t b4, b7;
|
||||
|
||||
|
||||
b6 = p_bmp085->param_b5 - 4000;
|
||||
// *****calculate B3************
|
||||
x1 = (b6 * b6) >> 12;
|
||||
x1 = (b6 * b6) >> 12;
|
||||
x1 *= p_bmp085->cal_param.b2;
|
||||
x1 >>= 11;
|
||||
|
||||
|
||||
x2 = (p_bmp085->cal_param.ac2 * b6);
|
||||
x2 >>= 11;
|
||||
|
||||
|
||||
x3 = x1 + x2;
|
||||
|
||||
|
||||
b3 = (((((int32_t)p_bmp085->cal_param.ac1) * 4 + x3) << p_bmp085->oversampling_setting) + 2) >> 2;
|
||||
|
||||
|
||||
// *****calculate B4************
|
||||
x1 = (p_bmp085->cal_param.ac3 * b6) >> 13;
|
||||
x2 = (p_bmp085->cal_param.b1 * ((b6 * b6) >> 12) ) >> 16;
|
||||
|
@ -217,13 +211,13 @@ int32_t bmp085_get_pressure(uint32_t up)
|
|||
} else {
|
||||
pressure = (b7 / b4) << 1;
|
||||
}
|
||||
|
||||
|
||||
x1 = pressure >> 8;
|
||||
x1 *= x1;
|
||||
x1 = (x1 * SMD500_PARAM_MG) >> 16;
|
||||
x2 = (pressure * SMD500_PARAM_MH) >> 16;
|
||||
pressure += (x1 + x2 + SMD500_PARAM_MI) >> 4; // pressure in Pa
|
||||
|
||||
pressure += (x1 + x2 + SMD500_PARAM_MI) >> 4; // pressure in Pa
|
||||
|
||||
return pressure;
|
||||
}
|
||||
|
||||
|
@ -272,9 +266,9 @@ uint32_t bmp085_get_up(void)
|
|||
while (!convDone && timeout-- > 0) {
|
||||
__NOP();
|
||||
}
|
||||
|
||||
i2cRead(p_bmp085->dev_addr, BMP085_ADC_OUT_MSB_REG, 3, data);
|
||||
up = (((uint32_t) data[0] << 16) | ((uint32_t) data[1] << 8) | (uint32_t) data[2]) >> (8 - p_bmp085->oversampling_setting);
|
||||
|
||||
i2cRead(p_bmp085->dev_addr, BMP085_ADC_OUT_MSB_REG, 3, data);
|
||||
up = (((uint32_t) data[0] << 16) | ((uint32_t) data[1] << 8) | (uint32_t) data[2]) >> (8 - p_bmp085->oversampling_setting);
|
||||
|
||||
return up;
|
||||
}
|
||||
|
@ -283,7 +277,7 @@ static void bmp085_get_cal_param(void)
|
|||
{
|
||||
uint8_t data[22];
|
||||
i2cRead(p_bmp085->dev_addr, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data);
|
||||
|
||||
|
||||
/*parameters AC1-AC6*/
|
||||
p_bmp085->cal_param.ac1 = (data[0] <<8) | data[1];
|
||||
p_bmp085->cal_param.ac2 = (data[2] <<8) | data[3];
|
||||
|
@ -291,11 +285,11 @@ static void bmp085_get_cal_param(void)
|
|||
p_bmp085->cal_param.ac4 = (data[6] <<8) | data[7];
|
||||
p_bmp085->cal_param.ac5 = (data[8] <<8) | data[9];
|
||||
p_bmp085->cal_param.ac6 = (data[10] <<8) | data[11];
|
||||
|
||||
|
||||
/*parameters B1,B2*/
|
||||
p_bmp085->cal_param.b1 = (data[12] <<8) | data[13];
|
||||
p_bmp085->cal_param.b2 = (data[14] <<8) | data[15];
|
||||
|
||||
|
||||
/*parameters MB,MC,MD*/
|
||||
p_bmp085->cal_param.mb = (data[16] <<8) | data[17];
|
||||
p_bmp085->cal_param.mc = (data[18] <<8) | data[19];
|
||||
|
|
|
@ -1,9 +1,9 @@
|
|||
#include "board.h"
|
||||
|
||||
#define PULSE_1MS (1000) // 1ms pulse width
|
||||
#define PULSE_PERIOD (2500) // pulse period (400Hz)
|
||||
#define PULSE_PERIOD_SERVO_DIGITAL (5000) // pulse period for digital servo (200Hz)
|
||||
#define PULSE_PERIOD_SERVO_ANALOG (20000) // pulse period for analog servo (50Hz)
|
||||
// #define PULSE_PERIOD (2500) // pulse period (400Hz)
|
||||
// #define PULSE_PERIOD_SERVO_DIGITAL (5000) // pulse period for digital servo (200Hz)
|
||||
// #define PULSE_PERIOD_SERVO_ANALOG (20000) // pulse period for analog servo (50Hz)
|
||||
|
||||
// Forward declaration
|
||||
static void pwmIRQHandler(TIM_TypeDef *tim);
|
||||
|
@ -244,7 +244,7 @@ static void pwmInitializeInput(bool usePPM)
|
|||
}
|
||||
}
|
||||
|
||||
bool pwmInit(bool usePPM, bool pwmppmInput, bool useServos, bool useDigitalServos)
|
||||
bool pwmInit(drv_pwm_config_t *init)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure = { 0, };
|
||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = { 0, };
|
||||
|
@ -294,7 +294,7 @@ bool pwmInit(bool usePPM, bool pwmppmInput, bool useServos, bool useDigitalServo
|
|||
#endif
|
||||
|
||||
// use PPM or PWM input
|
||||
usePPMFlag = usePPM;
|
||||
usePPMFlag = init->usePPM;
|
||||
|
||||
// preset channels to center
|
||||
for (i = 0; i < 8; i++)
|
||||
|
@ -302,7 +302,7 @@ bool pwmInit(bool usePPM, bool pwmppmInput, bool useServos, bool useDigitalServo
|
|||
|
||||
// Timers run at 1mhz.
|
||||
// TODO: clean this shit up. Make it all dynamic etc.
|
||||
if (pwmppmInput)
|
||||
if (init->enableInput)
|
||||
pwmInitializeInput(usePPMFlag);
|
||||
|
||||
// Output pins
|
||||
|
@ -317,17 +317,14 @@ bool pwmInit(bool usePPM, bool pwmppmInput, bool useServos, bool useDigitalServo
|
|||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (72 - 1);
|
||||
|
||||
if (useServos) {
|
||||
// 50Hz/200Hz period on ch1, 2 for servo
|
||||
if (useDigitalServos)
|
||||
TIM_TimeBaseStructure.TIM_Period = PULSE_PERIOD_SERVO_DIGITAL - 1;
|
||||
else
|
||||
TIM_TimeBaseStructure.TIM_Period = PULSE_PERIOD_SERVO_ANALOG - 1;
|
||||
if (init->useServos) {
|
||||
// ch1, 2 for servo
|
||||
TIM_TimeBaseStructure.TIM_Period = (1000000 / init->servoPwmRate) - 1;
|
||||
TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseStructure.TIM_Period = PULSE_PERIOD - 1;
|
||||
TIM_TimeBaseStructure.TIM_Period = (1000000 / init->motorPwmRate) - 1;
|
||||
TIM_TimeBaseInit(TIM4, &TIM_TimeBaseStructure);
|
||||
} else {
|
||||
TIM_TimeBaseStructure.TIM_Period = PULSE_PERIOD - 1;
|
||||
TIM_TimeBaseStructure.TIM_Period = (1000000 / init->motorPwmRate) - 1;
|
||||
TIM_TimeBaseInit(TIM1, &TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseInit(TIM4, &TIM_TimeBaseStructure);
|
||||
}
|
||||
|
@ -354,9 +351,9 @@ bool pwmInit(bool usePPM, bool pwmppmInput, bool useServos, bool useDigitalServo
|
|||
TIM_CtrlPWMOutputs(TIM4, ENABLE);
|
||||
|
||||
// turn on more motor outputs if we're using ppm / not using pwm input
|
||||
if (!pwmppmInput || usePPM) {
|
||||
if (!init->enableInput || init->usePPM) {
|
||||
// PWM 7,8,9,10
|
||||
TIM_TimeBaseStructure.TIM_Period = PULSE_PERIOD - 1;
|
||||
TIM_TimeBaseStructure.TIM_Period = (1000000 / init->motorPwmRate) - 1;
|
||||
TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
|
||||
|
||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
|
||||
|
|
|
@ -1,6 +1,14 @@
|
|||
#pragma once
|
||||
|
||||
bool pwmInit(bool usePPM, bool pwmppmInput, bool useServos, bool useDigitalServos); // returns whether driver is asking to calibrate throttle or not
|
||||
typedef struct drv_pwm_config_t {
|
||||
bool enableInput;
|
||||
bool usePPM;
|
||||
bool useServos;
|
||||
uint16_t motorPwmRate;
|
||||
uint16_t servoPwmRate;
|
||||
} drv_pwm_config_t;
|
||||
|
||||
bool pwmInit(drv_pwm_config_t *init); // returns whether driver is asking to calibrate throttle or not
|
||||
void pwmWrite(uint8_t channel, uint16_t value);
|
||||
uint16_t pwmRead(uint8_t channel);
|
||||
uint8_t pwmGetNumOutputChannels(void);
|
||||
|
|
|
@ -1,9 +1,9 @@
|
|||
#include "board.h"
|
||||
|
||||
// Cycle counter stuff - these should be defined by CMSIS, but they aren't
|
||||
#define DWT_CTRL (*(volatile uint32_t *)0xE0001000)
|
||||
#define DWT_CYCCNT ((volatile uint32_t *)0xE0001004)
|
||||
#define CYCCNTENA (1 << 0)
|
||||
#define DWT_CTRL (*(volatile uint32_t *)0xE0001000)
|
||||
#define DWT_CYCCNT ((volatile uint32_t *)0xE0001004)
|
||||
#define CYCCNTENA (1 << 0)
|
||||
|
||||
// cycles per microsecond
|
||||
static volatile uint32_t usTicks = 0;
|
||||
|
@ -13,14 +13,14 @@ static volatile uint32_t sysTickCycleCounter = 0;
|
|||
|
||||
static void cycleCounterInit(void)
|
||||
{
|
||||
RCC_ClocksTypeDef clocks;
|
||||
RCC_GetClocksFreq(&clocks);
|
||||
usTicks = clocks.SYSCLK_Frequency / 1000000;
|
||||
RCC_ClocksTypeDef clocks;
|
||||
RCC_GetClocksFreq(&clocks);
|
||||
usTicks = clocks.SYSCLK_Frequency / 1000000;
|
||||
|
||||
// enable DWT access
|
||||
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
|
||||
// enable the CPU cycle counter
|
||||
DWT_CTRL |= CYCCNTENA;
|
||||
// enable the CPU cycle counter
|
||||
DWT_CTRL |= CYCCNTENA;
|
||||
}
|
||||
|
||||
|
||||
|
@ -75,9 +75,9 @@ void systemInit(void)
|
|||
|
||||
// Turn off JTAG port 'cause we're using the GPIO for leds
|
||||
GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE);
|
||||
|
||||
|
||||
// Configure gpio
|
||||
|
||||
|
||||
// PB3, PB4 (LEDs)
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3 | GPIO_Pin_4;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
|
@ -95,48 +95,48 @@ void systemInit(void)
|
|||
|
||||
// Init cycle counter
|
||||
cycleCounterInit();
|
||||
|
||||
|
||||
// SysTick
|
||||
SysTick_Config(SystemCoreClock / 1000);
|
||||
|
||||
// Configure the rest of the stuff
|
||||
adcInit();
|
||||
i2cInit(I2C2);
|
||||
|
||||
|
||||
// sleep for 100ms
|
||||
delay(100);
|
||||
}
|
||||
|
||||
void delayMicroseconds(uint32_t us)
|
||||
{
|
||||
uint32_t elapsed = 0;
|
||||
uint32_t lastCount = *DWT_CYCCNT;
|
||||
uint32_t elapsed = 0;
|
||||
uint32_t lastCount = *DWT_CYCCNT;
|
||||
|
||||
for (;;) {
|
||||
register uint32_t current_count = *DWT_CYCCNT;
|
||||
uint32_t elapsed_us;
|
||||
for (;;) {
|
||||
register uint32_t current_count = *DWT_CYCCNT;
|
||||
uint32_t elapsed_us;
|
||||
|
||||
// measure the time elapsed since the last time we checked
|
||||
elapsed += current_count - lastCount;
|
||||
lastCount = current_count;
|
||||
// measure the time elapsed since the last time we checked
|
||||
elapsed += current_count - lastCount;
|
||||
lastCount = current_count;
|
||||
|
||||
// convert to microseconds
|
||||
elapsed_us = elapsed / usTicks;
|
||||
if (elapsed_us >= us)
|
||||
break;
|
||||
// convert to microseconds
|
||||
elapsed_us = elapsed / usTicks;
|
||||
if (elapsed_us >= us)
|
||||
break;
|
||||
|
||||
// reduce the delay by the elapsed time
|
||||
us -= elapsed_us;
|
||||
// reduce the delay by the elapsed time
|
||||
us -= elapsed_us;
|
||||
|
||||
// keep fractional microseconds for the next iteration
|
||||
elapsed %= usTicks;
|
||||
}
|
||||
// keep fractional microseconds for the next iteration
|
||||
elapsed %= usTicks;
|
||||
}
|
||||
}
|
||||
|
||||
void delay(uint32_t ms)
|
||||
{
|
||||
while (ms--)
|
||||
delayMicroseconds(1000);
|
||||
while (ms--)
|
||||
delayMicroseconds(1000);
|
||||
}
|
||||
|
||||
void failureMode(uint8_t mode)
|
||||
|
|
|
@ -112,6 +112,11 @@ uint16_t uartAvailable(void)
|
|||
return (DMA_GetCurrDataCounter(DMA1_Channel5) != rxDMAPos) ? true : false;
|
||||
}
|
||||
|
||||
bool uartTransmitEmpty(void)
|
||||
{
|
||||
return (txBufferTail == txBufferHead);
|
||||
}
|
||||
|
||||
uint8_t uartRead(void)
|
||||
{
|
||||
uint8_t ch;
|
||||
|
|
|
@ -2,6 +2,7 @@
|
|||
|
||||
void uartInit(uint32_t speed);
|
||||
uint16_t uartAvailable(void);
|
||||
bool uartTransmitEmpty(void);
|
||||
uint8_t uartRead(void);
|
||||
uint8_t uartReadPoll(void);
|
||||
void uartWrite(uint8_t ch);
|
||||
|
|
|
@ -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(cfg.gps_baudrate, GPS_NewData);
|
||||
uart2Init(baudrate, GPS_NewData);
|
||||
sensorsSet(SENSOR_GPS);
|
||||
}
|
||||
|
||||
|
|
|
@ -33,6 +33,7 @@ void throttleCalibration(void)
|
|||
int main(void)
|
||||
{
|
||||
uint8_t i;
|
||||
drv_pwm_config_t pwm_params;
|
||||
|
||||
#if 0
|
||||
// using this to write asm for bootloader :)
|
||||
|
@ -55,7 +56,13 @@ int main(void)
|
|||
|
||||
mixerInit(); // this will set useServo var depending on mixer type
|
||||
// pwmInit returns true if throttle calibration is requested. if so, do it here. throttleCalibration() does NOT return - for safety.
|
||||
if (pwmInit(feature(FEATURE_PPM), !feature(FEATURE_SPEKTRUM), useServo, feature(FEATURE_DIGITAL_SERVO)))
|
||||
pwm_params.usePPM = feature(FEATURE_PPM);
|
||||
pwm_params.enableInput = !feature(FEATURE_SPEKTRUM); // disable inputs if using spektrum
|
||||
pwm_params.useServos = useServo;
|
||||
pwm_params.motorPwmRate = cfg.motor_pwm_rate;
|
||||
pwm_params.servoPwmRate = cfg.servo_pwm_rate;
|
||||
|
||||
if (pwmInit(&pwm_params))
|
||||
throttleCalibration(); // noreturn
|
||||
|
||||
// configure PWM/CPPM read function. spektrum will override that
|
||||
|
|
4
src/mw.h
4
src/mw.h
|
@ -163,9 +163,13 @@ typedef struct config_t {
|
|||
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
|
||||
uint16_t mincheck; // minimum rc end
|
||||
uint16_t maxcheck; // maximum rc end
|
||||
|
||||
// motor/esc/servo related stuff
|
||||
uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
|
||||
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
|
||||
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
|
||||
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
|
||||
uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
|
||||
|
||||
// mixer-related configuration
|
||||
int8_t yaw_direction;
|
||||
|
|
|
@ -320,7 +320,7 @@ void stmLoader(serialStruct_t *s, FILE *fp, unsigned char overrideParity) {
|
|||
printf("Flashing device...\n");
|
||||
jumpAddress = stmHexLoader(s, fp);
|
||||
if (jumpAddress) {
|
||||
printf("\nFlash complete, cylce power\n");
|
||||
printf("\nFlash complete, cycle power\n");
|
||||
|
||||
go:
|
||||
// send GO command
|
||||
|
|
Loading…
Reference in New Issue