Merge branch 'master' into serial-cleanup

Conflicts:
	src/main/main.c
	src/main/rx/sbus.c
	src/main/version.h
This commit is contained in:
Dominic Clifton 2015-02-18 19:41:53 +00:00
commit 3e64ce883c
8 changed files with 170 additions and 75 deletions

View File

@ -64,7 +64,7 @@
#ifndef UART3_GPIO
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
#define UART2_GPIO_AF GPIO_AF_7
#define UART3_GPIO_AF GPIO_AF_7
#define UART3_GPIO GPIOB
#define UART3_TX_PINSOURCE GPIO_PinSource10
#define UART3_RX_PINSOURCE GPIO_PinSource11
@ -270,20 +270,20 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode)
if (mode & MODE_TX) {
GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN;
GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, GPIO_AF_7);
GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, UART3_GPIO_AF);
GPIO_Init(UART3_GPIO, &GPIO_InitStructure);
}
if (mode & MODE_RX) {
GPIO_InitStructure.GPIO_Pin = UART3_RX_PIN;
GPIO_PinAFConfig(UART3_GPIO, UART3_RX_PINSOURCE, GPIO_AF_7);
GPIO_PinAFConfig(UART3_GPIO, UART3_RX_PINSOURCE, UART3_GPIO_AF);
GPIO_Init(UART3_GPIO, &GPIO_InitStructure);
}
if (mode & MODE_BIDIR) {
GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN;
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, GPIO_AF_7);
GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, UART3_GPIO_AF);
GPIO_Init(UART3_GPIO, &GPIO_InitStructure);
}

View File

@ -292,7 +292,7 @@ void calculateEstimatedAltitude(uint32_t currentTime)
accAlt = accAlt * barometerConfig->baro_cf_alt + (float)BaroAlt * (1.0f - barometerConfig->baro_cf_alt); // complementary filter for altitude estimation (baro & acc)
vel += vel_acc;
#if 1
#ifdef DEBUG_ALT_HOLD
debug[1] = accSum[2] / accSumCount; // acceleration
debug[2] = vel; // velocity
debug[3] = accAlt; // height

View File

