Merge branch 'port-changes' of https://github.com/ledvinap/cleanflight into ledvinap-port-changes

Conflicts:
	src/main/blackbox/blackbox.c
	src/main/io/serial.c
This commit is contained in:
Dominic Clifton 2015-03-09 22:23:04 +01:00
commit bce6c6722c
25 changed files with 162 additions and 89 deletions

View File

@ -559,12 +559,12 @@ CFLAGS = $(ARCH_FLAGS) \
-D'__TARGET__="$(TARGET)"' \
-D'__REVISION__="$(REVISION)"' \
-save-temps=obj \
-MMD
-MMD -MP
ASFLAGS = $(ARCH_FLAGS) \
-x assembler-with-cpp \
$(addprefix -I,$(INCLUDE_DIRS)) \
-MMD
-MMD -MP
LDFLAGS = -lm \
-nostartfiles \

View File

@ -27,6 +27,7 @@
#include "common/axis.h"
#include "common/color.h"
#include "common/encoding.h"
#include "common/utils.h"
#include "drivers/gpio.h"
#include "drivers/sensor.h"
@ -88,11 +89,6 @@
typedef char assert_failed_ ## name [(condition) ? 1 : -1 ]
// Some macros to make writing FLIGHT_LOG_FIELD_* constants shorter:
#define STR_HELPER(x) #x
#define STR(x) STR_HELPER(x)
#define CONCAT_HELPER(x,y) x ## y
#define CONCAT(x,y) CONCAT_HELPER(x, y)
#define PREDICT(x) CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x)
#define ENCODING(x) CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x)

View File

@ -21,6 +21,12 @@
#define ARRAYLEN(x) (sizeof(x) / sizeof((x)[0]))
#define CONCAT_HELPER(x,y) x ## y
#define CONCAT(x,y) CONCAT_HELPER(x, y)
#define STR_HELPER(x) #x
#define STR(x) STR_HELPER(x)
/*
http://resnet.uoregon.edu/~gurney_j/jmpc/bitwise.html
*/

View File

@ -720,16 +720,12 @@ void validateAndFixConfig(void)
#if defined(LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
if (feature(FEATURE_SOFTSERIAL) && (
0
#ifdef USE_SOFTSERIAL1
(LED_STRIP_TIMER == SOFTSERIAL_1_TIMER)
#else
0
|| (LED_STRIP_TIMER == SOFTSERIAL_1_TIMER)
#endif
||
#ifdef USE_SOFTSERIAL2
(LED_STRIP_TIMER == SOFTSERIAL_2_TIMER)
#else
0
|| (LED_STRIP_TIMER == SOFTSERIAL_2_TIMER)
#endif
)) {
// led strip needs the same timer as softserial

View File

@ -24,6 +24,7 @@
#include "system.h"
#include "adc.h"
#include "adc_impl.h"
//#define DEBUG_ADC_CHANNELS

View File

@ -0,0 +1,21 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
extern adc_config_t adcConfig[ADC_CHANNEL_COUNT];
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];

View File

