allow controlling external XOR gate connected to PB2 (BOOT1) to invert USART2_RX signal on F1. Currently used by sbus driver.

This commit is contained in:
dongie 2014-06-11 12:52:03 +09:00
parent e35c92b0da
commit 84729747b0
6 changed files with 57 additions and 5 deletions

View File

@ -1,3 +1,7 @@
/*
* This file is part of baseflight
* Licensed under GPL V3 or modified DCL - see https://github.com/multiwii/baseflight/blob/master/README.md
*/
#pragma once
// for roundf()
@ -208,6 +212,8 @@ typedef struct baro_t {
#define BEEP_PIN Pin_12 // PA12 (Buzzer)
#define BARO_GPIO GPIOC
#define BARO_PIN Pin_13
#define INV_PIN Pin_2 // PB2 (BOOT1) abused as inverter select GPIO
#define INV_GPIO GPIOB
#define GYRO
#define ACC
@ -255,6 +261,14 @@ typedef struct baro_t {
#define BEEP_ON ;
#endif
#ifdef INV_GPIO
#define INV_OFF digitalLo(INV_GPIO, INV_PIN);
#define INV_ON digitalHi(INV_GPIO, INV_PIN);
#else
#define INV_OFF ;
#define INV_ON ;
#endif
// #define SOFT_I2C // enable to test software i2c
#include "utils.h"

View File

@ -1,3 +1,8 @@
/*
* This file is part of baseflight
* Licensed under GPL V3 or modified DCL - see https://github.com/multiwii/baseflight/blob/master/README.md
*/
#include "board.h"
#include "mw.h"
@ -131,6 +136,7 @@ const clivalue_t valueTable[] = {
{ "fixedwing_althold_dir", VAR_INT8, &mcfg.fixedwing_althold_dir, -1, 1 },
{ "reboot_character", VAR_UINT8, &mcfg.reboot_character, 48, 126 },
{ "serial_baudrate", VAR_UINT32, &mcfg.serial_baudrate, 1200, 115200 },
{ "serial2_rx_inverted", VAR_UINT8, &mcfg.serial2_rx_inverted, 0, 1 },
{ "softserial_baudrate", VAR_UINT32, &mcfg.softserial_baudrate, 1200, 19200 },
{ "softserial_1_inverted", VAR_UINT8, &mcfg.softserial_1_inverted, 0, 1 },
{ "softserial_2_inverted", VAR_UINT8, &mcfg.softserial_2_inverted, 0, 1 },

View File

@ -1,3 +1,8 @@
/*
* This file is part of baseflight
* Licensed under GPL V3 or modified DCL - see https://github.com/multiwii/baseflight/blob/master/README.md
*/
#include "board.h"
#include "mw.h"
#include <string.h>
@ -13,7 +18,7 @@ master_t mcfg; // master config struct with data independent from profiles
config_t cfg; // profile config struct
const char rcChannelLetters[] = "AERT1234";
static const uint8_t EEPROM_CONF_VERSION = 64;
static const uint8_t EEPROM_CONF_VERSION = 65;
static uint32_t enabledSensors = 0;
static void resetConf(void);
@ -125,7 +130,8 @@ void writeEEPROM(uint8_t b, uint8_t updateProfile)
while (tries--) {
FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
status = FLASH_ErasePage(FLASH_WRITE_ADDR);
FLASH_ErasePage(FLASH_WRITE_ADDR);
status = FLASH_ErasePage(FLASH_WRITE_ADDR + FLASH_PAGE_SIZE);
for (i = 0; i < sizeof(master_t) && status == FLASH_COMPLETE; i += 4)
status = FLASH_ProgramWord(FLASH_WRITE_ADDR + i, *(uint32_t *)((char *)&mcfg + i));
if (status == FLASH_COMPLETE)

View File

@ -1,3 +1,8 @@
/*
* This file is part of baseflight
* Licensed under GPL V3 or modified DCL - see https://github.com/multiwii/baseflight/blob/master/README.md
*/
#include "board.h"
// cycles per microsecond
@ -68,6 +73,10 @@ void systemInit(bool overclock)
.cfg = { BEEP_PIN, Mode_Out_OD, Speed_2MHz }
},
#endif
{
.gpio = INV_GPIO,
.cfg = { INV_PIN, Mode_Out_PP, Speed_2MHz }
},
};
gpio_config_t gpio;
uint32_t i;

View File

@ -1,3 +1,8 @@
/*
* This file is part of baseflight
* Licensed under GPL V3 or modified DCL - see https://github.com/multiwii/baseflight/blob/master/README.md
*/
#pragma once
/* for VBAT monitoring frequency */
@ -281,10 +286,11 @@ typedef struct master_t {
int8_t gps_baudrate; // See GPSBaudRates enum.
uint32_t serial_baudrate;
uint8_t serial2_rx_inverted; // invert RX only for USART2 (for Sbus, etc)
uint32_t softserial_baudrate; // shared by both soft serial ports
uint8_t softserial_1_inverted; // use inverted softserial input and output signals on port 1
uint8_t softserial_2_inverted; // use inverted softserial input and output signals on port 2
uint32_t softserial_baudrate; // shared by both soft serial ports
uint8_t softserial_1_inverted; // use inverted softserial input and output signals on port 1
uint8_t softserial_2_inverted; // use inverted softserial input and output signals on port 2
uint8_t telemetry_provider; // See TelemetryProvider enum.
uint8_t telemetry_port; // See TelemetryPort enum.

View File

@ -1,3 +1,8 @@
/*
* This file is part of baseflight
* Licensed under GPL V3 or modified DCL - see https://github.com/multiwii/baseflight/blob/master/README.md
*/
#include "board.h"
#include "mw.h"
@ -22,6 +27,12 @@ void sbusInit(rcReadRawDataPtr *callback)
int b;
for (b = 0; b < SBUS_MAX_CHANNEL; b++)
sbusChannelData[b] = 2 * (mcfg.midrc - SBUS_OFFSET);
// Configure hardware inverter on PB2. If not available, this has no effect.
if (mcfg.serial2_rx_inverted) {
INV_ON;
} else {
INV_OFF;
}
core.rcvrport = uartOpen(USART2, sbusDataReceive, 100000, (portMode_t)(MODE_RX | MODE_SBUS));
if (callback)
*callback = sbusReadRawRC;