1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 04:45:24 +03:00

added gps baudrage config setting

renamed gcc startup file to .S (breaks some lunix dudes apparently)
ppm sum handler waws hardcoded to TIM2 instead of using passed parameter. fixed. (thanks sbaron)
invalid data from pwm/ppm read are returned as midrc, not 1500. (robert_b)


git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@133 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop 2012-03-27 12:55:44 +00:00
parent 791d67b4ee
commit da5ac020e1
9 changed files with 2413 additions and 2395 deletions

View file

@ -2,14 +2,18 @@
#include "mw.h"
#include <string.h>
#ifndef FLASH_PAGE_COUNT
#define FLASH_PAGE_COUNT 64
#endif
#define FLASH_PAGE_SIZE ((uint16_t)0x400)
#define FLASH_WRITE_ADDR (0x08000000 + (uint32_t)FLASH_PAGE_SIZE * 63) // use the last KB for storage
#define FLASH_WRITE_ADDR (0x08000000 + (uint32_t)FLASH_PAGE_SIZE * (FLASH_PAGE_COUNT - 1)) // use the last KB for storage
config_t cfg;
const char rcChannelLetters[] = "AERT1234";
static uint32_t enabledSensors = 0;
static uint8_t checkNewConf = 8;
static uint8_t checkNewConf = 9;
void parseRcChannels(const char *input)
{
@ -144,6 +148,9 @@ void checkFirstTime(bool reset)
cfg.tilt_pitch_prop = 10;
cfg.tilt_roll_prop = 10;
// gps baud-rate
cfg.gps_baudrate = 9600;
writeParams();
}