From 5a1cb21ad538876b23d8f06c90b8abb574df8b2e Mon Sep 17 00:00:00 2001
From: 4712 <4712@outlook.de>
Date: Fri, 8 Apr 2016 18:47:18 +0200
Subject: [PATCH] 4way-if cleanup
removed superseded 1wire-uart and 1wire-vcp
---
Makefile | 2 -
src/main/io/serial_1wire.c | 227 ------------------
src/main/io/serial_1wire.h | 37 ---
src/main/io/serial_1wire.h~HEAD | 37 ---
...h~a94ce1fef3a5d63c8af6a85b24f8eba2961e0890 | 36 ---
src/main/io/serial_1wire_vcp.c | 224 -----------------
src/main/io/serial_1wire_vcp.h | 42 ----
src/main/io/serial_4way.c | 227 ++++++++++++------
src/main/io/serial_4way.h | 75 +++---
src/main/io/serial_4way_avrootloader.c | 87 ++++---
src/main/io/serial_4way_avrootloader.h | 17 +-
src/main/io/serial_4way_stk500v2.c | 131 +++++-----
src/main/io/serial_4way_stk500v2.h | 14 +-
src/main/io/serial_msp.c | 121 +---------
src/main/io/serial_msp.h | 1 -
src/main/target/CC3D/target.h | 21 +-
src/main/target/COLIBRI_RACE/target.h | 18 +-
src/main/target/LUX_RACE/target.h | 19 +-
src/main/target/MOTOLAB/target.h | 18 +-
src/main/target/NAZE/target.h | 20 +-
src/main/target/PORT103R/target.h | 18 +-
src/main/target/RMDO/target.h | 18 +-
src/main/target/SPARKY/target.h | 18 +-
src/main/target/SPRACINGF3/target.h | 18 +-
src/main/target/SPRACINGF3EVO/target.h | 16 +-
src/main/target/SPRACINGF3MINI/target.h | 18 +-
src/main/target/STM32F3DISCOVERY/target.h | 20 +-
27 files changed, 312 insertions(+), 1188 deletions(-)
delete mode 100644 src/main/io/serial_1wire.c
delete mode 100644 src/main/io/serial_1wire.h
delete mode 100644 src/main/io/serial_1wire.h~HEAD
delete mode 100644 src/main/io/serial_1wire.h~a94ce1fef3a5d63c8af6a85b24f8eba2961e0890
delete mode 100644 src/main/io/serial_1wire_vcp.c
delete mode 100644 src/main/io/serial_1wire_vcp.h
diff --git a/Makefile b/Makefile
index a20beb44a..a8de88e93 100644
--- a/Makefile
+++ b/Makefile
@@ -303,8 +303,6 @@ COMMON_SRC = build_config.c \
io/rc_controls.c \
io/rc_curves.c \
io/serial.c \
- io/serial_1wire.c \
- io/serial_1wire_vcp.c \
io/serial_4way.c \
io/serial_4way_avrootloader.c \
io/serial_4way_stk500v2.c \
diff --git a/src/main/io/serial_1wire.c b/src/main/io/serial_1wire.c
deleted file mode 100644
index 6b0a5e89a..000000000
--- a/src/main/io/serial_1wire.c
+++ /dev/null
@@ -1,227 +0,0 @@
-/*
- * 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 .
- *
- * Ported from https://github.com/4712/BLHeliSuite/blob/master/Interfaces/Arduino1Wire/Source/Arduino1Wire_C/Arduino1Wire.c
- * by Nathan Tsoi
- * Several updates by 4712 in order to optimize interaction with BLHeliSuite
- */
-
-#include
-#include
-#include
-#include
-#include "platform.h"
-
-#ifdef USE_SERIAL_1WIRE
-#include "drivers/gpio.h"
-#include "drivers/light_led.h"
-#include "drivers/system.h"
-#include "io/serial_1wire.h"
-#include "io/beeper.h"
-#include "drivers/pwm_mapping.h"
-#include "drivers/pwm_output.h"
-#include "flight/mixer.h"
-
-uint8_t escCount; // we detect the hardware dynamically
-
-static escHardware_t escHardware[MAX_PWM_MOTORS];
-
-static void gpio_set_mode(GPIO_TypeDef* gpio, uint16_t pin, GPIO_Mode mode) {
- gpio_config_t cfg;
- cfg.pin = pin;
- cfg.mode = mode;
- cfg.speed = Speed_2MHz;
- gpioInit(gpio, &cfg);
-}
-
-static uint32_t GetPinPos(uint32_t pin) {
- uint32_t pinPos;
- for (pinPos = 0; pinPos < 16; pinPos++) {
- uint32_t pinMask = (0x1 << pinPos);
- if (pin & pinMask) {
- return pinPos;
- }
- }
- return 0;
-}
-
-void usb1WireInitialize()
-{
- escCount = 0;
- pwmDisableMotors();
- memset(&escHardware,0,sizeof(escHardware));
- pwmOutputConfiguration_t *pwmOutputConfiguration = pwmGetOutputConfiguration();
- 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++;
- }
- }
- }
-}
-
-void usb1WireDeInitialize(void){
- for (uint8_t selected_esc = 0; selected_esc < (escCount); selected_esc++) {
- gpio_set_mode(escHardware[selected_esc].gpio,escHardware[selected_esc].pin, Mode_AF_PP); //GPIO_Mode_IPU
- }
- escCount = 0;
- pwmEnableMotors();
-}
-
-#ifdef STM32F10X
-static volatile uint32_t in_cr_mask, out_cr_mask;
-
-static __IO uint32_t *cr;
-static void gpio_prep_vars(uint32_t escIndex)
-{
- GPIO_TypeDef *gpio = escHardware[escIndex].gpio;
- uint32_t pinpos = escHardware[escIndex].pinpos;
- // mask out extra bits from pinmode, leaving just CNF+MODE
- uint32_t inmode = Mode_IPU & 0x0F;
- uint32_t outmode = (Mode_Out_PP & 0x0F) | Speed_10MHz;
- // reference CRL or CRH, depending whether pin number is 0..7 or 8..15
- cr = &gpio->CRL + (pinpos / 8);
- // offset to CNF and MODE portions of CRx register
- uint32_t shift = (pinpos % 8) * 4;
- // Read out current CRx value
- in_cr_mask = out_cr_mask = *cr;
- // Mask out 4 bits
- in_cr_mask &= ~(0xF << shift);
- out_cr_mask &= ~(0xF << shift);
- // save current pinmode
- in_cr_mask |= inmode << shift;
- out_cr_mask |= outmode << shift;
-}
-
-static void gpioSetOne(uint32_t escIndex, GPIO_Mode mode) {
- // reference CRL or CRH, depending whether pin number is 0..7 or 8..15
- if (mode == Mode_IPU) {
- *cr = in_cr_mask;
- escHardware[escIndex].gpio->ODR |= escHardware[escIndex].pin;
- }
- else {
- *cr = out_cr_mask;
- }
-}
-#endif
-
-#define ESC_HI(escIndex) ((escHardware[escIndex].gpio->IDR & escHardware[escIndex].pin) != (uint32_t)Bit_RESET)
-#define RX_HI ((S1W_RX_GPIO->IDR & S1W_RX_PIN) != (uint32_t)Bit_RESET)
-#define ESC_SET_HI(escIndex) escHardware[escIndex].gpio->BSRR = escHardware[escIndex].pin
-#define ESC_SET_LO(escIndex) escHardware[escIndex].gpio->BRR = escHardware[escIndex].pin
-#define TX_SET_HIGH S1W_TX_GPIO->BSRR = S1W_TX_PIN
-#define TX_SET_LO S1W_TX_GPIO->BRR = S1W_TX_PIN
-
-#ifdef STM32F303xC
-#define ESC_INPUT(escIndex) escHardware[escIndex].gpio->MODER &= ~(GPIO_MODER_MODER0 << (escHardware[escIndex].pinpos * 2))
-#define ESC_OUTPUT(escIndex) escHardware[escIndex].gpio->MODER |= GPIO_Mode_OUT << (escHardware[escIndex].pinpos * 2)
-#endif
-
-#ifdef STM32F10X
-#define ESC_INPUT(escIndex) gpioSetOne(escIndex, Mode_IPU)
-#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
-#define TX_LED_ON LED1_ON
-
-// This method translates 2 wires (a tx and rx line) to 1 wire, by letting the
-// 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);
-
-#ifdef STM32F10X
- // reset our gpio register pointers and bitmask values
- gpio_prep_vars(escIndex);
-#endif
-
- ESC_OUTPUT(escIndex);
- ESC_SET_HI(escIndex);
- TX_SET_HIGH;
- // Wait for programmer to go from 1 -> 0 indicating incoming data
- while(RX_HI);
-
- while(1) {
- // A new iteration on this loop starts when we have data from the programmer (read_programmer goes low)
- // Setup escIndex pin to send data, pullup is the default
- ESC_OUTPUT(escIndex);
- // Write the first bit
- ESC_SET_LO(escIndex);
- // Echo on the programmer tx line
- TX_SET_LO;
- //set LEDs
- RX_LED_OFF;
- TX_LED_ON;
- // Wait for programmer to go 0 -> 1
- uint32_t ct=3333;
- while(!RX_HI) {
- 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
- }
- // Programmer is high, end of bit
- // 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);
- TX_LED_OFF;
- 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 {
- TX_SET_LO;
- RX_LED_ON;
- }
- }
- }
-
- // we get here in case ct reached zero
- TX_SET_HIGH;
- RX_LED_OFF;
- // reactivate serial port
- gpio_set_mode(S1W_TX_GPIO, S1W_TX_PIN, Mode_AF_PP);
- // Enable all irq (for Hardware UART)
- __enable_irq();
- return;
-}
-#endif
diff --git a/src/main/io/serial_1wire.h b/src/main/io/serial_1wire.h
deleted file mode 100644
index 594cdd43a..000000000
--- a/src/main/io/serial_1wire.h
+++ /dev/null
@@ -1,37 +0,0 @@
-/*
- * 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 .
- *
- * Ported from https://github.com/4712/BLHeliSuite/blob/master/Interfaces/Arduino1Wire/Source/Arduino1Wire_C/Arduino1Wire.c
- * by Nathan Tsoi
- */
-
-#pragma once
-
-#ifdef USE_SERIAL_1WIRE
-
-extern uint8_t escCount;
-
-typedef struct {
- GPIO_TypeDef* gpio;
- uint16_t pinpos;
- uint16_t pin;
-} escHardware_t;
-
-
-void usb1WireInitialize();
-void usb1WirePassthrough(uint8_t escIndex);
-void usb1WireDeInitialize(void);
-#endif
diff --git a/src/main/io/serial_1wire.h~HEAD b/src/main/io/serial_1wire.h~HEAD
deleted file mode 100644
index 594cdd43a..000000000
--- a/src/main/io/serial_1wire.h~HEAD
+++ /dev/null
@@ -1,37 +0,0 @@
-/*
- * 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 .
- *
- * Ported from https://github.com/4712/BLHeliSuite/blob/master/Interfaces/Arduino1Wire/Source/Arduino1Wire_C/Arduino1Wire.c
- * by Nathan Tsoi
- */
-
-#pragma once
-
-#ifdef USE_SERIAL_1WIRE
-
-extern uint8_t escCount;
-
-typedef struct {
- GPIO_TypeDef* gpio;
- uint16_t pinpos;
- uint16_t pin;
-} escHardware_t;
-
-
-void usb1WireInitialize();
-void usb1WirePassthrough(uint8_t escIndex);
-void usb1WireDeInitialize(void);
-#endif
diff --git a/src/main/io/serial_1wire.h~a94ce1fef3a5d63c8af6a85b24f8eba2961e0890 b/src/main/io/serial_1wire.h~a94ce1fef3a5d63c8af6a85b24f8eba2961e0890
deleted file mode 100644
index 1e560ed93..000000000
--- a/src/main/io/serial_1wire.h~a94ce1fef3a5d63c8af6a85b24f8eba2961e0890
+++ /dev/null
@@ -1,36 +0,0 @@
-/*
- * 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 .
- *
- * Ported from https://github.com/4712/BLHeliSuite/blob/master/Interfaces/Arduino1Wire/Source/Arduino1Wire_C/Arduino1Wire.c
- * by Nathan Tsoi
- */
-
-#pragma once
-
-#ifdef USE_SERIAL_1WIRE
-
-extern uint8_t escCount;
-
-typedef struct {
- GPIO_TypeDef* gpio;
- uint16_t pinpos;
- uint16_t pin;
-} escHardware_t;
-
-
-void usb1WireInitialize();
-void usb1WirePassthrough(uint8_t escIndex);
-#endif
diff --git a/src/main/io/serial_1wire_vcp.c b/src/main/io/serial_1wire_vcp.c
deleted file mode 100644
index 6e350f769..000000000
--- a/src/main/io/serial_1wire_vcp.c
+++ /dev/null
@@ -1,224 +0,0 @@
-/*
- * 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 .
- *
- * Author 4712
- */
-
-#include
-#include
-#include
-#include
-#include "platform.h"
-
-#ifdef USE_SERIAL_1WIRE_VCP
-#include "drivers/gpio.h"
-#include "drivers/light_led.h"
-#include "drivers/system.h"
-#include "io/serial_1wire_vcp.h"
-#include "io/beeper.h"
-#include "drivers/pwm_mapping.h"
-#include "drivers/pwm_output.h"
-#include "flight/mixer.h"
-#include "io/serial_msp.h"
-#include "drivers/buf_writer.h"
-#include "drivers/serial_usb_vcp.h"
-
-uint8_t escCount;
-
-static escHardware_t escHardware[MAX_PWM_MOTORS];
-
-static uint32_t GetPinPos(uint32_t pin) {
- uint32_t pinPos;
- for (pinPos = 0; pinPos < 16; pinPos++) {
- uint32_t pinMask = (0x1 << pinPos);
- if (pin & pinMask) {
- return pinPos;
- }
- }
- return 0;
-}
-static uint8_t selected_esc;
-
-#define ESC_IS_HI digitalIn(escHardware[selected_esc].gpio, escHardware[selected_esc].pin) != Bit_RESET
-#define ESC_IS_LO digitalIn(escHardware[selected_esc].gpio, escHardware[selected_esc].pin) == Bit_RESET
-#define ESC_SET_HI digitalHi(escHardware[selected_esc].gpio, escHardware[selected_esc].pin)
-#define ESC_SET_LO digitalLo(escHardware[selected_esc].gpio, escHardware[selected_esc].pin)
-
-#define ESC_INPUT gpioInit(escHardware[selected_esc].gpio, &escHardware[selected_esc].gpio_config_INPUT)
-#define ESC_OUTPUT gpioInit(escHardware[selected_esc].gpio, &escHardware[selected_esc].gpio_config_OUTPUT)
-
-void usb1WireInitializeVcp(void)
-{
- pwmDisableMotors();
- selected_esc = 0;
- memset(&escHardware, 0, sizeof(escHardware));
- pwmOutputConfiguration_t *pwmOutputConfiguration = pwmGetOutputConfiguration();
- 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[selected_esc].gpio = pwmOutputConfiguration->portConfigurations[i].timerHardware->gpio;
- escHardware[selected_esc].pin = pwmOutputConfiguration->portConfigurations[i].timerHardware->pin;
- escHardware[selected_esc].pinpos = GetPinPos(escHardware[selected_esc].pin);
- escHardware[selected_esc].gpio_config_INPUT.pin = escHardware[selected_esc].pin;
- escHardware[selected_esc].gpio_config_INPUT.speed = Speed_2MHz; // see pwmOutConfig()
- escHardware[selected_esc].gpio_config_INPUT.mode = Mode_IPU;
- escHardware[selected_esc].gpio_config_OUTPUT = escHardware[selected_esc].gpio_config_INPUT;
- escHardware[selected_esc].gpio_config_OUTPUT.mode = Mode_Out_PP;
- ESC_INPUT;
- ESC_SET_HI;
- selected_esc++;
- }
- }
- }
- escCount = selected_esc;
- selected_esc = 0;
-}
-
-void usb1WireDeInitializeVcp(void){
- for (selected_esc = 0; selected_esc < (escCount); selected_esc++) {
- escHardware[selected_esc].gpio_config_OUTPUT.mode = Mode_AF_PP; // see pwmOutConfig()
- ESC_OUTPUT;
- ESC_SET_LO;
- }
- escCount = 0;
- pwmEnableMotors();
-}
-
-#define START_BIT_TIMEOUT_MS 2
-
-#define BIT_TIME (52) //52uS
-#define BIT_TIME_HALVE (BIT_TIME >> 1) //26uS
-#define START_BIT_TIME (BIT_TIME_HALVE + 1)
-#define STOP_BIT_TIME ((BIT_TIME * 9) + BIT_TIME_HALVE)
-
-static void suart_putc_(uint8_t *tx_b)
-{
- // shift out stopbit first
- uint16_t bitmask = (*tx_b << 2) | 1 | (1 << 10);
- uint32_t btime = micros();
- while(1) {
- if(bitmask & 1) {
- ESC_SET_HI; // 1
- } else {
- ESC_SET_LO; // 0
- }
- btime = btime + BIT_TIME;
- bitmask = (bitmask >> 1);
- if (bitmask == 0) break; // stopbit shifted out - but don't wait
- while (micros() < btime);
- }
-}
-
-static uint8_t suart_getc_(uint8_t *bt)
-{
- uint32_t btime;
- uint32_t start_time;
-
- uint32_t wait_time = millis() + START_BIT_TIMEOUT_MS;
- while (ESC_IS_HI) {
- // check for startbit begin
- if (millis() >= wait_time) {
- return 0;
- }
- }
- // start bit
- start_time = micros();
- btime = start_time + START_BIT_TIME;
- uint16_t bitmask = 0;
- uint8_t bit = 0;
- while (micros() < btime);
- while(1) {
- if (ESC_IS_HI) {
- bitmask |= (1 << bit);
- }
- btime = btime + BIT_TIME;
- bit++;
- if (bit == 10) break;
- while (micros() < btime);
- }
- // check start bit and stop bit
- if ((bitmask & 1) || (!(bitmask & (1 << 9)))) {
- return 0;
- }
- *bt = bitmask >> 1;
- return 1;
-}
-#define USE_TXRX_LED
-
-#ifdef USE_TXRX_LED
-#define RX_LED_OFF LED0_OFF
-#define RX_LED_ON LED0_ON
-#ifdef LED1
-#define TX_LED_OFF LED1_OFF
-#define TX_LED_ON LED1_ON
-#else
-#define TX_LED_OFF LED0_OFF
-#define TX_LED_ON LED0_ON
-#endif
-#else
-#define RX_LED_OFF
-#define RX_LED_ON
-#define TX_LED_OFF
-#define TX_LED_ON
-#endif
-
-// This method translates 2 wires (a tx and rx line) to 1 wire, by letting the
-// RX line control when data should be read or written from the single line
-void usb1WirePassthroughVcp(mspPort_t *mspPort, bufWriter_t *bufwriter, uint8_t escIndex)
-{
-#ifdef BEEPER
- // fix for buzzer often starts beeping continuously when the ESCs are read
- // switch beeper silent here
- // TODO (4712) do we need beeperSilence()?
- // beeperSilence();
-#endif
-
- selected_esc = escIndex;
- // TODO (4712) check all possible baud rate ok?
- // uint32_t baudrate = serialGetBaudRate(mspPort->port);
- // serialSetBaudRate(mspPort->port, 19200);
-
- while(usbVcpGetBaudRate(mspPort->port) != 4800) {
- // esc line is in Mode_IPU by default
- static uint8_t bt;
-
- if (suart_getc_(&bt)) {
- RX_LED_ON;
- serialBeginWrite(mspPort->port);
- bufWriterAppend(bufwriter, bt);
- while (suart_getc_(&bt)){
- bufWriterAppend(bufwriter, bt);
- }
- serialEndWrite(mspPort->port);
- bufWriterFlush(bufwriter);
- RX_LED_OFF;
- }
- if (serialRxBytesWaiting(mspPort->port)) {
- ESC_OUTPUT;
- TX_LED_ON;
- do {
- bt = serialRead(mspPort->port);
- suart_putc_(&bt);
- } while(serialRxBytesWaiting(mspPort->port));
- ESC_INPUT;
- TX_LED_OFF;
- }
- }
- // serialSetBaudRate(mspPort->port, baudrate);
- return;
-}
-#endif
-
diff --git a/src/main/io/serial_1wire_vcp.h b/src/main/io/serial_1wire_vcp.h
deleted file mode 100644
index 0f4a6a3dc..000000000
--- a/src/main/io/serial_1wire_vcp.h
+++ /dev/null
@@ -1,42 +0,0 @@
-/*
- * 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 .
- *
- * Author 4712
- */
-#pragma once
-
-#include "platform.h"
-#ifdef USE_SERIAL_1WIRE_VCP
-#include "drivers/serial.h"
-#include "drivers/buf_writer.h"
-#include "drivers/pwm_mapping.h"
-#include "io/serial_msp.h"
-
-extern uint8_t escCount;
-
-typedef struct {
- GPIO_TypeDef* gpio;
- uint16_t pinpos;
- uint16_t pin;
- gpio_config_t gpio_config_INPUT;
- gpio_config_t gpio_config_OUTPUT;
-} escHardware_t;
-
-void usb1WireInitializeVcp(void);
-void usb1WireDeInitializeVcp(void);
-void usb1WirePassthroughVcp(mspPort_t *mspPort, bufWriter_t *bufwriter, uint8_t escIndex);
-#endif
-
diff --git a/src/main/io/serial_4way.c b/src/main/io/serial_4way.c
index 0e7fc889f..5f0dfb466 100644
--- a/src/main/io/serial_4way.c
+++ b/src/main/io/serial_4way.c
@@ -15,20 +15,29 @@
* along with Cleanflight. If not, see .
* Author: 4712
*/
-#include "platform.h"
-#if (defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
+
#include
#include
#include
#include
#include
-#include "drivers/system.h"
+
+#include "platform.h"
+#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
+#include "drivers/serial.h"
+#include "drivers/buf_writer.h"
+#include "drivers/gpio.h"
+#include "drivers/timer.h"
+#include "drivers/pwm_mapping.h"
#include "drivers/pwm_output.h"
+#include "drivers/light_led.h"
+#include "drivers/system.h"
+#include "drivers/buf_writer.h"
#include "flight/mixer.h"
#include "io/beeper.h"
-#include "io/serial_4way.h"
#include "io/serial_msp.h"
-#include "drivers/buf_writer.h"
+#include "io/serial_msp.h"
+#include "io/serial_4way.h"
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
#include "io/serial_4way_avrootloader.h"
@@ -37,11 +46,30 @@
#include "io/serial_4way_stk500v2.h"
#endif
+#define USE_TXRX_LED
+
+#ifdef USE_TXRX_LED
+#define RX_LED_OFF LED0_OFF
+#define RX_LED_ON LED0_ON
+#ifdef LED1
+#define TX_LED_OFF LED1_OFF
+#define TX_LED_ON LED1_ON
+#else
+#define TX_LED_OFF LED0_OFF
+#define TX_LED_ON LED0_ON
+#endif
+#else
+#define RX_LED_OFF
+#define RX_LED_ON
+#define TX_LED_OFF
+#define TX_LED_ON
+#endif
+
#define SERIAL_4WAY_INTERFACE_NAME_STR "m4wFCIntf"
// *** change to adapt Revision
#define SERIAL_4WAY_VER_MAIN 14
#define SERIAL_4WAY_VER_SUB_1 (uint8_t) 4
-#define SERIAL_4WAY_VER_SUB_2 (uint8_t) 03
+#define SERIAL_4WAY_VER_SUB_2 (uint8_t) 04
#define SERIAL_4WAY_PROTOCOL_VER 106
// *** end
@@ -50,7 +78,6 @@
#error "beware of SERIAL_4WAY_VER_SUB_1 is uint8_t"
#endif
-
#define SERIAL_4WAY_VERSION (uint16_t) ((SERIAL_4WAY_VER_MAIN * 1000) + (SERIAL_4WAY_VER_SUB_1 * 100) + SERIAL_4WAY_VER_SUB_2)
#define SERIAL_4WAY_VERSION_HI (uint8_t) (SERIAL_4WAY_VERSION / 100)
@@ -58,6 +85,48 @@
static uint8_t escCount;
+escHardware_t escHardware[MAX_PWM_MOTORS];
+
+uint8_t selected_esc;
+
+uint8_32_u DeviceInfo;
+
+#define DeviceInfoSize 4
+
+inline bool isMcuConnected(void)
+{
+ return (DeviceInfo.bytes[0] > 0);
+}
+
+inline bool isEscHi(uint8_t selEsc)
+{
+ return (digitalIn(escHardware[selEsc].gpio, escHardware[selEsc].pin) != Bit_RESET);
+}
+inline bool isEscLo(uint8_t selEsc)
+{
+ return (digitalIn(escHardware[selEsc].gpio, escHardware[selEsc].pin) == Bit_RESET);
+}
+
+inline void setEscHi(uint8_t selEsc)
+{
+ digitalHi(escHardware[selEsc].gpio, escHardware[selEsc].pin);
+}
+
+inline void setEscLo(uint8_t selEsc)
+{
+ digitalLo(escHardware[selEsc].gpio, escHardware[selEsc].pin);
+}
+
+inline void setEscInput(uint8_t selEsc)
+{
+ gpioInit(escHardware[selEsc].gpio, &escHardware[selEsc].gpio_config_INPUT);
+}
+
+inline void setEscOutput(uint8_t selEsc)
+{
+ gpioInit(escHardware[selEsc].gpio, &escHardware[selEsc].gpio_config_OUTPUT);
+}
+
static uint32_t GetPinPos(uint32_t pin)
{
uint32_t pinPos;
@@ -74,38 +143,37 @@ uint8_t Initialize4WayInterface(void)
{
// StopPwmAllMotors();
pwmDisableMotors();
- selected_esc = 0;
+ escCount = 0;
memset(&escHardware, 0, sizeof(escHardware));
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmGetOutputConfiguration();
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[selected_esc].gpio = pwmOutputConfiguration->portConfigurations[i].timerHardware->gpio;
- escHardware[selected_esc].pin = pwmOutputConfiguration->portConfigurations[i].timerHardware->pin;
- escHardware[selected_esc].pinpos = GetPinPos(escHardware[selected_esc].pin);
- escHardware[selected_esc].gpio_config_INPUT.pin = escHardware[selected_esc].pin;
- escHardware[selected_esc].gpio_config_INPUT.speed = Speed_2MHz; // see pwmOutConfig()
- escHardware[selected_esc].gpio_config_INPUT.mode = Mode_IPU;
- escHardware[selected_esc].gpio_config_OUTPUT = escHardware[selected_esc].gpio_config_INPUT;
- escHardware[selected_esc].gpio_config_OUTPUT.mode = Mode_Out_PP;
- ESC_INPUT;
- ESC_SET_HI;
- selected_esc++;
+ escHardware[escCount].gpio = pwmOutputConfiguration->portConfigurations[i].timerHardware->gpio;
+ escHardware[escCount].pin = pwmOutputConfiguration->portConfigurations[i].timerHardware->pin;
+ escHardware[escCount].pinpos = GetPinPos(escHardware[escCount].pin);
+ escHardware[escCount].gpio_config_INPUT.pin = escHardware[escCount].pin;
+ escHardware[escCount].gpio_config_INPUT.speed = Speed_2MHz; // see pwmOutConfig()
+ escHardware[escCount].gpio_config_INPUT.mode = Mode_IPU;
+ escHardware[escCount].gpio_config_OUTPUT = escHardware[escCount].gpio_config_INPUT;
+ escHardware[escCount].gpio_config_OUTPUT.mode = Mode_Out_PP;
+ setEscInput(escCount);
+ setEscHi(escCount);
+ escCount++;
}
}
}
- escCount = selected_esc;
return escCount;
}
void DeInitialize4WayInterface(void)
{
- for (selected_esc = 0; selected_esc < (escCount); selected_esc++) {
- escHardware[selected_esc].gpio_config_OUTPUT.mode = Mode_AF_PP; // see pwmOutConfig()
- ESC_OUTPUT;
- ESC_SET_LO;
+ while (escCount > 0) {
+ escCount--;
+ escHardware[escCount].gpio_config_OUTPUT.mode = Mode_AF_PP; // see pwmOutConfig()
+ setEscOutput(escCount);
+ setEscLo(escCount);
}
- escCount = 0;
pwmEnableMotors();
}
@@ -265,25 +333,25 @@ uint16_t _crc_xmodem_update (uint16_t crc, uint8_t data) {
// * End copyright
-#define ATMEL_DEVICE_MATCH ((DeviceInfo.words[0] == 0x9307) || (DeviceInfo.words[0] == 0x930A) || \
- (DeviceInfo.words[0] == 0x930F) || (DeviceInfo.words[0] == 0x940B))
+#define ATMEL_DEVICE_MATCH ((pDeviceInfo->words[0] == 0x9307) || (pDeviceInfo->words[0] == 0x930A) || \
+ (pDeviceInfo->words[0] == 0x930F) || (pDeviceInfo->words[0] == 0x940B))
-#define SILABS_DEVICE_MATCH ((DeviceInfo.words[0] == 0xF310)||(DeviceInfo.words[0] ==0xF330) || \
- (DeviceInfo.words[0] == 0xF410) || (DeviceInfo.words[0] == 0xF390) || \
- (DeviceInfo.words[0] == 0xF850) || (DeviceInfo.words[0] == 0xE8B1) || \
- (DeviceInfo.words[0] == 0xE8B2))
+#define SILABS_DEVICE_MATCH ((pDeviceInfo->words[0] == 0xF310)||(pDeviceInfo->words[0] ==0xF330) || \
+ (pDeviceInfo->words[0] == 0xF410) || (pDeviceInfo->words[0] == 0xF390) || \
+ (pDeviceInfo->words[0] == 0xF850) || (pDeviceInfo->words[0] == 0xE8B1) || \
+ (pDeviceInfo->words[0] == 0xE8B2))
static uint8_t CurrentInterfaceMode;
-static uint8_t Connect(void)
+static uint8_t Connect(uint8_32_u *pDeviceInfo)
{
for (uint8_t I = 0; I < 3; ++I) {
#if (defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) && defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
- if (Stk_ConnectEx() && ATMEL_DEVICE_MATCH) {
+ if (Stk_ConnectEx(pDeviceInfo) && ATMEL_DEVICE_MATCH) {
CurrentInterfaceMode = imSK;
return 1;
} else {
- if (BL_ConnectEx()) {
+ if (BL_ConnectEx(pDeviceInfo)) {
if SILABS_DEVICE_MATCH {
CurrentInterfaceMode = imSIL_BLB;
return 1;
@@ -294,7 +362,7 @@ static uint8_t Connect(void)
}
}
#elif defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER)
- if (BL_ConnectEx()) {
+ if (BL_ConnectEx(pDeviceInfo)) {
if SILABS_DEVICE_MATCH {
CurrentInterfaceMode = imSIL_BLB;
return 1;
@@ -304,7 +372,7 @@ static uint8_t Connect(void)
}
}
#elif defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
- if (Stk_ConnectEx()) {
+ if (Stk_ConnectEx(pDeviceInfo)) {
CurrentInterfaceMode = imSK;
if ATMEL_DEVICE_MATCH return 1;
}
@@ -322,7 +390,7 @@ static uint8_t ReadByte(void) {
return serialRead(_mspPort->port);
}
-static union uint8_16u CRC_in;
+static uint8_16_u CRC_in;
static uint8_t ReadByteCrc(void) {
uint8_t b = ReadByte();
CRC_in.word = _crc_xmodem_update(CRC_in.word, b);
@@ -332,7 +400,7 @@ static void WriteByte(uint8_t b){
bufWriterAppend(_writer, b);
}
-static union uint8_16u CRCout;
+static uint8_16_u CRCout;
static void WriteByteCrc(uint8_t b){
WriteByte(b);
CRCout.word = _crc_xmodem_update(CRCout.word, b);
@@ -345,11 +413,12 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
uint8_t I_PARAM_LEN;
uint8_t CMD;
uint8_t ACK_OUT;
- union uint8_16u CRC_check;
- union uint8_16u Dummy;
+ uint8_16_u CRC_check;
+ uint8_16_u Dummy;
uint8_t O_PARAM_LEN;
uint8_t *O_PARAM;
uint8_t *InBuff;
+ ioMem_t ioMem;
_mspPort = mspPort;
_writer = bufwriter;
@@ -375,8 +444,8 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
O_PARAM = &Dummy.bytes[0];
O_PARAM_LEN = 1;
CMD = ReadByteCrc();
- D_FLASH_ADDR_H = ReadByteCrc();
- D_FLASH_ADDR_L = ReadByteCrc();
+ ioMem.D_FLASH_ADDR_H = ReadByteCrc();
+ ioMem.D_FLASH_ADDR_L = ReadByteCrc();
I_PARAM_LEN = ReadByteCrc();
InBuff = ParamBuf;
@@ -400,15 +469,15 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
if (ACK_OUT == ACK_OK)
{
- // D_FLASH_ADDR_H=Adress_H;
- // D_FLASH_ADDR_L=Adress_L;
- D_PTR_I = ParamBuf;
+ // wtf.D_FLASH_ADDR_H=Adress_H;
+ // wtf.D_FLASH_ADDR_L=Adress_L;
+ ioMem.D_PTR_I = ParamBuf;
switch(CMD) {
// ******* Interface related stuff *******
case cmd_InterfaceTestAlive:
{
- if (IsMcuConnected){
+ if (isMcuConnected()){
switch(CurrentInterfaceMode)
{
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
@@ -499,7 +568,7 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
case imATM_BLB:
{
- BL_SendCMDRunRestartBootloader();
+ BL_SendCMDRunRestartBootloader(&DeviceInfo);
break;
}
#endif
@@ -526,7 +595,7 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
}
O_PARAM_LEN = DeviceInfoSize; //4
O_PARAM = (uint8_t *)&DeviceInfo;
- if(Connect()) {
+ if(Connect(&DeviceInfo)) {
DeviceInfo.bytes[INTF_MODE_IDX] = CurrentInterfaceMode;
} else {
SET_DISCONNECTED;
@@ -561,9 +630,9 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
{
Dummy.bytes[0] = ParamBuf[0];
//Address = Page * 512
- D_FLASH_ADDR_H = (Dummy.bytes[0] << 1);
- D_FLASH_ADDR_L = 0;
- if (!BL_PageErase()) ACK_OUT = ACK_D_GENERAL_ERROR;
+ ioMem.D_FLASH_ADDR_H = (Dummy.bytes[0] << 1);
+ ioMem.D_FLASH_ADDR_L = 0;
+ if (!BL_PageErase(&ioMem)) ACK_OUT = ACK_D_GENERAL_ERROR;
break;
}
default:
@@ -576,11 +645,11 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
//*** Device Memory Read Ops ***
case cmd_DeviceRead:
{
- D_NUM_BYTES = ParamBuf[0];
+ ioMem.D_NUM_BYTES = ParamBuf[0];
/*
- D_FLASH_ADDR_H=Adress_H;
- D_FLASH_ADDR_L=Adress_L;
- D_PTR_I = BUF_I;
+ wtf.D_FLASH_ADDR_H=Adress_H;
+ wtf.D_FLASH_ADDR_L=Adress_L;
+ wtf.D_PTR_I = BUF_I;
*/
switch(CurrentInterfaceMode)
{
@@ -588,7 +657,7 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
case imSIL_BLB:
case imATM_BLB:
{
- if(!BL_ReadFlash(CurrentInterfaceMode))
+ if(!BL_ReadFlash(CurrentInterfaceMode, &ioMem))
{
ACK_OUT = ACK_D_GENERAL_ERROR;
}
@@ -598,7 +667,7 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
case imSK:
{
- if(!Stk_ReadFlash())
+ if(!Stk_ReadFlash(&ioMem))
{
ACK_OUT = ACK_D_GENERAL_ERROR;
}
@@ -610,7 +679,7 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
}
if (ACK_OUT == ACK_OK)
{
- O_PARAM_LEN = D_NUM_BYTES;
+ O_PARAM_LEN = ioMem.D_NUM_BYTES;
O_PARAM = (uint8_t *)&ParamBuf;
}
break;
@@ -618,18 +687,18 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
case cmd_DeviceReadEEprom:
{
- D_NUM_BYTES = ParamBuf[0];
+ ioMem.D_NUM_BYTES = ParamBuf[0];
/*
- D_FLASH_ADDR_H = Adress_H;
- D_FLASH_ADDR_L = Adress_L;
- D_PTR_I = BUF_I;
+ wtf.D_FLASH_ADDR_H = Adress_H;
+ wtf.D_FLASH_ADDR_L = Adress_L;
+ wtf.D_PTR_I = BUF_I;
*/
switch (CurrentInterfaceMode)
{
#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
case imATM_BLB:
{
- if (!BL_ReadEEprom())
+ if (!BL_ReadEEprom(&ioMem))
{
ACK_OUT = ACK_D_GENERAL_ERROR;
}
@@ -639,7 +708,7 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
case imSK:
{
- if (!Stk_ReadEEprom())
+ if (!Stk_ReadEEprom(&ioMem))
{
ACK_OUT = ACK_D_GENERAL_ERROR;
}
@@ -651,7 +720,7 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
}
if(ACK_OUT == ACK_OK)
{
- O_PARAM_LEN = D_NUM_BYTES;
+ O_PARAM_LEN = ioMem.D_NUM_BYTES;
O_PARAM = (uint8_t *)&ParamBuf;
}
break;
@@ -660,11 +729,11 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
//*** Device Memory Write Ops ***
case cmd_DeviceWrite:
{
- D_NUM_BYTES = I_PARAM_LEN;
+ ioMem.D_NUM_BYTES = I_PARAM_LEN;
/*
- D_FLASH_ADDR_H=Adress_H;
- D_FLASH_ADDR_L=Adress_L;
- D_PTR_I = BUF_I;
+ wtf.D_FLASH_ADDR_H=Adress_H;
+ wtf.D_FLASH_ADDR_L=Adress_L;
+ wtf.D_PTR_I = BUF_I;
*/
switch (CurrentInterfaceMode)
{
@@ -672,7 +741,7 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
case imSIL_BLB:
case imATM_BLB:
{
- if (!BL_WriteFlash()) {
+ if (!BL_WriteFlash(&ioMem)) {
ACK_OUT = ACK_D_GENERAL_ERROR;
}
break;
@@ -681,7 +750,7 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
case imSK:
{
- if (!Stk_WriteFlash())
+ if (!Stk_WriteFlash(&ioMem))
{
ACK_OUT = ACK_D_GENERAL_ERROR;
}
@@ -694,12 +763,12 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
case cmd_DeviceWriteEEprom:
{
- D_NUM_BYTES = I_PARAM_LEN;
+ ioMem.D_NUM_BYTES = I_PARAM_LEN;
ACK_OUT = ACK_D_GENERAL_ERROR;
/*
- D_FLASH_ADDR_H=Adress_H;
- D_FLASH_ADDR_L=Adress_L;
- D_PTR_I = BUF_I;
+ wtf.D_FLASH_ADDR_H=Adress_H;
+ wtf.D_FLASH_ADDR_L=Adress_L;
+ wtf.D_PTR_I = BUF_I;
*/
switch (CurrentInterfaceMode)
{
@@ -711,7 +780,7 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
}
case imATM_BLB:
{
- if (BL_WriteEEprom())
+ if (BL_WriteEEprom(&ioMem))
{
ACK_OUT = ACK_OK;
}
@@ -721,7 +790,7 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
case imSK:
{
- if (Stk_WriteEEprom())
+ if (Stk_WriteEEprom(&ioMem))
{
ACK_OUT = ACK_OK;
}
@@ -744,8 +813,8 @@ void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter) {
serialBeginWrite(_mspPort->port);
WriteByteCrc(cmd_Remote_Escape);
WriteByteCrc(CMD);
- WriteByteCrc(D_FLASH_ADDR_H);
- WriteByteCrc(D_FLASH_ADDR_L);
+ WriteByteCrc(ioMem.D_FLASH_ADDR_H);
+ WriteByteCrc(ioMem.D_FLASH_ADDR_L);
WriteByteCrc(O_PARAM_LEN);
i=O_PARAM_LEN;
diff --git a/src/main/io/serial_4way.h b/src/main/io/serial_4way.h
index 853b120a2..1a350e682 100644
--- a/src/main/io/serial_4way.h
+++ b/src/main/io/serial_4way.h
@@ -16,27 +16,14 @@
* Author: 4712
*/
-#include
-#if (defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
-#include "drivers/serial.h"
-#include "drivers/buf_writer.h"
-#include "drivers/gpio.h"
-#include "drivers/timer.h"
-#include "drivers/pwm_mapping.h"
-#include "drivers/light_led.h"
-#include "io/serial_msp.h"
-
+#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
+#define USE_SERIAL_4WAY_SK_BOOTLOADER
#define imC2 0
#define imSIL_BLB 1
#define imATM_BLB 2
#define imSK 3
-#define RX_LED_OFF LED0_OFF
-#define RX_LED_ON LED0_ON
-#define TX_LED_OFF LED1_OFF
-#define TX_LED_ON LED1_ON
-
typedef struct {
GPIO_TypeDef* gpio;
uint16_t pinpos;
@@ -45,51 +32,45 @@ typedef struct {
gpio_config_t gpio_config_OUTPUT;
} escHardware_t;
-uint8_t selected_esc;
+extern uint8_t selected_esc;
-escHardware_t escHardware[MAX_PWM_MOTORS];
+bool isEscHi(uint8_t selEsc);
+bool isEscLo(uint8_t selEsc);
+void setEscHi(uint8_t selEsc);
+void setEscLo(uint8_t selEsc);
+void setEscInput(uint8_t selEsc);
+void setEscOutput(uint8_t selEsc);
-#define ESC_IS_HI digitalIn(escHardware[selected_esc].gpio, escHardware[selected_esc].pin) != Bit_RESET
-#define ESC_IS_LO digitalIn(escHardware[selected_esc].gpio, escHardware[selected_esc].pin) == Bit_RESET
-#define ESC_SET_HI digitalHi(escHardware[selected_esc].gpio, escHardware[selected_esc].pin)
-#define ESC_SET_LO digitalLo(escHardware[selected_esc].gpio, escHardware[selected_esc].pin)
+#define ESC_IS_HI isEscHi(selected_esc)
+#define ESC_IS_LO isEscLo(selected_esc)
+#define ESC_SET_HI setEscHi(selected_esc)
+#define ESC_SET_LO setEscLo(selected_esc)
+#define ESC_INPUT setEscInput(selected_esc)
+#define ESC_OUTPUT setEscOutput(selected_esc)
-#define ESC_INPUT gpioInit(escHardware[selected_esc].gpio, &escHardware[selected_esc].gpio_config_INPUT)
-#define ESC_OUTPUT gpioInit(escHardware[selected_esc].gpio, &escHardware[selected_esc].gpio_config_OUTPUT)
+typedef struct ioMem_s {
+ uint8_t D_NUM_BYTES;
+ uint8_t D_FLASH_ADDR_H;
+ uint8_t D_FLASH_ADDR_L;
+ uint8_t *D_PTR_I;
+} ioMem_t;
+extern ioMem_t ioMem;
-
-void delay_us(uint32_t delay);
-
-union __attribute__ ((packed)) uint8_16u
-{
+typedef union __attribute__ ((packed)) {
uint8_t bytes[2];
uint16_t word;
-};
+} uint8_16_u;
-union __attribute__ ((packed)) uint8_32u
-{
+typedef union __attribute__ ((packed)) {
uint8_t bytes[4];
uint16_t words[2];
uint32_t dword;
-};
+} uint8_32_u;
-//-----------------------------------------------------------------------------------
-// Global VARIABLES
-//-----------------------------------------------------------------------------------
-uint8_t D_NUM_BYTES;
-uint8_t D_FLASH_ADDR_H;
-uint8_t D_FLASH_ADDR_L;
-uint8_t *D_PTR_I;
-
-#define DeviceInfoSize 4
-
-union uint8_32u DeviceInfo;
-
-#define IsMcuConnected (DeviceInfo.bytes[0] > 0)
+//extern uint8_32_u DeviceInfo;
+bool isMcuConnected(void);
uint8_t Initialize4WayInterface(void);
void Process4WayInterface(mspPort_t *mspPort, bufWriter_t *bufwriter);
void DeInitialize4WayInterface(void);
-
-#endif
diff --git a/src/main/io/serial_4way_avrootloader.c b/src/main/io/serial_4way_avrootloader.c
index 9aca1fb2e..a44048b70 100644
--- a/src/main/io/serial_4way_avrootloader.c
+++ b/src/main/io/serial_4way_avrootloader.c
@@ -22,12 +22,20 @@
#include
#include
#include
-#include
+#include "platform.h"
-#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
+#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
#include "drivers/system.h"
-#include "io/serial_4way_avrootloader.h"
+#include "drivers/serial.h"
+#include "drivers/buf_writer.h"
+#include "drivers/pwm_mapping.h"
+#include "drivers/gpio.h"
+#include "io/serial.h"
+#include "io/serial_msp.h"
#include "io/serial_4way.h"
+#include "io/serial_4way_avrootloader.h"
+#ifdef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
+
// Bootloader commands
// RunCmd
@@ -62,7 +70,7 @@
#define BIT_TIME (52) //52uS
#define BIT_TIME_HALVE (BIT_TIME >> 1) //26uS
-#define START_BIT_TIME (BIT_TIME_HALVE)// + 1)
+#define START_BIT_TIME (BIT_TIME_HALVE + 1)
//#define STOP_BIT_TIME ((BIT_TIME * 9) + BIT_TIME_HALVE)
static uint8_t suart_getc_(uint8_t *bt)
@@ -120,8 +128,8 @@ static void suart_putc_(uint8_t *tx_b)
}
}
-static union uint8_16u CRC_16;
-static union uint8_16u LastCRC_16;
+static uint8_16_u CRC_16;
+static uint8_16_u LastCRC_16;
static void ByteCrc(uint8_t *bt)
{
@@ -151,7 +159,7 @@ static uint8_t BL_ReadBuf(uint8_t *pstring, uint8_t len)
len--;
} while(len > 0);
- if(IsMcuConnected) {
+ if(isMcuConnected()) {
//With CRC read 3 more
if(!suart_getc_(&LastCRC_16.bytes[0])) goto timeout;
if(!suart_getc_(&LastCRC_16.bytes[1])) goto timeout;
@@ -177,14 +185,14 @@ static void BL_SendBuf(uint8_t *pstring, uint8_t len)
len--;
} while (len > 0);
- if (IsMcuConnected) {
+ if (isMcuConnected()) {
suart_putc_(&CRC_16.bytes[0]);
suart_putc_(&CRC_16.bytes[1]);
}
ESC_INPUT;
}
-uint8_t BL_ConnectEx(void)
+uint8_t BL_ConnectEx(uint8_32_u *pDeviceInfo)
{
#define BootMsgLen 4
#define DevSignHi (BootMsgLen)
@@ -213,9 +221,9 @@ uint8_t BL_ConnectEx(void)
}
//only 2 bytes used $1E9307 -> 0x9307
- DeviceInfo.bytes[2] = BootInfo[BootMsgLen - 1];
- DeviceInfo.bytes[1] = BootInfo[DevSignHi];
- DeviceInfo.bytes[0] = BootInfo[DevSignLo];
+ pDeviceInfo->bytes[2] = BootInfo[BootMsgLen - 1];
+ pDeviceInfo->bytes[1] = BootInfo[DevSignHi];
+ pDeviceInfo->bytes[0] = BootInfo[DevSignLo];
return (1);
}
@@ -238,50 +246,50 @@ uint8_t BL_SendCMDKeepAlive(void)
return 1;
}
-void BL_SendCMDRunRestartBootloader(void)
+void BL_SendCMDRunRestartBootloader(uint8_32_u *pDeviceInfo)
{
uint8_t sCMD[] = {RestartBootloader, 0};
- DeviceInfo.bytes[0] = 1;
+ pDeviceInfo->bytes[0] = 1;
BL_SendBuf(sCMD, 2); //sends simply 4 x 0x00 (CRC =00)
return;
}
-static uint8_t BL_SendCMDSetAddress(void) //supports only 16 bit Adr
+static uint8_t BL_SendCMDSetAddress(ioMem_t *pMem) //supports only 16 bit Adr
{
// skip if adr == 0xFFFF
- if((D_FLASH_ADDR_H == 0xFF) && (D_FLASH_ADDR_L == 0xFF)) return 1;
- uint8_t sCMD[] = {CMD_SET_ADDRESS, 0, D_FLASH_ADDR_H, D_FLASH_ADDR_L };
+ if((pMem->D_FLASH_ADDR_H == 0xFF) && (pMem->D_FLASH_ADDR_L == 0xFF)) return 1;
+ uint8_t sCMD[] = {CMD_SET_ADDRESS, 0, pMem->D_FLASH_ADDR_H, pMem->D_FLASH_ADDR_L };
BL_SendBuf(sCMD, 4);
return (BL_GetACK(2) == brSUCCESS);
}
-static uint8_t BL_SendCMDSetBuffer(void)
+static uint8_t BL_SendCMDSetBuffer(ioMem_t *pMem)
{
- uint8_t sCMD[] = {CMD_SET_BUFFER, 0, 0, D_NUM_BYTES};
- if (D_NUM_BYTES == 0) {
+ uint8_t sCMD[] = {CMD_SET_BUFFER, 0, 0, pMem->D_NUM_BYTES};
+ if (pMem->D_NUM_BYTES == 0) {
// set high byte
sCMD[2] = 1;
}
BL_SendBuf(sCMD, 4);
if (BL_GetACK(2) != brNONE) return 0;
- BL_SendBuf(D_PTR_I, D_NUM_BYTES);
+ BL_SendBuf(pMem->D_PTR_I, pMem->D_NUM_BYTES);
return (BL_GetACK(40) == brSUCCESS);
}
-static uint8_t BL_ReadA(uint8_t cmd)
+static uint8_t BL_ReadA(uint8_t cmd, ioMem_t *pMem)
{
- if (BL_SendCMDSetAddress()) {
- uint8_t sCMD[] = {cmd, D_NUM_BYTES};
+ if (BL_SendCMDSetAddress(pMem)) {
+ uint8_t sCMD[] = {cmd, pMem->D_NUM_BYTES};
BL_SendBuf(sCMD, 2);
- return (BL_ReadBuf(D_PTR_I, D_NUM_BYTES ));
+ return (BL_ReadBuf(pMem->D_PTR_I, pMem->D_NUM_BYTES ));
}
return 0;
}
-static uint8_t BL_WriteA(uint8_t cmd, uint32_t timeout)
+static uint8_t BL_WriteA(uint8_t cmd, ioMem_t *pMem, uint32_t timeout)
{
- if (BL_SendCMDSetAddress()) {
- if (!BL_SendCMDSetBuffer()) return 0;
+ if (BL_SendCMDSetAddress(pMem)) {
+ if (!BL_SendCMDSetBuffer(pMem)) return 0;
uint8_t sCMD[] = {cmd, 0x01};
BL_SendBuf(sCMD, 2);
return (BL_GetACK(timeout) == brSUCCESS);
@@ -290,24 +298,24 @@ static uint8_t BL_WriteA(uint8_t cmd, uint32_t timeout)
}
-uint8_t BL_ReadFlash(uint8_t interface_mode)
+uint8_t BL_ReadFlash(uint8_t interface_mode, ioMem_t *pMem)
{
if(interface_mode == imATM_BLB) {
- return BL_ReadA(CMD_READ_FLASH_ATM);
+ return BL_ReadA(CMD_READ_FLASH_ATM, pMem);
} else {
- return BL_ReadA(CMD_READ_FLASH_SIL);
+ return BL_ReadA(CMD_READ_FLASH_SIL, pMem);
}
}
-uint8_t BL_ReadEEprom(void)
+uint8_t BL_ReadEEprom(ioMem_t *pMem)
{
- return BL_ReadA(CMD_READ_EEPROM);
+ return BL_ReadA(CMD_READ_EEPROM, pMem);
}
-uint8_t BL_PageErase(void)
+uint8_t BL_PageErase(ioMem_t *pMem)
{
- if (BL_SendCMDSetAddress()) {
+ if (BL_SendCMDSetAddress(pMem)) {
uint8_t sCMD[] = {CMD_ERASE_FLASH, 0x01};
BL_SendBuf(sCMD, 2);
return (BL_GetACK((40 / START_BIT_TIMEOUT_MS)) == brSUCCESS);
@@ -315,14 +323,15 @@ uint8_t BL_PageErase(void)
return 0;
}
-uint8_t BL_WriteEEprom(void)
+uint8_t BL_WriteEEprom(ioMem_t *pMem)
{
- return BL_WriteA(CMD_PROG_EEPROM, (3000 / START_BIT_TIMEOUT_MS));
+ return BL_WriteA(CMD_PROG_EEPROM, pMem, (3000 / START_BIT_TIMEOUT_MS));
}
-uint8_t BL_WriteFlash(void)
+uint8_t BL_WriteFlash(ioMem_t *pMem)
{
- return BL_WriteA(CMD_PROG_FLASH, (40 / START_BIT_TIMEOUT_MS));
+ return BL_WriteA(CMD_PROG_FLASH, pMem, (40 / START_BIT_TIMEOUT_MS));
}
#endif
+#endif
diff --git a/src/main/io/serial_4way_avrootloader.h b/src/main/io/serial_4way_avrootloader.h
index 2f13e1bb7..39cfaaa3d 100644
--- a/src/main/io/serial_4way_avrootloader.h
+++ b/src/main/io/serial_4way_avrootloader.h
@@ -20,15 +20,12 @@
#pragma once
-#if defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER)
-
void BL_SendBootInit(void);
-uint8_t BL_ConnectEx(void);
+uint8_t BL_ConnectEx(uint8_32_u *pDeviceInfo);
uint8_t BL_SendCMDKeepAlive(void);
-uint8_t BL_PageErase(void);
-uint8_t BL_ReadEEprom(void);
-uint8_t BL_WriteEEprom(void);
-uint8_t BL_WriteFlash(void);
-uint8_t BL_ReadFlash(uint8_t interface_mode);
-void BL_SendCMDRunRestartBootloader(void);
-#endif
+uint8_t BL_PageErase(ioMem_t *pMem);
+uint8_t BL_ReadEEprom(ioMem_t *pMem);
+uint8_t BL_WriteEEprom(ioMem_t *pMem);
+uint8_t BL_WriteFlash(ioMem_t *pMem);
+uint8_t BL_ReadFlash(uint8_t interface_mode, ioMem_t *pMem);
+void BL_SendCMDRunRestartBootloader(uint8_32_u *pDeviceInfo);
diff --git a/src/main/io/serial_4way_stk500v2.c b/src/main/io/serial_4way_stk500v2.c
index 2bd0c6f7c..f6e21d580 100644
--- a/src/main/io/serial_4way_stk500v2.c
+++ b/src/main/io/serial_4way_stk500v2.c
@@ -17,16 +17,24 @@
* have a look at https://github.com/sim-/tgy/blob/master/boot.inc
* for info about the stk500v2 implementation
*/
-#include
-#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
#include
#include
#include
#include
+
+#include "platform.h"
+#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
+#include "drivers/gpio.h"
+#include "drivers/buf_writer.h"
+#include "drivers/pwm_mapping.h"
+#include "drivers/serial.h"
+#include "config/config.h"
+#include "io/serial.h"
+#include "io/serial_msp.h"
+#include "io/serial_4way.h"
#include "io/serial_4way_stk500v2.h"
#include "drivers/system.h"
-#include "io/serial_4way.h"
-#include "config/config.h"
+#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
#define BIT_LO_US (32) //32uS
#define BIT_HI_US (2*BIT_LO_US)
@@ -78,18 +86,14 @@ static uint8_t ckSumOut;
static void StkSendByte(uint8_t dat)
{
ckSumOut ^= dat;
- for (uint8_t i = 0; i < 8; i++)
- {
- if (dat & 0x01)
- {
+ for (uint8_t i = 0; i < 8; i++) {
+ if (dat & 0x01) {
// 1-bits are encoded as 64.0us high, 72.8us low (135.8us total).
ESC_SET_HI;
delay_us(BIT_HI_US);
ESC_SET_LO;
delay_us(BIT_HI_US);
- }
- else
- {
+ } else {
// 0-bits are encoded as 27.8us high, 34.5us low, 34.4us high, 37.9 low (134.6us total)
ESC_SET_HI;
delay_us(BIT_LO_US);
@@ -111,7 +115,7 @@ static void StkSendPacketHeader(void)
StkSendByte(0xFF);
StkSendByte(0xFF);
StkSendByte(0x7F);
- ckSumOut=0;
+ ckSumOut = 0;
StkSendByte(MESSAGE_START);
StkSendByte(++SeqNumber);
}
@@ -134,15 +138,15 @@ static int8_t ReadBit(void)
WaitPinLo;
WaitPinHi;
LastBitTime = micros() - btimer;
- if (LastBitTime <= HiLoTsh)
- {
+ if (LastBitTime <= HiLoTsh) {
timeout_timer = timeout_timer + STK_BIT_TIMEOUT;
WaitPinLo;
WaitPinHi;
//lo-bit
return 0;
+ } else {
+ return 1;
}
- else return 1;
timeout:
return -1;
}
@@ -150,8 +154,7 @@ timeout:
static uint8_t ReadByte(uint8_t *bt)
{
*bt = 0;
- for (uint8_t i = 0; i < 8; i++)
- {
+ for (uint8_t i = 0; i < 8; i++) {
int8_t bit = ReadBit();
if (bit == -1) goto timeout;
if (bit == 1) {
@@ -164,8 +167,6 @@ timeout:
return 0;
}
-
-
static uint8_t StkReadLeader(void)
{
@@ -175,32 +176,24 @@ static uint8_t StkReadLeader(void)
// Wait for the first bit
uint32_t waitcycl; //250uS each
- if((StkCmd == CMD_PROGRAM_EEPROM_ISP) || (StkCmd == CMD_CHIP_ERASE_ISP))
- {
+ if((StkCmd == CMD_PROGRAM_EEPROM_ISP) || (StkCmd == CMD_CHIP_ERASE_ISP)) {
waitcycl = STK_WAITCYLCES_EXT;
- }
- else if(StkCmd == CMD_SIGN_ON)
- {
+ } else if(StkCmd == CMD_SIGN_ON) {
waitcycl = STK_WAITCYLCES_START;
- }
- else
- {
+ } else {
waitcycl= STK_WAITCYLCES;
}
- for ( ; waitcycl >0 ; waitcycl--)
- {
+ for ( ; waitcycl >0 ; waitcycl--) {
//check is not timeout
if (ReadBit() >- 1) break;
}
//Skip the first bits
- if (waitcycl == 0)
- {
+ if (waitcycl == 0){
goto timeout;
}
- for (uint8_t i = 0; i < 10; i++)
- {
+ for (uint8_t i = 0; i < 10; i++) {
if (ReadBit() == -1) goto timeout;
}
@@ -209,8 +202,7 @@ static uint8_t StkReadLeader(void)
// Read until we get a 0 bit
int8_t bit;
- do
- {
+ do {
bit = ReadBit();
if (bit == -1) goto timeout;
} while (bit > 0);
@@ -222,7 +214,7 @@ timeout:
static uint8_t StkRcvPacket(uint8_t *pstring)
{
uint8_t bt = 0;
- union uint8_16u Len;
+ uint8_16_u Len;
IRQ_OFF;
if (!StkReadLeader()) goto Err;
@@ -275,11 +267,11 @@ static uint8_t _CMD_SPI_MULTI_EX(volatile uint8_t * ResByte,uint8_t Cmd,uint8_t
return 0;
}
-static uint8_t _CMD_LOAD_ADDRESS(void)
+static uint8_t _CMD_LOAD_ADDRESS(ioMem_t *pMem)
{
// ignore 0xFFFF
// assume address is set before and we read or write the immediately following package
- if((D_FLASH_ADDR_H == 0xFF) && (D_FLASH_ADDR_L == 0xFF)) return 1;
+ if((pMem->D_FLASH_ADDR_H == 0xFF) && (pMem->D_FLASH_ADDR_L == 0xFF)) return 1;
StkCmd = CMD_LOAD_ADDRESS;
StkSendPacketHeader();
StkSendByte(0); // hi byte Msg len
@@ -288,16 +280,16 @@ static uint8_t _CMD_LOAD_ADDRESS(void)
StkSendByte(CMD_LOAD_ADDRESS);
StkSendByte(0);
StkSendByte(0);
- StkSendByte(D_FLASH_ADDR_H);
- StkSendByte(D_FLASH_ADDR_L);
+ StkSendByte(pMem->D_FLASH_ADDR_H);
+ StkSendByte(pMem->D_FLASH_ADDR_L);
StkSendPacketFooter();
return (StkRcvPacket((void *)StkInBuf));
}
-static uint8_t _CMD_READ_MEM_ISP()
+static uint8_t _CMD_READ_MEM_ISP(ioMem_t *pMem)
{
uint8_t LenHi;
- if (D_NUM_BYTES>0) {
+ if (pMem->D_NUM_BYTES>0) {
LenHi=0;
} else {
LenHi=1;
@@ -308,23 +300,23 @@ static uint8_t _CMD_READ_MEM_ISP()
StkSendByte(TOKEN);
StkSendByte(StkCmd);
StkSendByte(LenHi);
- StkSendByte(D_NUM_BYTES);
+ StkSendByte(pMem->D_NUM_BYTES);
StkSendByte(CmdFlashEepromRead);
StkSendPacketFooter();
- return (StkRcvPacket(D_PTR_I));
+ return (StkRcvPacket(pMem->D_PTR_I));
}
-static uint8_t _CMD_PROGRAM_MEM_ISP(void)
+static uint8_t _CMD_PROGRAM_MEM_ISP(ioMem_t *pMem)
{
- union uint8_16u Len;
- uint8_t LenLo=D_NUM_BYTES;
+ uint8_16_u Len;
+ uint8_t LenLo = pMem->D_NUM_BYTES;
uint8_t LenHi;
if (LenLo) {
- LenHi=0;
- Len.word=LenLo+10;
+ LenHi = 0;
+ Len.word = LenLo + 10;
} else {
- LenHi=1;
- Len.word=256+10;
+ LenHi = 1;
+ Len.word = 256 + 10;
}
StkSendPacketHeader();
StkSendByte(Len.bytes[1]); // high byte Msg len
@@ -341,8 +333,8 @@ static uint8_t _CMD_PROGRAM_MEM_ISP(void)
StkSendByte(0); // poll1
StkSendByte(0); // poll2
do {
- StkSendByte(*D_PTR_I);
- D_PTR_I++;
+ StkSendByte(*pMem->D_PTR_I);
+ pMem->D_PTR_I++;
LenLo--;
} while (LenLo);
StkSendPacketFooter();
@@ -361,11 +353,11 @@ uint8_t Stk_SignOn(void)
return (StkRcvPacket((void *) StkInBuf));
}
-uint8_t Stk_ConnectEx(void)
+uint8_t Stk_ConnectEx(uint8_32_u *pDeviceInfo)
{
if (Stk_SignOn()) {
- if (_CMD_SPI_MULTI_EX(&DeviceInfo.bytes[1],signature_r,0,1)) {
- if (_CMD_SPI_MULTI_EX(&DeviceInfo.bytes[0],signature_r,0,2)) {
+ if (_CMD_SPI_MULTI_EX(&pDeviceInfo->bytes[1], signature_r,0,1)) {
+ if (_CMD_SPI_MULTI_EX(&pDeviceInfo->bytes[0], signature_r,0,2)) {
return 1;
}
}
@@ -388,43 +380,44 @@ uint8_t Stk_Chip_Erase(void)
StkSendByte(0x13);
StkSendByte(0x76);
StkSendPacketFooter();
- return (StkRcvPacket((void *)StkInBuf));
+ return (StkRcvPacket(StkInBuf));
}
-uint8_t Stk_ReadFlash(void)
+uint8_t Stk_ReadFlash(ioMem_t *pMem)
{
- if (_CMD_LOAD_ADDRESS()) {
+ if (_CMD_LOAD_ADDRESS(pMem)) {
StkCmd = CMD_READ_FLASH_ISP;
- return (_CMD_READ_MEM_ISP());
+ return (_CMD_READ_MEM_ISP(pMem));
}
return 0;
}
-uint8_t Stk_ReadEEprom(void)
+uint8_t Stk_ReadEEprom(ioMem_t *pMem)
{
- if (_CMD_LOAD_ADDRESS()) {
+ if (_CMD_LOAD_ADDRESS(pMem)) {
StkCmd = CMD_READ_EEPROM_ISP;
- return (_CMD_READ_MEM_ISP());
+ return (_CMD_READ_MEM_ISP(pMem));
}
return 0;
}
-uint8_t Stk_WriteFlash(void)
+uint8_t Stk_WriteFlash(ioMem_t *pMem)
{
- if (_CMD_LOAD_ADDRESS()) {
+ if (_CMD_LOAD_ADDRESS(pMem)) {
StkCmd = CMD_PROGRAM_FLASH_ISP;
- return (_CMD_PROGRAM_MEM_ISP());
+ return (_CMD_PROGRAM_MEM_ISP(pMem));
}
return 0;
}
-uint8_t Stk_WriteEEprom(void)
+uint8_t Stk_WriteEEprom(ioMem_t *pMem)
{
- if (_CMD_LOAD_ADDRESS()) {
+ if (_CMD_LOAD_ADDRESS(pMem)) {
StkCmd = CMD_PROGRAM_EEPROM_ISP;
- return (_CMD_PROGRAM_MEM_ISP());
+ return (_CMD_PROGRAM_MEM_ISP(pMem));
}
return 0;
}
#endif
+#endif
diff --git a/src/main/io/serial_4way_stk500v2.h b/src/main/io/serial_4way_stk500v2.h
index f24b60ae7..80ca89826 100644
--- a/src/main/io/serial_4way_stk500v2.h
+++ b/src/main/io/serial_4way_stk500v2.h
@@ -15,17 +15,13 @@
* along with Cleanflight. If not, see .
* Author: 4712
*/
-#include
-#ifdef USE_SERIAL_4WAY_SK_BOOTLOADER
-
#pragma once
uint8_t Stk_SignOn(void);
-uint8_t Stk_ConnectEx(void);
-uint8_t Stk_ReadEEprom(void);
-uint8_t Stk_WriteEEprom(void);
-uint8_t Stk_ReadFlash(void);
-uint8_t Stk_WriteFlash(void);
+uint8_t Stk_ConnectEx(uint8_32_u *pDeviceInfo);
+uint8_t Stk_ReadEEprom(ioMem_t *pMem);
+uint8_t Stk_WriteEEprom(ioMem_t *pMem);
+uint8_t Stk_ReadFlash(ioMem_t *pMem);
+uint8_t Stk_WriteFlash(ioMem_t *pMem);
uint8_t Stk_Chip_Erase(void);
-#endif
diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c
index 85931b023..65a9a0666 100644
--- a/src/main/io/serial_msp.c
+++ b/src/main/io/serial_msp.c
@@ -92,14 +92,7 @@
#include "serial_msp.h"
-#ifdef USE_SERIAL_1WIRE
-#include "io/serial_1wire.h"
-#endif
-
-#ifdef USE_SERIAL_1WIRE_VCP
-#include "io/serial_1wire_vcp.h"
-#endif
-#if (defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
+#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
#include "io/serial_4way.h"
#endif
@@ -1745,117 +1738,7 @@ static bool processInCommand(void)
isRebootScheduled = true;
break;
-#ifdef USE_SERIAL_1WIRE
- case MSP_SET_1WIRE:
- // get channel number
- i = read8();
- // we do not give any data back, assume channel number is transmitted OK
- if (i == 0xFF) {
- // 0xFF -> preinitialize the Passthrough
- // switch all motor lines HI
- usb1WireInitialize();
- // reply the count of ESC found
- headSerialReply(2);
- serialize8(escCount);
- serialize8(currentPort->port->identifier);
- // and come back right afterwards
- // rem: App: Wait at least appx. 500 ms for BLHeli to jump into
- // bootloader mode before try to connect any ESC
-
- return true;
- } else if (i < escCount) {
- // Check for channel number 0..ESC_COUNT-1
- // because we do not come back after calling usb1WirePassthrough
- // proceed with a success reply first
- headSerialReply(0);
- tailSerialReply();
- // flush the transmit buffer
- bufWriterFlush(writer);
- // wait for all data to send
- waitForSerialPortToFinishTransmitting(currentPort->port);
- // Start to activate here
- // motor 1 => index 0
-
- // search currentPort portIndex
- /* next lines seems to be unnecessary, because the currentPort always point to the same mspPorts[portIndex]
- uint8_t portIndex;
- for (portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
- if (currentPort == &mspPorts[portIndex]) {
- break;
- }
- }
- */
- // *mspReleasePortIfAllocated(mspSerialPort); // CloseSerialPort also marks currentPort as UNUSED_PORT
- usb1WirePassthrough(i);
- // Wait a bit more to let App read the 0 byte and/or switch baudrate
- // 2ms will most likely do the job, but give some grace time
- delay(10);
- // rebuild/refill currentPort structure, does openSerialPort if marked UNUSED_PORT - used ports are skiped
- // *mspAllocateSerialPorts(&masterConfig.serialConfig);
- /* restore currentPort and mspSerialPort
- setCurrentPort(&mspPorts[portIndex]); // not needed same index will be restored
- */
- // former used MSP uart is active again
- // restore MSP_SET_1WIRE as current command for correct headSerialReply(0)
- //currentPort->cmdMSP = MSP_SET_1WIRE;
- } else if (i == 0xFE) {
- usb1WireDeInitialize();
- } else {
- // ESC channel higher than max. allowed
- headSerialError(0);
- }
- // proceed as usual with MSP commands
- // and wait to switch to next channel
- // rem: App needs to call MSP_BOOT to deinitialize Passthrough
- break;
-#endif
-
-#ifdef USE_SERIAL_1WIRE_VCP
- case MSP_SET_1WIRE:
- // get channel number
- i = read8();
- // we do not give any data back, assume channel number is transmitted OK
- if (i == 0xFF) {
- // 0xFF -> preinitialize the Passthrough
- // switch all motor lines HI
- usb1WireInitializeVcp();
- // reply the count of ESC found
- headSerialReply(2);
- serialize8(escCount);
- serialize8(currentPort->port->identifier);
- // and come back right afterwards
- // rem: App: Wait at least appx. 500 ms for BLHeli to jump into
- // bootloader mode before try to connect any ESC
-
- return true;
- } else if (i < escCount) {
- // Check for channel number 0..ESC_COUNT-1
- // because we do not come back after calling usb1WirePassthrough
- // proceed with a success reply first
- headSerialReply(0);
- tailSerialReply();
- // flush the transmit buffer
- bufWriterFlush(writer);
- // wait for all data to send
- waitForSerialPortToFinishTransmitting(currentPort->port);
- // Start to activate here
- // motor 1 => index 0
- usb1WirePassthroughVcp(currentPort, writer, i);
- // Wait a bit more to let App switch baudrate
- delay(10);
- // former used MSP uart is still active
- // proceed as usual with MSP commands
- // and wait to switch to next channel
- // rem: App needs to call MSP_SET_1WIRE(0xFE) to deinitialize Passthrough
- } else if (i == 0xFE) {
- usb1WireDeInitializeVcp();
- } else {
- // ESC channel higher than max. allowed
- headSerialError(0);
- }
- break;
-#endif
-#if (defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
+#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
case MSP_SET_4WAY_IF:
// get channel number
// switch all motor lines HI
diff --git a/src/main/io/serial_msp.h b/src/main/io/serial_msp.h
index c493e37f1..c1041cf61 100644
--- a/src/main/io/serial_msp.h
+++ b/src/main/io/serial_msp.h
@@ -254,7 +254,6 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_SET_ACC_TRIM 239 //in message set acc angle trim values
#define MSP_SERVO_MIX_RULES 241 //out message Returns servo mixer configuration
#define MSP_SET_SERVO_MIX_RULE 242 //in message Sets servo mixer configuration
-#define MSP_SET_1WIRE 243 //in message Sets 1Wire paththrough
#define MSP_SET_4WAY_IF 245 //in message Sets 4way interface
// Each MSP port requires state and a receive buffer, revisit this default if someone needs more than 2 MSP ports.
diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h
index c3639e4d9..caf6e7b88 100644
--- a/src/main/target/CC3D/target.h
+++ b/src/main/target/CC3D/target.h
@@ -124,27 +124,8 @@
#define USE_SERVOS
#define USE_CLI
-#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
-#define USE_SERIAL_4WAY_SK_BOOTLOADER
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
-#ifdef USE_VCP
-#define USE_SERIAL_1WIRE_VCP
-#else
-#define USE_SERIAL_1WIRE
-#endif
-#endif
-
-#ifdef USE_SERIAL_1WIRE
-// FlexPort (pin 21/22, TX/RX respectively):
-// Note, FlexPort has 10k pullups on both TX and RX
-// JST Pin3 TX - connect to external UART/USB RX
-#define S1W_TX_GPIO GPIOB
-#define S1W_TX_PIN GPIO_Pin_10
-// JST Pin4 RX - connect to external UART/USB TX
-#define S1W_RX_GPIO GPIOB
-#define S1W_RX_PIN GPIO_Pin_11
-#endif
#undef DISPLAY
#undef SONAR
diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h
index c618dd14a..4b9f5c634 100755
--- a/src/main/target/COLIBRI_RACE/target.h
+++ b/src/main/target/COLIBRI_RACE/target.h
@@ -181,20 +181,4 @@
#define USE_SERVOS
#define USE_CLI
-#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
-#define USE_SERIAL_4WAY_SK_BOOTLOADER
-
-#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
-#ifdef USE_VCP
-#define USE_SERIAL_1WIRE_VCP
-#else
-#define USE_SERIAL_1WIRE
-#endif
-#endif
-
-#ifdef USE_SERIAL_1WIRE
-#define S1W_TX_GPIO GPIOB
-#define S1W_TX_PIN GPIO_Pin_10
-#define S1W_RX_GPIO GPIOB
-#define S1W_RX_PIN GPIO_Pin_11
-#endif
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h
index 3b19243aa..a3b370df7 100644
--- a/src/main/target/LUX_RACE/target.h
+++ b/src/main/target/LUX_RACE/target.h
@@ -162,21 +162,4 @@
#define BIND_PORT GPIOC
#define BIND_PIN Pin_5
-#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
-#define USE_SERIAL_4WAY_SK_BOOTLOADER
-
-#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
-#ifdef USE_VCP
-#define USE_SERIAL_1WIRE_VCP
-#else
-#define USE_SERIAL_1WIRE
-#endif
-#endif
-
-#ifdef USE_SERIAL_1WIRE
-// Untested
-#define S1W_TX_GPIO GPIOB
-#define S1W_TX_PIN GPIO_Pin_10
-#define S1W_RX_GPIO GPIOB
-#define S1W_RX_PIN GPIO_Pin_11
-#endif
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h
index a7961aa4c..9f168587f 100644
--- a/src/main/target/MOTOLAB/target.h
+++ b/src/main/target/MOTOLAB/target.h
@@ -188,20 +188,4 @@
#define BIND_PORT GPIOB
#define BIND_PIN Pin_4
-#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
-#define USE_SERIAL_4WAY_SK_BOOTLOADER
-
-#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
-#ifdef USE_VCP
-#define USE_SERIAL_1WIRE_VCP
-#else
-#define USE_SERIAL_1WIRE
-#endif
-#endif
-
-#ifdef USE_SERIAL_1WIRE
-#define S1W_TX_GPIO GPIOB
-#define S1W_TX_PIN GPIO_Pin_6
-#define S1W_RX_GPIO GPIOB
-#define S1W_RX_PIN GPIO_Pin_7
-#endif
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h
index 239d03c66..944206a98 100644
--- a/src/main/target/NAZE/target.h
+++ b/src/main/target/NAZE/target.h
@@ -188,25 +188,7 @@
#define BIND_PORT GPIOA
#define BIND_PIN Pin_3
-#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
-#define USE_SERIAL_4WAY_SK_BOOTLOADER
-
-#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
-#ifdef USE_VCP
-#define USE_SERIAL_1WIRE_VCP
-#else
-#define USE_SERIAL_1WIRE
-#endif
-#endif
-
-#ifdef USE_SERIAL_1WIRE
-// STM32F103CBT6-LQFP48 Pin30 (PA9) TX - PC3 connects to onboard CP2102 RX
-#define S1W_TX_GPIO GPIOA
-#define S1W_TX_PIN GPIO_Pin_9
-// STM32F103CBT6-LQFP48 Pin31 (PA10) RX - PC1 to onboard CP2102 TX
-#define S1W_RX_GPIO GPIOA
-#define S1W_RX_PIN GPIO_Pin_10
-#endif
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// alternative defaults for AlienWii32 F1 target
#ifdef ALIENWII32
diff --git a/src/main/target/PORT103R/target.h b/src/main/target/PORT103R/target.h
index 7ed70db57..4f58065da 100644
--- a/src/main/target/PORT103R/target.h
+++ b/src/main/target/PORT103R/target.h
@@ -157,20 +157,4 @@
#define USE_SERVOS
#define USE_CLI
-#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
-#define USE_SERIAL_4WAY_SK_BOOTLOADER
-
-#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
-#ifdef USE_VCP
-#define USE_SERIAL_1WIRE_VCP
-#else
-#define USE_SERIAL_1WIRE
-#endif
-#endif
-
-#ifdef USE_SERIAL_1WIRE
-#define S1W_TX_GPIO GPIOA
-#define S1W_TX_PIN GPIO_Pin_9
-#define S1W_RX_GPIO GPIOA
-#define S1W_RX_PIN GPIO_Pin_10
-#endif
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
diff --git a/src/main/target/RMDO/target.h b/src/main/target/RMDO/target.h
index b17efe35e..b9f201ab1 100644
--- a/src/main/target/RMDO/target.h
+++ b/src/main/target/RMDO/target.h
@@ -154,20 +154,4 @@
#define BIND_PORT GPIOB
#define BIND_PIN Pin_11
-#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
-#define USE_SERIAL_4WAY_SK_BOOTLOADER
-
-#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
-#ifdef USE_VCP
-#define USE_SERIAL_1WIRE_VCP
-#else
-#define USE_SERIAL_1WIRE
-#endif
-#endif
-
-#ifdef USE_SERIAL_1WIRE
-#define S1W_TX_GPIO GPIOA
-#define S1W_TX_PIN GPIO_Pin_9
-#define S1W_RX_GPIO GPIOA
-#define S1W_RX_PIN GPIO_Pin_10
-#endif
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h
index 7f85e4d73..8ff56c86c 100644
--- a/src/main/target/SPARKY/target.h
+++ b/src/main/target/SPARKY/target.h
@@ -163,23 +163,7 @@
#define WS2811_IRQ DMA1_Channel7_IRQn
#endif
-#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
-#define USE_SERIAL_4WAY_SK_BOOTLOADER
-
-#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
-#ifdef USE_VCP
-#define USE_SERIAL_1WIRE_VCP
-#else
-#define USE_SERIAL_1WIRE
-#endif
-#endif
-
-#ifdef USE_SERIAL_1WIRE
-#define S1W_TX_GPIO GPIOB
-#define S1W_TX_PIN GPIO_Pin_6
-#define S1W_RX_GPIO GPIOB
-#define S1W_RX_PIN GPIO_Pin_7
-#endif
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define SPEKTRUM_BIND
// USART2, PA3
diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h
index 29c2d216b..c5a0e5265 100644
--- a/src/main/target/SPRACINGF3/target.h
+++ b/src/main/target/SPRACINGF3/target.h
@@ -163,20 +163,4 @@
#define BIND_PORT GPIOB
#define BIND_PIN Pin_11
-#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
-#define USE_SERIAL_4WAY_SK_BOOTLOADER
-
-#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
-#ifdef USE_VCP
-#define USE_SERIAL_1WIRE_VCP
-#else
-#define USE_SERIAL_1WIRE
-#endif
-#endif
-
-#ifdef USE_SERIAL_1WIRE
-#define S1W_TX_GPIO GPIOA
-#define S1W_TX_PIN GPIO_Pin_9
-#define S1W_RX_GPIO GPIOA
-#define S1W_RX_PIN GPIO_Pin_10
-#endif
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h
index 6e511e3ab..27c094834 100755
--- a/src/main/target/SPRACINGF3EVO/target.h
+++ b/src/main/target/SPRACINGF3EVO/target.h
@@ -222,18 +222,4 @@
#define BIND_PORT GPIOB
#define BIND_PIN Pin_11
-#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
-#define USE_SERIAL_4WAY_SK_BOOTLOADER
-
-#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
-#ifdef USE_VCP
-#define USE_SERIAL_1WIRE_VCP
-#else
-#define USE_SERIAL_1WIRE
-#endif
-#endif
-
-#define S1W_TX_GPIO UART1_GPIO
-#define S1W_TX_PIN UART1_TX_PIN
-#define S1W_RX_GPIO UART1_GPIO
-#define S1W_RX_PIN UART1_RX_PIN
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h
index e9780b134..5459d4f9a 100644
--- a/src/main/target/SPRACINGF3MINI/target.h
+++ b/src/main/target/SPRACINGF3MINI/target.h
@@ -232,20 +232,4 @@
#define BINDPLUG_PORT BUTTON_B_PORT
#define BINDPLUG_PIN BUTTON_B_PIN
-#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
-#define USE_SERIAL_4WAY_SK_BOOTLOADER
-
-#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
-#ifdef USE_VCP
-#define USE_SERIAL_1WIRE_VCP
-#else
-#define USE_SERIAL_1WIRE
-#endif
-#endif
-
-#ifdef USE_SERIAL_1WIRE
-#define S1W_TX_GPIO UART1_GPIO
-#define S1W_TX_PIN UART1_TX_PIN
-#define S1W_RX_GPIO UART1_GPIO
-#define S1W_RX_PIN UART1_RX_PIN
-#endif
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h
index e474ef073..8a812d879 100644
--- a/src/main/target/STM32F3DISCOVERY/target.h
+++ b/src/main/target/STM32F3DISCOVERY/target.h
@@ -162,22 +162,4 @@
#define USE_SERVOS
#define USE_CLI
-#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
-#define USE_SERIAL_4WAY_SK_BOOTLOADER
-
-#if !(defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER))
-#ifdef USE_VCP
-#define USE_SERIAL_1WIRE_VCP
-#else
-#define USE_SERIAL_1WIRE
-#endif
-#endif
-
-#ifdef USE_SERIAL_1WIRE
-// STM32F3DISCOVERY TX - PD5 connects to UART RX
-#define S1W_TX_GPIO GPIOD
-#define S1W_TX_PIN GPIO_Pin_5
-// STM32F3DISCOVERY RX - PD6 connects to UART TX
-#define S1W_RX_GPIO GPIOD
-#define S1W_RX_PIN GPIO_Pin_6
-#endif
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE