Merge branch 'Battery_monitoring' of git://github.com/MJ666/cleanflight into MJ666-Battery_monitoring

This commit is contained in:
Dominic Clifton 2015-03-30 19:44:33 +01:00
commit d33e4e6afd
5 changed files with 45 additions and 12 deletions

View File

@ -6,18 +6,19 @@ Here are the hardware specifications:
- STM32F103CBT6 MCU (ALIENWIIF1)
- STM32F303CCT6 MCU (ALIENWIIF3)
- optional integrated serial/ppm receiver (ALIENWIIF3 only, future enhancement)
- MPU6050 accelerometer/gyro sensor unit
- 8x 4.2A brushed ESCs, integrated, to run the strongest micro motors
- extra-wide traces on the PCB, for maximum power throughput
- USB port, integrated
- (*) serial connection for external DSM2/DSMX sat receiver (e.g. Spektrum SAT, OrangeRx R100 or Lemon RX)
- alternatively PPM receiver connection (i.e. Deltang Rx31)
- (*) serial connection for external DSM2/DSMX sat receiver (e.g. Spektrum SAT, OrangeRx R100, Lemon RX or Deltang Rx31)
- ground and 3.3V for the receiver
- hardware bind plug for easy binding
- motor connections are at the corners for a clean look with reduced wiring
- dimensions: 29x33mm
- direct operation from an single cell lipoly battery
- 3.3V LDO power regulator (ALIENWIIF1 only)
- 3.3V buck-boost power converter (ALIENWIIF3 only)
- battery monitoring with an white LED for buzzer functionality (ALIENWIIF3 only)
(*) Spektrum Compatible DSM2 satellites are supported out of the box. DSMX sat will work with DSM2 protocol with default settings (DSM2, 11bit, 11ms is preset).

View File

@ -17,12 +17,15 @@ Flyable!
Tested with revision 1 board.
## TODO
* ADC
* Sonar
* Display (via Flex port)
* SoftSerial - though having 3 hardware serial ports makes it a little redundant.
* Airplane PWM mappings.
# Voltage and current monitoring (ADC support)
Voltage monitoring is possible when enabled via PWM9 pin and current can be monitored via PWM8 pin. The voltage divider and current sensor need to be connected externally. The vbatscale cli parameter need to be adjusted to fit the sensor specification. For more details regarding the sensor hardware you can check here: https://github.com/TauLabs/TauLabs/wiki/User-Guide:-Battery-Configuration
# Flashing
## Via Device Firmware Upload (DFU, USB) - Windows
@ -166,7 +169,7 @@ Flashing cleanflight will erase the TauLabs bootloader, this is not a problem an
# Serial Ports
| Value | Identifier | RX | TX | Notes |
| ----- | ------------ | --------- | ---------- | ------------------------------------------------------------------------------------------- |
| ----- | ------------ | --------- | ---------- | -------------------------------------------------------------- |
| 1 | USB VCP | RX (USB) | TX (USB) | |
| 2 | USART1 | RX / PB7 | TX / PB6 | Conn1 / Flexi Port. |
| 3 | USART2 | RX / PA3 | PWM6 / PA2 | On RX is on INPUT header. Best port for Serial RX input |

View File

@ -511,10 +511,11 @@ static void resetConf(void)
featureSet(FEATURE_RX_SERIAL);
featureSet(FEATURE_MOTOR_STOP);
featureSet(FEATURE_FAILSAFE);
featureClear(FEATURE_VBAT);
#ifdef ALIENWIIF3
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
masterConfig.batteryConfig.vbatscale = 20;
#else
featureClear(FEATURE_VBAT);
masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL;
#endif
masterConfig.rxConfig.serialrx_provider = 1;

View File

@ -25,6 +25,9 @@
#define LED1_GPIO GPIOB
#define LED1_PIN Pin_5 // Green LEDs - PB5
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOB
#define BEEP_GPIO GPIOA
#define BEEP_PIN Pin_5 // White LEDs - PA5
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOA
#define USABLE_TIMER_CHANNEL_COUNT 11
@ -49,6 +52,7 @@
#define MAG_AK8975_ALIGN CW0_DEG_FLIP
#define BEEPER
#define LED0
#define LED1
@ -87,9 +91,19 @@
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define BLACKBOX
#define USE_ADC
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_1
//#define BLACKBOX
#define SERIAL_RX
#define GPS
//#define GPS
//#define DISPLAY
#define AUTOTUNE
#define USE_SERVOS

View File

@ -86,6 +86,20 @@
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define USE_ADC
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define CURRENT_METER_ADC_GPIO GPIOA
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_7
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_4
#define BLACKBOX
#define SERIAL_RX
#define GPS