@ -31,6 +31,7 @@
#include "accgyro.h"
#include "adc.h"
#include "adc_impl.h"
// Driver for STM32F103CB onboard ADC
//
@ -43,8 +44,6 @@
//
// CC3D Only one ADC channel supported currently, for battery on S5_IN/PA0
extern adc_config_t adcConfig[ADC_CHANNEL_COUNT];
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
void adcInit(drv_adc_config_t *init)
{

View File

@ -28,9 +28,7 @@
#include "accgyro.h"
#include "adc.h"
extern adc_config_t adcConfig[ADC_CHANNEL_COUNT];
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
#include "adc_impl.h"
#ifndef ADC_INSTANCE
#define ADC_INSTANCE ADC1

View File

@ -184,7 +184,7 @@ bool i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
static void i2c_er_handler(void)
{
// Read the I2Cx status register
volatile uint32_t SR1Register = I2Cx->SR1;
uint32_t SR1Register = I2Cx->SR1;
if (SR1Register & 0x0F00) { // an error
error = true;
@ -325,6 +325,9 @@ void i2cInit(I2CDevice index)
I2Cx_index = index;
RCC_APB1PeriphClockCmd(i2cHardwareMap[index].peripheral, ENABLE);
// diable I2C interrrupts first to avoid ER handler triggering
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE);
// clock out stuff to make sure slaves arent stuck
// This will also configure GPIO as AF_OD at the end
i2cUnstick();
@ -333,7 +336,7 @@ void i2cInit(I2CDevice index)
I2C_DeInit(I2Cx);
I2C_StructInit(&i2c);
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Enable EVT and ERR interrupts - they are enabled by the first request
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts - they are enabled by the first request
i2c.I2C_Mode = I2C_Mode_I2C;
i2c.I2C_DutyCycle = I2C_DutyCycle_2;
i2c.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;

View File

@ -18,11 +18,11 @@
#pragma once
#ifdef INVERTER
#define INVERTER_OFF digitalLo(INVERTER_GPIO, INVERTER_PIN);
#define INVERTER_ON digitalHi(INVERTER_GPIO, INVERTER_PIN);
#define INVERTER_OFF digitalLo(INVERTER_GPIO, INVERTER_PIN)
#define INVERTER_ON digitalHi(INVERTER_GPIO, INVERTER_PIN)
#else
#define INVERTER_OFF ;
#define INVERTER_ON ;
#define INVERTER_OFF do {} while(0)
#define INVERTER_ON do {} while(0)
#endif
void initInverter(void);

View File

@ -19,49 +19,49 @@
// Helpful macros
#ifdef LED0
#define LED0_TOGGLE digitalToggle(LED0_GPIO, LED0_PIN);
#define LED0_TOGGLE digitalToggle(LED0_GPIO, LED0_PIN)
#ifndef LED0_INVERTED
#define LED0_OFF digitalHi(LED0_GPIO, LED0_PIN);
#define LED0_ON digitalLo(LED0_GPIO, LED0_PIN);
#define LED0_OFF digitalHi(LED0_GPIO, LED0_PIN)
#define LED0_ON digitalLo(LED0_GPIO, LED0_PIN)
#else
#define LED0_OFF digitalLo(LED0_GPIO, LED0_PIN);
#define LED0_ON digitalHi(LED0_GPIO, LED0_PIN);
#define LED0_OFF digitalLo(LED0_GPIO, LED0_PIN)
#define LED0_ON digitalHi(LED0_GPIO, LED0_PIN)
#endif // inverted
#else
#define LED0_TOGGLE
#define LED0_OFF
#define LED0_ON
#define LED0_TOGGLE do {} while(0)
#define LED0_OFF do {} while(0)
#define LED0_ON do {} while(0)
#endif
#ifdef LED1
#define LED1_TOGGLE digitalToggle(LED1_GPIO, LED1_PIN);
#define LED1_TOGGLE digitalToggle(LED1_GPIO, LED1_PIN)
#ifndef LED1_INVERTED
#define LED1_OFF digitalHi(LED1_GPIO, LED1_PIN);
#define LED1_ON digitalLo(LED1_GPIO, LED1_PIN);
#define LED1_OFF digitalHi(LED1_GPIO, LED1_PIN)
#define LED1_ON digitalLo(LED1_GPIO, LED1_PIN)
#else
#define LED1_OFF digitalLo(LED1_GPIO, LED1_PIN);
#define LED1_ON digitalHi(LED1_GPIO, LED1_PIN);
#define LED1_OFF digitalLo(LED1_GPIO, LED1_PIN)
#define LED1_ON digitalHi(LED1_GPIO, LED1_PIN)
#endif // inverted
#else
#define LED1_TOGGLE
#define LED1_OFF
#define LED1_ON
#define LED1_TOGGLE do {} while(0)
#define LED1_OFF do {} while(0)
#define LED1_ON do {} while(0)
#endif
#ifdef LED2
#define LED2_TOGGLE digitalToggle(LED2_GPIO, LED2_PIN);
#define LED2_TOGGLE digitalToggle(LED2_GPIO, LED2_PIN)
#ifndef LED2_INVERTED
#define LED2_OFF digitalHi(LED2_GPIO, LED2_PIN);
#define LED2_ON digitalLo(LED2_GPIO, LED2_PIN);
#define LED2_OFF digitalHi(LED2_GPIO, LED2_PIN)
#define LED2_ON digitalLo(LED2_GPIO, LED2_PIN)
#else
#define LED2_OFF digitalLo(LED2_GPIO, LED2_PIN);
#define LED2_ON digitalHi(LED2_GPIO, LED2_PIN);
#define LED2_OFF digitalLo(LED2_GPIO, LED2_PIN)
#define LED2_ON digitalHi(LED2_GPIO, LED2_PIN)
#endif // inverted
#else
#define LED2_TOGGLE
#define LED2_OFF
#define LED2_ON
#define LED2_TOGGLE do {} while(0)
#define LED2_OFF do {} while(0)
#define LED2_ON do {} while(0)
#endif
void ledInit(void);

View File

@ -351,13 +351,10 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
setup = hardwareMaps[i];
for (i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
for (i = 0; i < USABLE_TIMER_CHANNEL_COUNT && setup[i] != 0xFFFF; i++) {
uint8_t timerIndex = setup[i] & 0x00FF;
uint8_t type = (setup[i] & 0xFF00) >> 8;
if (setup[i] == 0xFFFF) // terminator
break;
const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
#ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER

View File

@ -34,10 +34,7 @@
#include "serial.h"
#include "serial_uart.h"
uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode);
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode);
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode);
#include "serial_uart_impl.h"
static void usartConfigurePinInversion(uartPort_t *uartPort) {
#if !defined(INVERTER) && !defined(STM32F303xC)

View File

@ -44,8 +44,6 @@ typedef struct {
USART_TypeDef *USARTx;
} uartPort_t;
extern const struct serialPortVTable uartVTable[];
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uint32_t baudRate, portMode_t mode, serialInversion_e inversion);
// serialPort API

View File

@ -0,0 +1,29 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
// device specific uart implementation is defined here
extern const struct serialPortVTable uartVTable[];
void uartStartTxDMA(uartPort_t *s);
uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode);
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode);
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode);