@ -21,11 +21,11 @@ extern int16_t throttleAngleCorrection;
extern uint32_t accTimeSum;
extern int accSumCount;
extern float accVelScale;
extern t_fp_vector EstG;
extern int16_t accSmooth[XYZ_AXIS_COUNT];
extern int32_t accSum[XYZ_AXIS_COUNT];
extern int16_t gyroData[FLIGHT_DYNAMICS_INDEX_COUNT];
extern int16_t smallAngle;
typedef struct rollAndPitchInclination_s {
// absolute angle inclination in multiple of 0.1 degree 180 deg = 1800

View File

@ -35,6 +35,7 @@
#include "common/printf.h"
#include "common/maths.h"
#include "common/axis.h"
#include "common/typeconversion.h"
#ifdef DISPLAY
@ -384,20 +385,20 @@ void showBatteryPage(void)
void showSensorsPage(void)
{
uint8_t rowIndex = PAGE_TITLE_LINE_COUNT;
static const char *format = "%c = %5d %5d %5d";
static const char *format = "%s %5d %5d %5d";
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(" X Y Z");
if (sensors(SENSOR_ACC)) {
tfp_sprintf(lineBuffer, format, 'A', accSmooth[X], accSmooth[Y], accSmooth[Z]);
tfp_sprintf(lineBuffer, format, "ACC", accSmooth[X], accSmooth[Y], accSmooth[Z]);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
}
if (sensors(SENSOR_GYRO)) {
tfp_sprintf(lineBuffer, format, 'G', gyroADC[X], gyroADC[Y], gyroADC[Z]);
tfp_sprintf(lineBuffer, format, "GYR", gyroADC[X], gyroADC[Y], gyroADC[Z]);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
@ -405,12 +406,42 @@ void showSensorsPage(void)
#ifdef MAG
if (sensors(SENSOR_MAG)) {
tfp_sprintf(lineBuffer, format, 'M', magADC[X], magADC[Y], magADC[Z]);
tfp_sprintf(lineBuffer, format, "MAG", magADC[X], magADC[Y], magADC[Z]);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
}
#endif
tfp_sprintf(lineBuffer, format, "I&H", inclination.values.rollDeciDegrees, inclination.values.pitchDeciDegrees, heading);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
uint8_t length;
ftoa(EstG.A[X], lineBuffer);
length = strlen(lineBuffer);
while (length < HALF_SCREEN_CHARACTER_COLUMN_COUNT) {
lineBuffer[length++] = ' ';
lineBuffer[length+1] = 0;
}
ftoa(EstG.A[Y], lineBuffer + length);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
ftoa(EstG.A[Z], lineBuffer);
length = strlen(lineBuffer);
while (length < HALF_SCREEN_CHARACTER_COLUMN_COUNT) {
lineBuffer[length++] = ' ';
lineBuffer[length+1] = 0;
}
ftoa(smallAngle, lineBuffer + length);
padLineBuffer();
i2c_OLED_set_line(rowIndex++);
i2c_OLED_send_string(lineBuffer);
}
#ifdef ENABLE_DEBUG_OLED_PAGE

View File

@ -180,6 +180,44 @@ void init(void)
timerInit(); // timer must be initialized before any channel is allocated
mixerInit(masterConfig.mixerMode, masterConfig.customMixer);
memset(&pwm_params, 0, sizeof(pwm_params));
// when using airplane/wing mixer, servo/motor outputs are remapped
if (masterConfig.mixerMode == MIXER_AIRPLANE || masterConfig.mixerMode == MIXER_FLYING_WING)
pwm_params.airplane = true;
else
pwm_params.airplane = false;
#if defined(USE_USART2) && defined(STM32F10X)
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
#endif
pwm_params.useVbat = feature(FEATURE_VBAT);
pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL);
pwm_params.useParallelPWM = feature(FEATURE_RX_PARALLEL_PWM);
pwm_params.useRSSIADC = feature(FEATURE_RSSI_ADC);
pwm_params.useCurrentMeterADC = feature(FEATURE_CURRENT_METER)
&& masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC;
pwm_params.useLEDStrip = feature(FEATURE_LED_STRIP);
pwm_params.usePPM = feature(FEATURE_RX_PPM);
pwm_params.useOneshot = feature(FEATURE_ONESHOT125);
pwm_params.useSerialRx = feature(FEATURE_RX_SERIAL);
pwm_params.useServos = isMixerUsingServos();
pwm_params.extraServos = currentProfile->gimbalConfig.gimbal_flags & GIMBAL_FORWARDAUX;
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
pwm_params.servoPwmRate = masterConfig.servo_pwm_rate;
pwm_params.idlePulse = PULSE_1MS; // standard PWM for brushless ESC (default, overridden below)
if (feature(FEATURE_3D))
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
if (pwm_params.motorPwmRate > 500)
pwm_params.idlePulse = 0; // brushed motors
pwm_params.servoCenterPulse = masterConfig.escAndServoConfig.servoCenterPulse;
pwmRxInit(masterConfig.inputFilteringMode);
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);
mixerUsePWMOutputConfiguration(pwmOutputConfiguration);
#ifdef BEEPER
beeperConfig_t beeperConfig = {
.gpioPin = BEEP_PIN,
@ -280,56 +318,18 @@ void init(void)
LED0_OFF;
LED1_OFF;
imuInit();
mixerInit(masterConfig.mixerMode, masterConfig.customMixer);
#ifdef MAG
if (sensors(SENSOR_MAG))
compassInit();
#endif
imuInit();
serialInit(&masterConfig.serialConfig);
mspInit(&masterConfig.serialConfig);
cliInit(&masterConfig.serialConfig);
memset(&pwm_params, 0, sizeof(pwm_params));
// when using airplane/wing mixer, servo/motor outputs are remapped
if (masterConfig.mixerMode == MIXER_AIRPLANE || masterConfig.mixerMode == MIXER_FLYING_WING)
pwm_params.airplane = true;
else
pwm_params.airplane = false;
#if defined(USE_USART2) && defined(STM32F10X)
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
#endif
pwm_params.useVbat = feature(FEATURE_VBAT);
pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL);
pwm_params.useParallelPWM = feature(FEATURE_RX_PARALLEL_PWM);
pwm_params.useRSSIADC = feature(FEATURE_RSSI_ADC);
pwm_params.useCurrentMeterADC = feature(FEATURE_CURRENT_METER)
&& masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC;
pwm_params.useLEDStrip = feature(FEATURE_LED_STRIP);
pwm_params.usePPM = feature(FEATURE_RX_PPM);
pwm_params.useOneshot = feature(FEATURE_ONESHOT125);
pwm_params.useSerialRx = feature(FEATURE_RX_SERIAL);
pwm_params.useServos = isMixerUsingServos();
pwm_params.extraServos = currentProfile->gimbalConfig.gimbal_flags & GIMBAL_FORWARDAUX;
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
pwm_params.servoPwmRate = masterConfig.servo_pwm_rate;
pwm_params.idlePulse = PULSE_1MS; // standard PWM for brushless ESC (default, overridden below)
if (feature(FEATURE_3D))
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
if (pwm_params.motorPwmRate > 500)
pwm_params.idlePulse = 0; // brushed motors
pwm_params.servoCenterPulse = masterConfig.escAndServoConfig.servoCenterPulse;
pwmRxInit(masterConfig.inputFilteringMode);
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);
mixerUsePWMOutputConfiguration(pwmOutputConfiguration);
failsafe = failsafeInit(&masterConfig.rxConfig);
beepcodeInit(failsafe);
rxInit(&masterConfig.rxConfig, failsafe);

