1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-23 08:15:26 +03:00

Merge branch '1wire_pass_through_optimize' of https://github.com/4712/cleanflight into 4712-1wire_pass_through_optimize

This commit is contained in:
Dominic Clifton 2015-12-18 09:51:12 +01:00
commit 14ade88ca9
11 changed files with 38 additions and 84 deletions

View file

@ -16,6 +16,7 @@
*
* Ported from https://github.com/4712/BLHeliSuite/blob/master/Interfaces/Arduino1Wire/Source/Arduino1Wire_C/Arduino1Wire.c
* by Nathan Tsoi <nathan@vertile.com>
* Several updates by 4712 in order to optimize interaction with BLHeliSuite
*/
#include <stdbool.h>
@ -29,10 +30,11 @@
#include "drivers/light_led.h"
#include "drivers/system.h"
#include "io/serial_1wire.h"
#include "io/beeper.h"
#include "drivers/pwm_mapping.h"
#include "flight/mixer.h"
uint8_t escCount;
uint8_t escCount; // we detect the hardware dynamically
static escHardware_t escHardware[MAX_PWM_MOTORS];
@ -44,7 +46,6 @@ static void gpio_set_mode(GPIO_TypeDef* gpio, uint16_t pin, GPIO_Mode mode) {
gpioInit(gpio, &cfg);
}
static uint32_t GetPinPos(uint32_t pin) {
uint32_t pinPos;
for (pinPos = 0; pinPos < 16; pinPos++) {
@ -57,33 +58,22 @@ static uint32_t GetPinPos(uint32_t pin) {
return 0;
}
void usb1WireInitialize()
{
escCount = 0;
memset(&escHardware,0,sizeof(escHardware));
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmGetOutputConfiguration();
for (uint8_t i = 0; i < pwmOutputConfiguration->outputCount; i++) {
for (volatile uint8_t i = 0; i < pwmOutputConfiguration->outputCount; i++) {
if ((pwmOutputConfiguration->portConfigurations[i].flags & PWM_PF_MOTOR) == PWM_PF_MOTOR) {
if(motor[pwmOutputConfiguration->portConfigurations[i].index] > 0) {
escHardware[escCount].gpio = pwmOutputConfiguration->portConfigurations[i].timerHardware->gpio;
escHardware[escCount].pin = pwmOutputConfiguration->portConfigurations[i].timerHardware->pin;
escHardware[escCount].pinpos = GetPinPos(escHardware[escCount].pin);
gpio_set_mode(escHardware[escCount].gpio,escHardware[escCount].pin, Mode_IPU); //GPIO_Mode_IPU
escCount++;
}
}
}
#ifdef BEEPER
// fix for buzzer often starts beeping continuously when the ESCs are read
// switch beeper off until reboot
gpio_set_mode(BEEP_GPIO, BEEP_PIN, Mode_IN_FLOATING); // set input no pull up or down
#endif
}
#ifdef STM32F10X
@ -140,7 +130,6 @@ static void gpioSetOne(uint32_t escIndex, GPIO_Mode mode) {
#define ESC_OUTPUT(escIndex) gpioSetOne(escIndex, Mode_Out_PP)
#endif
#define RX_LED_OFF LED0_OFF
#define RX_LED_ON LED0_ON
#define TX_LED_OFF LED1_OFF
@ -150,16 +139,22 @@ static void gpioSetOne(uint32_t escIndex, GPIO_Mode mode) {
// RX line control when data should be read or written from the single line
void usb1WirePassthrough(uint8_t escIndex)
{
#ifdef BEEPER
// fix for buzzer often starts beeping continuously when the ESCs are read
// switch beeper silent here
beeperSilence();
#endif
// disable all interrupts
__disable_irq();
// prepare MSP UART port for direct pin access
// reset all the pins
GPIO_ResetBits(S1W_RX_GPIO, S1W_RX_PIN);
GPIO_ResetBits(S1W_TX_GPIO, S1W_TX_PIN);
// configure gpio
gpio_set_mode(S1W_RX_GPIO, S1W_RX_PIN, Mode_IPU);
gpio_set_mode(S1W_TX_GPIO, S1W_TX_PIN, Mode_Out_PP);
// hey user, turn on your ESC now
#ifdef STM32F10X
// reset our gpio register pointers and bitmask values
@ -170,8 +165,7 @@ void usb1WirePassthrough(uint8_t escIndex)
ESC_SET_HI(escIndex);
TX_SET_HIGH;
// Wait for programmer to go from 1 -> 0 indicating incoming data
while (RX_HI)
;
while(RX_HI);
while(1) {
// A new iteration on this loop starts when we have data from the programmer (read_programmer goes low)
@ -187,8 +181,7 @@ void usb1WirePassthrough(uint8_t escIndex)
// Wait for programmer to go 0 -> 1
uint32_t ct=3333;
while(!RX_HI) {
if (ct > 0)
ct--; // count down until 0;
if (ct > 0) ct--; // count down until 0;
// check for low time ->ct=3333 ~600uS //byte LO time for 0 @ 19200 baud -> 9*52 uS => 468.75uS
// App must send a 0 at 9600 baud (or lower) which has a LO time of at 104uS (or more) > 0 = 937.5uS LO
// BLHeliSuite will use 4800 baud
@ -197,17 +190,16 @@ void usb1WirePassthrough(uint8_t escIndex)
// At first Echo to the esc, which helps to charge input capacities at ESC
ESC_SET_HI(escIndex);
// Listen to the escIndex, input mode, pullup resistor is on
gpio_set_mode(escHardware[escIndex].gpio, escHardware[escIndex].pin,
Mode_IPU);
gpio_set_mode(escHardware[escIndex].gpio, escHardware[escIndex].pin, Mode_IPU);
TX_LED_OFF;
if (ct == 0)
break; //we reached zero
if (ct==0) break; //we reached zero
// Listen to the escIndex while there is no data from the programmer
while (RX_HI) {
if (ESC_HI(escIndex)) {
TX_SET_HIGH;
RX_LED_OFF;
} else {
}
else {
TX_SET_LO;
RX_LED_ON;
}
@ -221,5 +213,4 @@ void usb1WirePassthrough(uint8_t escIndex)
__enable_irq();
return;
}
#endif

View file

@ -51,7 +51,6 @@
#include "io/gimbal.h"
#include "io/rc_controls.h"
#include "io/serial.h"
#include "io/serial_1wire.h"
#include "io/ledstrip.h"
#include "io/flashfs.h"
#include "io/beeper.h"
@ -149,10 +148,6 @@ static void cliFlashRead(char *cmdline);
#endif
#endif
#ifdef USE_SERIAL_1WIRE_CLI
static void cliUSB1Wire(char *cmdline);
#endif
// buffer
static char cliBuffer[48];
static uint32_t bufferIndex = 0;
@ -229,9 +224,6 @@ typedef struct {
// should be sorted a..z for bsearch()
const clicmd_t cmdTable[] = {
#ifdef USE_SERIAL_1WIRE_CLI
CLI_COMMAND_DEF("1wire", "1-wire interface to escs", "<esc index>", cliUSB1Wire),
#endif
CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
CLI_COMMAND_DEF("aux", "configure modes", NULL, cliAux),
#ifdef LED_STRIP
@ -2317,27 +2309,6 @@ static void cliStatus(char *cmdline)
printf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime, i2cErrorCounter, sizeof(master_t));
}
#ifdef USE_SERIAL_1WIRE_CLI
static void cliUSB1Wire(char *cmdline)
{
if (isEmpty(cmdline)) {
cliShowParseError();
return;
} else {
usb1WireInitialize();
int i;
i = atoi(cmdline);
if (i >= 0 && i < escCount) {
printf("Switching to BlHeli mode on motor port %d\r\n", i);
usb1WirePassthrough(i);
} else {
cliShowArgumentRangeError("motor", 0, escCount - 1);
}
}
}
#endif
static void cliVersion(char *cmdline)
{
UNUSED(cmdline);

View file

@ -121,7 +121,6 @@
#define USE_CLI
#define USE_SERIAL_1WIRE
#define USE_SERIAL_1WIRE_CLI
// FlexPort (pin 21/22, TX/RX respectively):
// Note, FlexPort has 10k pullups on both TX and RX

View file

@ -177,7 +177,6 @@
#define BIND_PIN Pin_4
#define USE_SERIAL_1WIRE
#define USE_SERIAL_1WIRE_CLI
#define S1W_TX_GPIO GPIOB
#define S1W_TX_PIN GPIO_Pin_6

View file

@ -188,7 +188,6 @@
#define BIND_PIN Pin_3
#define USE_SERIAL_1WIRE
#define USE_SERIAL_1WIRE_CLI
// STM32F103CBT6-LQFP48 Pin30 (PA9) TX - PC3 connects to onboard CP2102 RX
#define S1W_TX_GPIO GPIOA

View file

@ -157,7 +157,6 @@
#define USE_CLI
#define USE_SERIAL_1WIRE
#define USE_SERIAL_1WIRE_CLI
#define S1W_TX_GPIO GPIOA
#define S1W_TX_PIN GPIO_Pin_9

View file

@ -165,7 +165,6 @@
#define BIND_PIN Pin_11
#define USE_SERIAL_1WIRE
#define USE_SERIAL_1WIRE_CLI
#define S1W_TX_GPIO GPIOA
#define S1W_TX_PIN GPIO_Pin_9

View file

@ -151,7 +151,6 @@
#endif
#define USE_SERIAL_1WIRE
#define USE_SERIAL_1WIRE_CLI
#define S1W_TX_GPIO GPIOB
#define S1W_TX_PIN GPIO_Pin_6

View file

@ -173,7 +173,6 @@
#define BIND_PIN Pin_11
#define USE_SERIAL_1WIRE
#define USE_SERIAL_1WIRE_CLI
#define S1W_TX_GPIO GPIOA
#define S1W_TX_PIN GPIO_Pin_9

View file

@ -100,7 +100,6 @@
#define USE_CLI
#define USE_SERIAL_1WIRE
#define USE_SERIAL_1WIRE_CLI
// STM32F3DISCOVERY TX - PD5 connects to UART RX
#define S1W_TX_GPIO GPIOD