2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
17 * Ported from https://github.com/4712/BLHeliSuite/blob/master/Interfaces/Arduino1Wire/Source/Arduino1Wire_C/Arduino1Wire.c
18 * by Nathan Tsoi <nathan@vertile.com>
19 * Several updates by 4712 in order to optimize interaction with BLHeliSuite
28 #ifdef USE_SERIAL_1WIRE
29 #include "drivers/gpio.h"
30 #include "drivers/light_led.h"
31 #include "drivers/system.h"
32 #include "io/serial_1wire.h"
33 #include "io/beeper.h"
34 #include "drivers/pwm_mapping.h"
35 #include "flight/mixer.h"
37 uint8_t escCount
; // we detect the hardware dynamically
39 static escHardware_t escHardware
[MAX_PWM_MOTORS
];
41 static void gpio_set_mode(GPIO_TypeDef
* gpio
, uint16_t pin
, GPIO_Mode mode
) {
45 cfg
.speed
= Speed_10MHz
;
49 static uint32_t GetPinPos(uint32_t pin
) {
51 for (pinPos
= 0; pinPos
< 16; pinPos
++) {
52 uint32_t pinMask
= (0x1 << pinPos
);
61 void usb1WireInitialize()
64 memset(&escHardware
,0,sizeof(escHardware
));
65 pwmOutputConfiguration_t
*pwmOutputConfiguration
= pwmGetOutputConfiguration();
66 for (volatile uint8_t i
= 0; i
< pwmOutputConfiguration
->outputCount
; i
++) {
67 if ((pwmOutputConfiguration
->portConfigurations
[i
].flags
& PWM_PF_MOTOR
) == PWM_PF_MOTOR
) {
68 if(motor
[pwmOutputConfiguration
->portConfigurations
[i
].index
] > 0) {
69 escHardware
[escCount
].gpio
= pwmOutputConfiguration
->portConfigurations
[i
].timerHardware
->gpio
;
70 escHardware
[escCount
].pin
= pwmOutputConfiguration
->portConfigurations
[i
].timerHardware
->pin
;
71 escHardware
[escCount
].pinpos
= GetPinPos(escHardware
[escCount
].pin
);
72 gpio_set_mode(escHardware
[escCount
].gpio
,escHardware
[escCount
].pin
, Mode_IPU
); //GPIO_Mode_IPU
80 static volatile uint32_t in_cr_mask
, out_cr_mask
;
82 static __IO
uint32_t *cr
;
83 static void gpio_prep_vars(uint32_t escIndex
)
85 GPIO_TypeDef
*gpio
= escHardware
[escIndex
].gpio
;
86 uint32_t pinpos
= escHardware
[escIndex
].pinpos
;
87 // mask out extra bits from pinmode, leaving just CNF+MODE
88 uint32_t inmode
= Mode_IPU
& 0x0F;
89 uint32_t outmode
= (Mode_Out_PP
& 0x0F) | Speed_10MHz
;
90 // reference CRL or CRH, depending whether pin number is 0..7 or 8..15
91 cr
= &gpio
->CRL
+ (pinpos
/ 8);
92 // offset to CNF and MODE portions of CRx register
93 uint32_t shift
= (pinpos
% 8) * 4;
94 // Read out current CRx value
95 in_cr_mask
= out_cr_mask
= *cr
;
97 in_cr_mask
&= ~(0xF << shift
);
98 out_cr_mask
&= ~(0xF << shift
);
99 // save current pinmode
100 in_cr_mask
|= inmode
<< shift
;
101 out_cr_mask
|= outmode
<< shift
;
104 static void gpioSetOne(uint32_t escIndex
, GPIO_Mode mode
) {
105 // reference CRL or CRH, depending whether pin number is 0..7 or 8..15
106 if (mode
== Mode_IPU
) {
108 escHardware
[escIndex
].gpio
->ODR
|= escHardware
[escIndex
].pin
;
116 #define ESC_HI(escIndex) ((escHardware[escIndex].gpio->IDR & escHardware[escIndex].pin) != (uint32_t)Bit_RESET)
117 #define RX_HI ((S1W_RX_GPIO->IDR & S1W_RX_PIN) != (uint32_t)Bit_RESET)
118 #define ESC_SET_HI(escIndex) escHardware[escIndex].gpio->BSRR = escHardware[escIndex].pin
119 #define ESC_SET_LO(escIndex) escHardware[escIndex].gpio->BRR = escHardware[escIndex].pin
120 #define TX_SET_HIGH S1W_TX_GPIO->BSRR = S1W_TX_PIN
121 #define TX_SET_LO S1W_TX_GPIO->BRR = S1W_TX_PIN
124 #define ESC_INPUT(escIndex) escHardware[escIndex].gpio->MODER &= ~(GPIO_MODER_MODER0 << (escHardware[escIndex].pinpos * 2))
125 #define ESC_OUTPUT(escIndex) escHardware[escIndex].gpio->MODER |= GPIO_Mode_OUT << (escHardware[escIndex].pinpos * 2)
129 #define ESC_INPUT(escIndex) gpioSetOne(escIndex, Mode_IPU)
130 #define ESC_OUTPUT(escIndex) gpioSetOne(escIndex, Mode_Out_PP)
133 #define RX_LED_OFF LED0_OFF
134 #define RX_LED_ON LED0_ON
135 #define TX_LED_OFF LED1_OFF
136 #define TX_LED_ON LED1_ON
138 // This method translates 2 wires (a tx and rx line) to 1 wire, by letting the
139 // RX line control when data should be read or written from the single line
140 void usb1WirePassthrough(uint8_t escIndex
)
143 // fix for buzzer often starts beeping continuously when the ESCs are read
144 // switch beeper silent here
148 // disable all interrupts
151 // prepare MSP UART port for direct pin access
152 // reset all the pins
153 GPIO_ResetBits(S1W_RX_GPIO
, S1W_RX_PIN
);
154 GPIO_ResetBits(S1W_TX_GPIO
, S1W_TX_PIN
);
156 gpio_set_mode(S1W_RX_GPIO
, S1W_RX_PIN
, Mode_IPU
);
157 gpio_set_mode(S1W_TX_GPIO
, S1W_TX_PIN
, Mode_Out_PP
);
160 // reset our gpio register pointers and bitmask values
161 gpio_prep_vars(escIndex
);
164 ESC_OUTPUT(escIndex
);
165 ESC_SET_HI(escIndex
);
167 // Wait for programmer to go from 1 -> 0 indicating incoming data
171 // A new iteration on this loop starts when we have data from the programmer (read_programmer goes low)
172 // Setup escIndex pin to send data, pullup is the default
173 ESC_OUTPUT(escIndex
);
174 // Write the first bit
175 ESC_SET_LO(escIndex
);
176 // Echo on the programmer tx line
181 // Wait for programmer to go 0 -> 1
184 if (ct
> 0) ct
--; // count down until 0;
185 // check for low time ->ct=3333 ~600uS //byte LO time for 0 @ 19200 baud -> 9*52 uS => 468.75uS
186 // App must send a 0 at 9600 baud (or lower) which has a LO time of at 104uS (or more) > 0 = 937.5uS LO
187 // BLHeliSuite will use 4800 baud
189 // Programmer is high, end of bit
190 // At first Echo to the esc, which helps to charge input capacities at ESC
191 ESC_SET_HI(escIndex
);
192 // Listen to the escIndex, input mode, pullup resistor is on
193 gpio_set_mode(escHardware
[escIndex
].gpio
, escHardware
[escIndex
].pin
, Mode_IPU
);
195 if (ct
==0) break; //we reached zero
196 // Listen to the escIndex while there is no data from the programmer
198 if (ESC_HI(escIndex
)) {
209 // we get here in case ct reached zero
212 // Enable all irq (for Hardware UART)