View File

@ -35,10 +35,33 @@
#include "rx/rx.h"
#include "rx/sbus.h"
/*
* Observations
*
* FrSky X8R
* time between frames: 6ms.
* time to send frame: 3ms.
*
* Futaba R6208SB/R6303SB
* time between frames: 11ms.
* time to send frame: 3ms.
*/
#define SBUS_TIME_NEEDED_PER_FRAME 3000
#ifndef CJMCU
#define DEBUG_SBUS_PACKETS
#endif
#ifdef DEBUG_SBUS_PACKETS
static uint16_t sbusStateFlags = 0;
#define SBUS_MAX_CHANNEL 16
#define SBUS_STATE_FAILSAFE (1 << 0)
#define SBUS_STATE_SIGNALLOSS (1 << 1)
#endif
#define SBUS_MAX_CHANNEL 18
#define SBUS_FRAME_SIZE 25
#define SBUS_FRAME_BEGIN_BYTE 0x0F
@ -46,6 +69,9 @@
#define SBUS_BAUDRATE 100000
#define SBUS_DIGITAL_CHANNEL_MIN 173
#define SBUS_DIGITAL_CHANNEL_MAX 1812
static bool sbusFrameDone = false;
static void sbusDataReceive(uint16_t c);
static uint16_t sbusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
@ -75,8 +101,8 @@ bool sbusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa
return sBusPort != NULL;
}
#define SBUS_FLAG_RESERVED_1 (1 << 0)
#define SBUS_FLAG_RESERVED_2 (1 << 1)
#define SBUS_FLAG_CHANNEL_17 (1 << 0)
#define SBUS_FLAG_CHANNEL_18 (1 << 1)
#define SBUS_FLAG_SIGNAL_LOSS (1 << 2)
#define SBUS_FLAG_FAILSAFE_ACTIVE (1 << 3)
@ -113,23 +139,23 @@ static sbusFrame_t sbusFrame;
// Receive ISR callback
static void sbusDataReceive(uint16_t c)
{
#ifdef DEBUG_SBUS_PACKETS
static uint8_t sbusUnusedFrameCount = 0;
#endif
static uint8_t sbusFramePosition = 0;
static uint32_t sbusTimeoutAt = 0;
static uint32_t sbusFrameStartAt = 0;
uint32_t now = micros();
if ((int32_t)(sbusTimeoutAt - now) < 0) {
int32_t sbusFrameTime = now - sbusFrameStartAt;
if (sbusFrameTime > (long)(SBUS_TIME_NEEDED_PER_FRAME + 500)) {
sbusFramePosition = 0;
}
sbusTimeoutAt = now + 2500;
sbusFrame.bytes[sbusFramePosition] = (uint8_t)c;
if (sbusFramePosition == 0 && c != SBUS_FRAME_BEGIN_BYTE) {
return;
if (sbusFramePosition == 0) {
if (c != SBUS_FRAME_BEGIN_BYTE) {
return;
}
sbusFrameStartAt = now;
}
sbusFramePosition++;
@ -137,14 +163,11 @@ static void sbusDataReceive(uint16_t c)
if (sbusFramePosition == SBUS_FRAME_SIZE) {
if (sbusFrame.frame.endByte == SBUS_FRAME_END_BYTE) {
sbusFrameDone = true;
}
sbusFramePosition = 0;
} else {
#ifdef DEBUG_SBUS_PACKETS
if (sbusFrameDone) {
sbusUnusedFrameCount++;
}
debug[2] = sbusFrameTime;
#endif
}
} else {
sbusFrameDone = false;
}
}
@ -156,11 +179,22 @@ bool sbusFrameComplete(void)
}
sbusFrameDone = false;
#ifdef DEBUG_SBUS_PACKETS
debug[1] = sbusFrame.frame.flags;
#endif
if (sbusFrame.frame.flags & SBUS_FLAG_SIGNAL_LOSS) {
// internal failsafe enabled and rx failsafe flag set
sbusSignalLostEventCount++;
#ifdef DEBUG_SBUS_PACKETS
sbusStateFlags |= SBUS_STATE_SIGNALLOSS;
debug[0] |= SBUS_STATE_SIGNALLOSS;
#endif
}
if (sbusFrame.frame.flags & SBUS_FLAG_FAILSAFE_ACTIVE) {
#ifdef DEBUG_SBUS_PACKETS
sbusStateFlags |= SBUS_STATE_FAILSAFE;
debug[0] = sbusStateFlags;
#endif
// internal failsafe enabled and rx failsafe flag set
return false;
}
@ -181,6 +215,23 @@ bool sbusFrameComplete(void)
sbusChannelData[13] = sbusFrame.frame.chan13;
sbusChannelData[14] = sbusFrame.frame.chan14;
sbusChannelData[15] = sbusFrame.frame.chan15;
if (sbusFrame.frame.flags & SBUS_FLAG_CHANNEL_17) {
sbusChannelData[16] = SBUS_DIGITAL_CHANNEL_MAX;
} else {
sbusChannelData[16] = SBUS_DIGITAL_CHANNEL_MIN;
}
if (sbusFrame.frame.flags & SBUS_FLAG_CHANNEL_18) {
sbusChannelData[17] = SBUS_DIGITAL_CHANNEL_MAX;
} else {
sbusChannelData[17] = SBUS_DIGITAL_CHANNEL_MIN;
}
#ifdef DEBUG_SBUS_PACKETS
sbusStateFlags = 0;
debug[0] = sbusStateFlags;
#endif
return true;
}

