Browse Source

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
master
timecop 13 years ago
parent
commit
58eb2b966f
  1. 4986
      obj/baseflight.hex
  2. 5
      src/board.h
  3. 10
      src/cli.c
  4. 8
      src/config.c
  5. 1
      src/drv_adc.c
  6. 6
      src/drv_bmp085.c
  7. 29
      src/drv_pwm.c
  8. 10
      src/drv_pwm.h
  9. 5
      src/drv_uart.c
  10. 1
      src/drv_uart.h
  11. 2
      src/gps.c
  12. 9
      src/main.c
  13. 4
      src/mw.h
  14. 2
      support/stmloader/stmbootloader.c

4986
obj/baseflight.hex
File diff suppressed because it is too large
View File

5
src/board.h

@ -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

@ -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

8
src/config.c

@ -13,7 +13,7 @@ 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)
{
@ -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;

1
src/drv_adc.c

@ -52,4 +52,3 @@ uint16_t adcGetBattery(void)
{
return adc1Ch4Value;
}

6
src/drv_bmp085.c

@ -33,15 +33,9 @@ typedef struct {
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 );
} bmp085_t;
#define BMP085_I2C_ADDR 0x77

29
src/drv_pwm.c

@ -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;

10
src/drv_pwm.h

@ -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);

5
src/drv_uart.c

@ -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;

1
src/drv_uart.h

@ -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);

2
src/gps.c

@ -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);
}

9
src/main.c

@ -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

@ -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;

2
support/stmloader/stmbootloader.c

@ -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…
Cancel
Save