View File

@ -34,6 +34,7 @@
#include "serial.h"
#include "serial_uart.h"
#include "serial_uart_impl.h"
#ifdef USE_USART1
static uartPort_t uartPort1;
@ -54,8 +55,6 @@ static uartPort_t uartPort3;
#undef USE_USART1_RX_DMA
#endif
void uartStartTxDMA(uartPort_t *s);
void usartIrqCallback(uartPort_t *s)
{
uint16_t SR = s->USARTx->SR;

View File

@ -35,6 +35,7 @@
#include "serial.h"
#include "serial_uart.h"
#include "serial_uart_impl.h"
// Using RX DMA disables the use of receive callbacks
#define USE_USART1_RX_DMA
@ -70,12 +71,17 @@
#define UART3_RX_PINSOURCE GPIO_PinSource11
#endif
#ifdef USE_USART1
static uartPort_t uartPort1;
#endif
#ifdef USE_USART2
static uartPort_t uartPort2;
#endif
#ifdef USE_USART3
static uartPort_t uartPort3;
#endif
void uartStartTxDMA(uartPort_t *s);
#ifdef USE_USART1
uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
{
uartPort_t *s;
@ -148,7 +154,9 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
return s;
}
#endif
#ifdef USE_USART2
uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode)
{
uartPort_t *s;
@ -227,7 +235,9 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode)
return s;
}
#endif
#ifdef USE_USART3
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode)
{
uartPort_t *s;
@ -306,6 +316,7 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode)
return s;
}
#endif
static void handleUsartTxDma(uartPort_t *s)
{
@ -338,7 +349,7 @@ void DMA1_Channel7_IRQHandler(void)
#endif
// USART3 Tx DMA Handler
#ifdef USE_USART2_TX_DMA
#ifdef USE_USART3_TX_DMA
void DMA1_Channel2_IRQHandler(void)
{
uartPort_t *s = &uartPort3;
@ -381,24 +392,29 @@ void usartIrqHandler(uartPort_t *s)
}
}
#ifdef USE_USART1
void USART1_IRQHandler(void)
{
uartPort_t *s = &uartPort1;
usartIrqHandler(s);
}
#endif
#ifdef USE_USART2
void USART2_IRQHandler(void)
{
uartPort_t *s = &uartPort2;
usartIrqHandler(s);
}
#endif
#ifdef USE_USART3
void USART3_IRQHandler(void)
{
uartPort_t *s = &uartPort3;
usartIrqHandler(s);
}
#endif

View File

@ -31,7 +31,7 @@
#include "system.h"
// cycles per microsecond
static volatile uint32_t usTicks = 0;
static uint32_t usTicks = 0;
// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care.
static volatile uint32_t sysTickUptime = 0;

View File

@ -1448,16 +1448,16 @@ static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
switch (var->type & VALUE_TYPE_MASK) {
case VAR_UINT8:
case VAR_INT8:
*(char *)ptr = (char)value.int_value;
*(int8_t *)ptr = value.int_value;
break;
case VAR_UINT16:
case VAR_INT16:
*(short *)ptr = (short)value.int_value;
*(int16_t *)ptr = value.int_value;
break;
case VAR_UINT32:
*(int *)ptr = (int)value.int_value;
*(uint32_t *)ptr = value.int_value;
break;
case VAR_FLOAT:
@ -1650,7 +1650,7 @@ void cliProcess()
}
for (; i < bufferIndex; i++)
cliWrite(cliBuffer[i]);
} else if (!bufferIndex && c == 4) {
} else if (!bufferIndex && c == 4) { // CTRL-D
cliExit(cliBuffer);
return;
} else if (c == 12) {

View File

@ -175,7 +175,7 @@ void init(void)
ledInit();
#ifdef SPEKTRUM_BIND
#ifdef SPEKTRUM_BIND
if (feature(FEATURE_RX_SERIAL)) {
switch (masterConfig.rxConfig.serialrx_provider) {
case SERIALRX_SPEKTRUM1024:

View File

@ -92,23 +92,20 @@ void batteryInit(batteryConfig_t *initialBatteryConfig)
delay((32 / BATTERY_SAMPLE_COUNT) * 10);
}
// autodetect cell count, going from 1S..8S
for (i = 1; i < 8; i++) {
if (vbat < i * batteryConfig->vbatmaxcellvoltage)
break;
}
batteryCellCount = i;
unsigned cells = (vbat / batteryConfig->vbatmaxcellvoltage) + 1;
if(cells > 8) // something is wrong, we expect 8 cells maximum (and autodetection will be problematic at 6+ cells)
cells = 8;
batteryCellCount = cells;
batteryWarningVoltage = batteryCellCount * batteryConfig->vbatwarningcellvoltage;
batteryCriticalVoltage = batteryCellCount * batteryConfig->vbatmincellvoltage;
}
#define ADCVREF 33L
#define ADCVREF 3300 // in mV
int32_t currentSensorToCentiamps(uint16_t src)
{
int32_t millivolts;
millivolts = ((uint32_t)src * ADCVREF * 100) / 4095;
millivolts = ((uint32_t)src * ADCVREF) / 4096;
millivolts -= batteryConfig->currentMeterOffset;
return (millivolts * 1000) / (int32_t)batteryConfig->currentMeterScale; // current in 0.01A steps

View File

@ -177,6 +177,7 @@ static void sendBaro(void)
serialize16(ABS(BaroAlt % 100));
}
#ifdef GPS
static void sendGpsAltitude(void)
{
uint16_t altitude = GPS_altitude;
@ -189,7 +190,7 @@ static void sendGpsAltitude(void)
sendDataHead(ID_GPS_ALTIDUTE_AP);
serialize16(0);
}
#endif
static void sendThrottleOrBatterySizeAsRpm(void)
{
@ -212,6 +213,7 @@ static void sendTemperature1(void)
#endif
}
#ifdef GPS
static void sendSatalliteSignalQualityAsTemperature2(void)
{
uint16_t satellite = GPS_numSat;
@ -241,6 +243,7 @@ static void sendSpeed(void)
sendDataHead(ID_GPS_SPEED_AP);
serialize16(0); //Not dipslayed
}
#endif
static void sendTime(void)
{

View File

@ -220,15 +220,15 @@ static inline void hottEAMUpdateBattery(HOTT_EAM_MSG_t *hottEAMMessage)
static inline void hottEAMUpdateCurrentMeter(HOTT_EAM_MSG_t *hottEAMMessage)
{
int32_t amp = amperage / 10;
hottEAMMessage->current_L = amp & 0xFF;
int32_t amp = amperage / 10;
hottEAMMessage->current_L = amp & 0xFF;
hottEAMMessage->current_H = amp >> 8;
}
static inline void hottEAMUpdateBatteryDrawnCapacity(HOTT_EAM_MSG_t *hottEAMMessage)
{
int32_t mAh = mAhDrawn / 10;
hottEAMMessage->batt_cap_L = mAh & 0xFF;
int32_t mAh = mAhDrawn / 10;
hottEAMMessage->batt_cap_L = mAh & 0xFF;
hottEAMMessage->batt_cap_H = mAh >> 8;
}

View File

@ -304,17 +304,18 @@ void handleSmartPortTelemetry(void)
smartPortIdCnt++;
int32_t tmpi;
uint32_t tmpui;
static uint8_t t1Cnt = 0;
switch(id) {
#ifdef GPS
case FSSP_DATAID_SPEED :
if (sensors(SENSOR_GPS) && STATE(GPS_FIX)) {
tmpui = (GPS_speed * 36 + 36 / 2) / 100;
uint32_t tmpui = (GPS_speed * 36 + 36 / 2) / 100;
smartPortSendPackage(id, tmpui); // given in 0.1 m/s, provide in KM/H
smartPortHasRequest = 0;
}
break;
#endif
case FSSP_DATAID_VFAS :
smartPortSendPackage(id, vbat * 83); // supposedly given in 0.1V, unknown requested unit
// multiplying by 83 seems to make Taranis read correctly
@ -335,9 +336,10 @@ void handleSmartPortTelemetry(void)
break;
//case FSSP_DATAID_ADC1 :
//case FSSP_DATAID_ADC2 :
#ifdef GPS
case FSSP_DATAID_LATLONG :
if (sensors(SENSOR_GPS) && STATE(GPS_FIX)) {
tmpui = 0;
uint32_t tmpui = 0;
// the same ID is sent twice, one for longitude, one for latitude
// the MSB of the sent uint32_t helps FrSky keep track
// the even/odd bit of our counter helps us keep track
@ -360,6 +362,7 @@ void handleSmartPortTelemetry(void)
smartPortHasRequest = 0;
}
break;
#endif
//case FSSP_DATAID_CAP_USED :
case FSSP_DATAID_VARIO :
smartPortSendPackage(id, vario); // unknown given unit but requested in 100 = 1m/s
@ -431,21 +434,25 @@ void handleSmartPortTelemetry(void)
break;
case FSSP_DATAID_T2 :
if (sensors(SENSOR_GPS)) {
#ifdef GPS
// provide GPS lock status
smartPortSendPackage(id, (STATE(GPS_FIX) ? 1000 : 0) + (STATE(GPS_FIX_HOME) ? 2000 : 0) + GPS_numSat);
smartPortHasRequest = 0;
#endif
}
else {
smartPortSendPackage(id, 0);
smartPortHasRequest = 0;
}
break;
#ifdef GPS
case FSSP_DATAID_GPS_ALT :
if (sensors(SENSOR_GPS) && STATE(GPS_FIX)) {
smartPortSendPackage(id, GPS_altitude * 1000); // given in 0.1m , requested in 100 = 1m
smartPortHasRequest = 0;
}
break;
#endif
default:
break;
// if nothing is sent, smartPortHasRequest isn't cleared, we already incremented the counter, just wait for the next loop

View File

@ -37,7 +37,17 @@ TEST(BatteryTest, BatteryADCToVoltage)
{
// given
batteryConfig_t batteryConfig;
batteryConfig_t batteryConfig = {
.vbatscale = 110,
.vbatmaxcellvoltage = 43,
.vbatmincellvoltage = 33,
.vbatwarningcellvoltage = 35,
.currentMeterScale = 400,
.currentMeterOffset = 0,
.currentMeterType = CURRENT_SENSOR_NONE,
.multiwiiCurrentMeterOutput = 0,
.batteryCapacity = 2200,
};
// batteryInit() reads a bunch of fields including vbatscale, so set up the config with useful initial values:
memset(&batteryConfig, 0, sizeof(batteryConfig));