View File

@ -19,9 +19,17 @@
#define TARGET_BOARD_IDENTIFIER "103R"
#define LED0_GPIO GPIOD
#define LED0_PIN Pin_2 // PD2 (LED)
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOD
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3 // PB3 (LED)
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOB
#define LED1_GPIO GPIOB
#define LED1_PIN Pin_4 // PB4 (LED)
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOB
#define LED2_GPIO GPIOD
#define LED2_PIN Pin_2 // PD2 (LED) - Labelled LED4
#define LED2_PERIPHERAL RCC_APB2Periph_GPIOD
#define BEEP_GPIO GPIOA
#define BEEP_PIN Pin_12 // PA12 (Beeper)
@ -66,12 +74,17 @@
#define BARO
#define USE_BARO_MS5611
//#define USE_BARO_BMP085
#define USE_BARO_BMP085
#define MAG
#define USE_MAG_HMC5883
#define USE_MAG_AK8975
#define SONAR
#define BEEPER
#define LED0
#define LED1
#define LED2
#define INVERTER
#define DISPLAY

View File

@ -72,7 +72,7 @@
#ifndef UART3_GPIO
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
#define UART2_GPIO_AF GPIO_AF_7
#define UART3_GPIO_AF GPIO_AF_7
#define UART3_GPIO GPIOB
#define UART3_TX_PINSOURCE GPIO_PinSource10
#define UART3_RX_PINSOURCE GPIO_PinSource11