mirror of
https://github.com/opentx/opentx.git
synced 2025-07-24 16:55:20 +03:00
TELEMETRY_MOD=14051_SWAPPED
TELEMETRY_MOD=14051 (by gerardv @ forum.turnigy9xr.com) makes USART0 available by reallocating AIL and THR onto pins 14 and 15 of the 14051 multiplexer. TELEMETRY_MOD=14051_SWAPPED is based on TELEMETRY_MOD=14051, but uses USART1 instead of USART0, freeing USART0 for other purposes (debugging, interfacing via AVRISP port). USART1 is freed up by reallocating LVert Trim Dn/Up onto 14051's 12 and 1 pins respectively. Additionally, this commit cleans a few things up: * moves AVR ADC-related code to adc_driver.cpp, * provides #defines to have a convenient way to access either USART0 or USART1 registers depending on static (build-time) configuration * moves code related to this telemetry mod to board_stock * replaces a few magic numbers with enums. Thanks to Bernard Songis for review and suggestions!
This commit is contained in:
parent
41f78440db
commit
485edb579d
11 changed files with 351 additions and 196 deletions
|
@ -415,7 +415,7 @@ ifeq ($(PCB), $(filter $(PCB), STD 9X 9XR))
|
||||||
INCDIRS += targets/stock
|
INCDIRS += targets/stock
|
||||||
CPPDEFS = -DF_CPU=$(F_CPU)UL -DPCBSTD -DCPUM64 -DEEPROM_VARIANT=$(shell echo ${EEPROM_VARIANT} | bc)
|
CPPDEFS = -DF_CPU=$(F_CPU)UL -DPCBSTD -DCPUM64 -DEEPROM_VARIANT=$(shell echo ${EEPROM_VARIANT} | bc)
|
||||||
BOARDSRC = main_avr.cpp targets/stock/board_stock.cpp
|
BOARDSRC = main_avr.cpp targets/stock/board_stock.cpp
|
||||||
EXTRABOARDSRC = targets/common_avr/telemetry_driver.cpp
|
EXTRABOARDSRC = targets/common_avr/adc_driver.cpp targets/common_avr/telemetry_driver.cpp
|
||||||
ifeq ($(GUI), YES)
|
ifeq ($(GUI), YES)
|
||||||
EXTRABOARDSRC += targets/stock/lcd_driver.cpp
|
EXTRABOARDSRC += targets/stock/lcd_driver.cpp
|
||||||
endif
|
endif
|
||||||
|
@ -437,6 +437,10 @@ ifeq ($(PCB), $(filter $(PCB), STD 9X 9XR))
|
||||||
CPPDEFS += -DTELEMETRY_MOD_14051
|
CPPDEFS += -DTELEMETRY_MOD_14051
|
||||||
endif
|
endif
|
||||||
|
|
||||||
|
ifeq ($(TELEMETRY_MOD), 14051_SWAPPED)
|
||||||
|
CPPDEFS += -DTELEMETRY_MOD_14051_SWAPPED
|
||||||
|
endif
|
||||||
|
|
||||||
ifeq ($(AUDIO), YES)
|
ifeq ($(AUDIO), YES)
|
||||||
CPPDEFS += -DAUDIO
|
CPPDEFS += -DAUDIO
|
||||||
CPPSRC += audio_avr.cpp
|
CPPSRC += audio_avr.cpp
|
||||||
|
@ -488,7 +492,7 @@ ifeq ($(PCB), $(filter $(PCB), STD128 9X128 9XR128))
|
||||||
CPPDEFS = -DF_CPU=$(F_CPU)UL -DPCBSTD -DCPUM128 -DEEPROM_VARIANT=$(shell echo ${EEPROM_VARIANT} | bc)
|
CPPDEFS = -DF_CPU=$(F_CPU)UL -DPCBSTD -DCPUM128 -DEEPROM_VARIANT=$(shell echo ${EEPROM_VARIANT} | bc)
|
||||||
INCDIRS += targets/stock
|
INCDIRS += targets/stock
|
||||||
BOARDSRC = main_avr.cpp targets/stock/board_stock.cpp
|
BOARDSRC = main_avr.cpp targets/stock/board_stock.cpp
|
||||||
EXTRABOARDSRC = targets/stock/lcd_driver.cpp targets/common_avr/telemetry_driver.cpp
|
EXTRABOARDSRC = targets/common_avr/adc_driver.cpp targets/stock/lcd_driver.cpp targets/common_avr/telemetry_driver.cpp
|
||||||
EEPROMSRC = eeprom_common.cpp eeprom_rlc.cpp
|
EEPROMSRC = eeprom_common.cpp eeprom_rlc.cpp
|
||||||
PULSESSRC = pulses/pulses_avr.cpp
|
PULSESSRC = pulses/pulses_avr.cpp
|
||||||
CPPSRC += debug.cpp
|
CPPSRC += debug.cpp
|
||||||
|
@ -507,6 +511,10 @@ ifeq ($(PCB), $(filter $(PCB), STD128 9X128 9XR128))
|
||||||
CPPDEFS += -DTELEMETRY_MOD_14051
|
CPPDEFS += -DTELEMETRY_MOD_14051
|
||||||
endif
|
endif
|
||||||
|
|
||||||
|
ifeq ($(TELEMETRY_MOD), 14051_SWAPPED)
|
||||||
|
CPPDEFS += -DTELEMETRY_MOD_14051_SWAPPED
|
||||||
|
endif
|
||||||
|
|
||||||
ifeq ($(AUDIO), YES)
|
ifeq ($(AUDIO), YES)
|
||||||
CPPDEFS += -DAUDIO
|
CPPDEFS += -DAUDIO
|
||||||
CPPSRC += audio_avr.cpp
|
CPPSRC += audio_avr.cpp
|
||||||
|
@ -554,7 +562,7 @@ ifeq ($(PCB), $(filter $(PCB), 9X2561))
|
||||||
CPPDEFS = -DF_CPU=$(F_CPU)UL -DPCBSTD -DCPUM2561 -DEEPROM_VARIANT=$(shell echo ${EEPROM_VARIANT} | bc)
|
CPPDEFS = -DF_CPU=$(F_CPU)UL -DPCBSTD -DCPUM2561 -DEEPROM_VARIANT=$(shell echo ${EEPROM_VARIANT} | bc)
|
||||||
INCDIRS += targets/stock
|
INCDIRS += targets/stock
|
||||||
BOARDSRC = main_avr.cpp targets/stock/board_stock.cpp
|
BOARDSRC = main_avr.cpp targets/stock/board_stock.cpp
|
||||||
EXTRABOARDSRC = targets/stock/lcd_driver.cpp targets/common_avr/telemetry_driver.cpp
|
EXTRABOARDSRC = targets/common_avr/adc_driver.cpp targets/stock/lcd_driver.cpp targets/common_avr/telemetry_driver.cpp
|
||||||
EEPROMSRC = eeprom_common.cpp eeprom_rlc.cpp
|
EEPROMSRC = eeprom_common.cpp eeprom_rlc.cpp
|
||||||
PULSESSRC = pulses/pulses_avr.cpp
|
PULSESSRC = pulses/pulses_avr.cpp
|
||||||
CPPSRC += debug.cpp
|
CPPSRC += debug.cpp
|
||||||
|
@ -622,7 +630,7 @@ ifeq ($(PCB), GRUVIN9X)
|
||||||
THR_TRACE = YES
|
THR_TRACE = YES
|
||||||
INCDIRS += targets/gruvin9x targets/stock $(FATFSDIR) $(FATFSDIR)/option
|
INCDIRS += targets/gruvin9x targets/stock $(FATFSDIR) $(FATFSDIR)/option
|
||||||
BOARDSRC = main_avr.cpp targets/gruvin9x/board_gruvin9x.cpp
|
BOARDSRC = main_avr.cpp targets/gruvin9x/board_gruvin9x.cpp
|
||||||
EXTRABOARDSRC = targets/stock/lcd_driver.cpp targets/common_avr/telemetry_driver.cpp
|
EXTRABOARDSRC = targets/common_avr/adc_driver.cpp targets/stock/lcd_driver.cpp targets/common_avr/telemetry_driver.cpp
|
||||||
EEPROMSRC = eeprom_common.cpp eeprom_rlc.cpp
|
EEPROMSRC = eeprom_common.cpp eeprom_rlc.cpp
|
||||||
PULSESSRC = pulses/pulses_avr.cpp
|
PULSESSRC = pulses/pulses_avr.cpp
|
||||||
CPPSRC += audio_avr.cpp haptic.cpp debug.cpp
|
CPPSRC += audio_avr.cpp haptic.cpp debug.cpp
|
||||||
|
@ -680,7 +688,7 @@ ifeq ($(PCB), MEGA2560)
|
||||||
ifeq ($(LCD), ST7565R)
|
ifeq ($(LCD), ST7565R)
|
||||||
CPPDEFS += -DLCD_ST7565R
|
CPPDEFS += -DLCD_ST7565R
|
||||||
endif
|
endif
|
||||||
EXTRABOARDSRC = targets/stock/lcd_driver.cpp targets/common_avr/telemetry_driver.cpp
|
EXTRABOARDSRC = targets/common_avr/adc_driver.cpp targets/stock/lcd_driver.cpp targets/common_avr/telemetry_driver.cpp
|
||||||
|
|
||||||
ifeq ($(SDCARD), YES)
|
ifeq ($(SDCARD), YES)
|
||||||
EXTRABOARDSRC += $(FATFSDIR)/ff.c $(FATFSDIR)/fattime.c $(FATFSDIR)/option/ccsbcs.c targets/gruvin9x/diskio.cpp
|
EXTRABOARDSRC += $(FATFSDIR)/ff.c $(FATFSDIR)/fattime.c $(FATFSDIR)/option/ccsbcs.c targets/gruvin9x/diskio.cpp
|
||||||
|
|
|
@ -1301,7 +1301,7 @@ uint8_t checkTrim(uint8_t event)
|
||||||
}
|
}
|
||||||
|
|
||||||
#if !defined(SIMU)
|
#if !defined(SIMU)
|
||||||
static uint16_t s_anaFilt[NUMBER_ANALOG];
|
uint16_t s_anaFilt[NUMBER_ANALOG];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(SIMU)
|
#if defined(SIMU)
|
||||||
|
@ -1328,8 +1328,12 @@ uint16_t anaIn(uint8_t chan)
|
||||||
}
|
}
|
||||||
volatile uint16_t *p = &s_anaFilt[pgm_read_byte(crossAna+chan)];
|
volatile uint16_t *p = &s_anaFilt[pgm_read_byte(crossAna+chan)];
|
||||||
return *p;
|
return *p;
|
||||||
|
#else
|
||||||
|
#if defined(TELEMETRY_MOD_14051) || defined(TELEMETRY_MOD_14051_SWAPPED)
|
||||||
|
static const pm_char crossAna[] PROGMEM = {3,1,2,0,4,5,6,0/* shouldn't be used */,TX_VOLTAGE};
|
||||||
#else
|
#else
|
||||||
static const pm_char crossAna[] PROGMEM = {3,1,2,0,4,5,6,7};
|
static const pm_char crossAna[] PROGMEM = {3,1,2,0,4,5,6,7};
|
||||||
|
#endif
|
||||||
#if defined(FRSKY_STICKS)
|
#if defined(FRSKY_STICKS)
|
||||||
volatile uint16_t temp = s_anaFilt[pgm_read_byte(crossAna+chan)]; // volatile saves here 40 bytes; maybe removed for newer AVR when available
|
volatile uint16_t temp = s_anaFilt[pgm_read_byte(crossAna+chan)]; // volatile saves here 40 bytes; maybe removed for newer AVR when available
|
||||||
if (chan < NUM_STICKS && (g_eeGeneral.stickReverse & (1 << chan))) {
|
if (chan < NUM_STICKS && (g_eeGeneral.stickReverse & (1 << chan))) {
|
||||||
|
@ -1378,132 +1382,6 @@ void getADC()
|
||||||
s_anaFilt[x] = v;
|
s_anaFilt[x] = v;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#else
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Read ADC using 10 bits
|
|
||||||
*/
|
|
||||||
inline uint16_t read_adc10(uint8_t adc_input)
|
|
||||||
{
|
|
||||||
uint16_t temp_ana;
|
|
||||||
ADMUX = adc_input|ADC_VREF_TYPE;
|
|
||||||
#if defined(TELEMETRY_MOD_14051)
|
|
||||||
ADCSRA &= 0x87;
|
|
||||||
#endif
|
|
||||||
ADCSRA |= 1 << ADSC; // Start the AD conversion
|
|
||||||
while (ADCSRA & (1 << ADSC)); // Wait for the AD conversion to complete
|
|
||||||
temp_ana = ADC;
|
|
||||||
ADCSRA |= 1 << ADSC; // Start the second AD conversion
|
|
||||||
while (ADCSRA & (1 << ADSC)); // Wait for the AD conversion to complete
|
|
||||||
temp_ana += ADC;
|
|
||||||
return temp_ana;
|
|
||||||
}
|
|
||||||
|
|
||||||
#if defined(TELEMETRY_MOD_14051)
|
|
||||||
enum MuxInput {
|
|
||||||
MUX_BATT,
|
|
||||||
MUX_THR,
|
|
||||||
MUX_AIL,
|
|
||||||
MUX_MAX = MUX_AIL
|
|
||||||
};
|
|
||||||
|
|
||||||
uint8_t pf7_digital[2];
|
|
||||||
/**
|
|
||||||
* Update ADC PF7 using 14051 multiplexer
|
|
||||||
* X0 : Battery voltage
|
|
||||||
* X1 : THR SW
|
|
||||||
* X2 : AIL SW
|
|
||||||
*/
|
|
||||||
void readMultiplexAna()
|
|
||||||
{
|
|
||||||
static uint8_t muxNum = MUX_BATT;
|
|
||||||
uint16_t temp_ana;
|
|
||||||
uint8_t nextMuxNum = muxNum-1;
|
|
||||||
|
|
||||||
DDRC |= 0xC1;
|
|
||||||
temp_ana = read_adc10(7);
|
|
||||||
|
|
||||||
switch (muxNum) {
|
|
||||||
case MUX_BATT:
|
|
||||||
s_anaFilt[TX_VOLTAGE] = temp_ana;
|
|
||||||
nextMuxNum = MUX_MAX;
|
|
||||||
break;
|
|
||||||
case MUX_THR:
|
|
||||||
case MUX_AIL:
|
|
||||||
// Digital switch depend from input voltage
|
|
||||||
// take half voltage to determine digital state
|
|
||||||
pf7_digital[muxNum-1] = (temp_ana >= (s_anaFilt[TX_VOLTAGE] / 2)) ? 1 : 0;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
// set the mux number for the next ADC convert,
|
|
||||||
// stabilize voltage before ADC read.
|
|
||||||
muxNum = nextMuxNum;
|
|
||||||
PORTC &= ~((1 << PC7) | (1 << PC6) | (1 << PC0)); // Clear CTRL ABC
|
|
||||||
switch (muxNum) {
|
|
||||||
case 1:
|
|
||||||
PORTC |= (1 << PC6); // Mux CTRL A : SW_THR
|
|
||||||
break;
|
|
||||||
case 2:
|
|
||||||
PORTC |= (1 << PC7); // Mux CTRL B : SW_AIL
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
void getADC()
|
|
||||||
{
|
|
||||||
#if defined(TELEMETRY_MOD_14051)
|
|
||||||
readMultiplexAna();
|
|
||||||
#define ADC_READ_COUNT 7
|
|
||||||
#else
|
|
||||||
#define ADC_READ_COUNT 8
|
|
||||||
#endif
|
|
||||||
|
|
||||||
for (uint8_t adc_input=0; adc_input<ADC_READ_COUNT; adc_input++) {
|
|
||||||
s_anaFilt[adc_input] = read_adc10(adc_input);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if !defined(CPUARM)
|
|
||||||
void getADC_bandgap()
|
|
||||||
{
|
|
||||||
#if defined(PCBGRUVIN9X)
|
|
||||||
static uint8_t s_bgCheck = 0;
|
|
||||||
static uint16_t s_bgSum = 0;
|
|
||||||
ADCSRA|=0x40; // request sample
|
|
||||||
s_bgCheck += 32;
|
|
||||||
while ((ADCSRA & 0x10)==0); ADCSRA|=0x10; // wait for sample
|
|
||||||
if (s_bgCheck == 0) { // 8x over-sample (256/32=8)
|
|
||||||
BandGap = s_bgSum+ADC;
|
|
||||||
s_bgSum = 0;
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
s_bgSum += ADC;
|
|
||||||
}
|
|
||||||
ADCSRB |= (1<<MUX5);
|
|
||||||
#elif defined(PCBMEGA2560)
|
|
||||||
BandGap = 2000;
|
|
||||||
#else
|
|
||||||
// TODO is the next line needed (because it has been called before perMain)?
|
|
||||||
ADMUX = 0x1E|ADC_VREF_TYPE; // Switch MUX to internal 1.22V reference
|
|
||||||
|
|
||||||
/*
|
|
||||||
MCUCR|=0x28; // enable Sleep (bit5) enable ADC Noise Reduction (bit2)
|
|
||||||
asm volatile(" sleep \n\t"); // if _SLEEP() is not defined use this
|
|
||||||
// ADCSRA|=0x40;
|
|
||||||
while ((ADCSRA & 0x10)==0);
|
|
||||||
ADCSRA|=0x10; // take sample clear flag?
|
|
||||||
BandGap=ADC;
|
|
||||||
MCUCR&=0x08; // disable sleep
|
|
||||||
*/
|
|
||||||
|
|
||||||
ADCSRA |= 0x40;
|
|
||||||
while (ADCSRA & 0x40);
|
|
||||||
BandGap = ADC;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // SIMU
|
#endif // SIMU
|
||||||
|
@ -1619,12 +1497,10 @@ void doMixerCalculations()
|
||||||
Current_analogue = (Current_analogue*31 + s_anaFilt[8] ) >> 5 ;
|
Current_analogue = (Current_analogue*31 + s_anaFilt[8] ) >> 5 ;
|
||||||
if (Current_analogue > Current_max)
|
if (Current_analogue > Current_max)
|
||||||
Current_max = Current_analogue ;
|
Current_max = Current_analogue ;
|
||||||
#elif defined(PCBGRUVIN9X) && !defined(SIMU)
|
#endif
|
||||||
// For PCB V4, use our own 1.2V, external reference (connected to ADC3)
|
|
||||||
ADCSRB &= ~(1<<MUX5);
|
#if !defined(CPUARM)
|
||||||
ADMUX = 0x03|ADC_VREF_TYPE; // Switch MUX to internal reference
|
adcPrepareBandgap();
|
||||||
#elif defined(PCBSTD) && !defined(SIMU)
|
|
||||||
ADMUX = 0x1E|ADC_VREF_TYPE; // Switch MUX to internal reference
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
evalMixes(tick10ms);
|
evalMixes(tick10ms);
|
||||||
|
@ -2176,14 +2052,14 @@ ISR(TIMER3_CAPT_vect) // G: High frequency noise can cause stack overflo with IS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(DSM2_SERIAL) && !defined(CPUARM)
|
#if defined(DSM2_SERIAL) && !defined(CPUARM)
|
||||||
FORCEINLINE void DSM2_USART0_vect()
|
FORCEINLINE void DSM2_USART_vect()
|
||||||
{
|
{
|
||||||
UDR0 = *((uint16_t*)pulses2MHzRPtr); // transmit next byte
|
UDR0 = *((uint16_t*)pulses2MHzRPtr); // transmit next byte
|
||||||
|
|
||||||
pulses2MHzRPtr += sizeof(uint16_t);
|
pulses2MHzRPtr += sizeof(uint16_t);
|
||||||
|
|
||||||
if (pulses2MHzRPtr == pulses2MHzWPtr) { // if reached end of DSM2 data buffer ...
|
if (pulses2MHzRPtr == pulses2MHzWPtr) { // if reached end of DSM2 data buffer ...
|
||||||
UCSR0B &= ~(1 << UDRIE0); // disable UDRE0 interrupt
|
UCSRB_N(TLM_USART) &= ~(1 << UDRIE_N(TLM_USART)); // disable UDRE interrupt
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -2192,30 +2068,30 @@ FORCEINLINE void DSM2_USART0_vect()
|
||||||
|
|
||||||
#if defined (FRSKY)
|
#if defined (FRSKY)
|
||||||
|
|
||||||
// USART0 Transmit Data Register Emtpy ISR
|
FORCEINLINE void FRSKY_USART_vect()
|
||||||
FORCEINLINE void FRSKY_USART0_vect()
|
|
||||||
{
|
{
|
||||||
if (frskyTxBufferCount > 0) {
|
if (frskyTxBufferCount > 0) {
|
||||||
UDR0 = frskyTxBuffer[--frskyTxBufferCount];
|
UDR_N(TLM_USART) = frskyTxBuffer[--frskyTxBufferCount];
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
UCSR0B &= ~(1 << UDRIE0); // disable UDRE0 interrupt
|
UCSRB_N(TLM_USART) &= ~(1 << UDRIE_N(TLM_USART)); // disable UDRE interrupt
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
ISR(USART0_UDRE_vect)
|
// USART0/1 Transmit Data Register Emtpy ISR
|
||||||
|
ISR(USART_UDRE_vect_N(TLM_USART))
|
||||||
{
|
{
|
||||||
#if defined(FRSKY) && defined(DSM2_SERIAL)
|
#if defined(FRSKY) && defined(DSM2_SERIAL)
|
||||||
if (IS_DSM2_PROTOCOL(g_model.protocol)) { // TODO not s_current_protocol?
|
if (IS_DSM2_PROTOCOL(g_model.protocol)) { // TODO not s_current_protocol?
|
||||||
DSM2_USART0_vect();
|
DSM2_USART_vect();
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
FRSKY_USART0_vect();
|
FRSKY_USART_vect();
|
||||||
}
|
}
|
||||||
#elif defined(FRSKY)
|
#elif defined(FRSKY)
|
||||||
FRSKY_USART0_vect();
|
FRSKY_USART_vect();
|
||||||
#else
|
#else
|
||||||
DSM2_USART0_vect();
|
DSM2_USART_vect();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -941,8 +941,6 @@ void checkSwitches();
|
||||||
void checkAlarm();
|
void checkAlarm();
|
||||||
void checkAll();
|
void checkAll();
|
||||||
|
|
||||||
#define ADC_VREF_TYPE 0x40 // AVCC with external capacitor at AREF pin
|
|
||||||
|
|
||||||
#if !defined(SIMU)
|
#if !defined(SIMU)
|
||||||
void getADC();
|
void getADC();
|
||||||
#endif
|
#endif
|
||||||
|
@ -979,6 +977,15 @@ enum Analogs {
|
||||||
POT2,
|
POT2,
|
||||||
POT3,
|
POT3,
|
||||||
POT_LAST = POT3,
|
POT_LAST = POT3,
|
||||||
|
#endif
|
||||||
|
#if defined(TELEMETRY_MOD_14051) || defined(TELEMETRY_MOD_14051_SWAPPED)
|
||||||
|
// When the mod is applied, ADC7 is connected to 14051's X pin and TX_VOLTAGE
|
||||||
|
// is connected to 14051's X0 pin (one of the multiplexed inputs). TX_VOLTAGE
|
||||||
|
// value is filled in by processMultiplexAna().
|
||||||
|
|
||||||
|
// This shifts TX_VOLTAGE from 7 to 8 and makes X14051 take the 7th position
|
||||||
|
// corresponding to ADC7.
|
||||||
|
X14051,
|
||||||
#endif
|
#endif
|
||||||
TX_VOLTAGE,
|
TX_VOLTAGE,
|
||||||
#if defined(PCBSKY9X) && !defined(REVA)
|
#if defined(PCBSKY9X) && !defined(REVA)
|
||||||
|
@ -1727,4 +1734,8 @@ struct Clipboard {
|
||||||
extern Clipboard clipboard;
|
extern Clipboard clipboard;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if !defined(SIMU)
|
||||||
|
extern uint16_t s_anaFilt[NUMBER_ANALOG];
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -604,7 +604,7 @@ void checkSwitches()
|
||||||
#if !defined(MODULE_ALWAYS_SEND_PULSES)
|
#if !defined(MODULE_ALWAYS_SEND_PULSES)
|
||||||
while (1) {
|
while (1) {
|
||||||
|
|
||||||
#if defined(TELEMETRY_MOD_14051) || defined(PCBTARANIS)
|
#if defined(TELEMETRY_MOD_14051) || defined(TELEMETRY_MOD_14051_SWAPPED) || defined(PCBTARANIS)
|
||||||
getADC();
|
getADC();
|
||||||
#endif
|
#endif
|
||||||
#endif // !defined(MODULE_ALWAYS_SEND_PULSES)
|
#endif // !defined(MODULE_ALWAYS_SEND_PULSES)
|
||||||
|
|
114
radio/src/targets/common_avr/adc_driver.cpp
Normal file
114
radio/src/targets/common_avr/adc_driver.cpp
Normal file
|
@ -0,0 +1,114 @@
|
||||||
|
/*
|
||||||
|
* Authors (alphabetical order)
|
||||||
|
* - Andre Bernet <bernet.andre@gmail.com>
|
||||||
|
* - Andreas Weitl
|
||||||
|
* - Bertrand Songis <bsongis@gmail.com>
|
||||||
|
* - Bryan J. Rentoul (Gruvin) <gruvin@gmail.com>
|
||||||
|
* - Cameron Weeks <th9xer@gmail.com>
|
||||||
|
* - Erez Raviv
|
||||||
|
* - Gabriel Birkus
|
||||||
|
* - Jean-Pierre Parisy
|
||||||
|
* - Karl Szmutny
|
||||||
|
* - Michael Blandford
|
||||||
|
* - Michal Hlavinka
|
||||||
|
* - Pat Mackenzie
|
||||||
|
* - Philip Moss
|
||||||
|
* - Rob Thomson
|
||||||
|
* - Romolo Manfredini <romolo.manfredini@gmail.com>
|
||||||
|
* - Thomas Husterer
|
||||||
|
*
|
||||||
|
* opentx is based on code named
|
||||||
|
* gruvin9x by Bryan J. Rentoul: http://code.google.com/p/gruvin9x/,
|
||||||
|
* er9x by Erez Raviv: http://code.google.com/p/er9x/,
|
||||||
|
* and the original (and ongoing) project by
|
||||||
|
* Thomas Husterer, th9x: http://code.google.com/p/th9x/
|
||||||
|
*
|
||||||
|
* This program is free software; you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License version 2 as
|
||||||
|
* published by the Free Software Foundation.
|
||||||
|
*
|
||||||
|
* This program 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.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "../../opentx.h"
|
||||||
|
|
||||||
|
#define ADC_VREF_TYPE (1 << REFS0) // AVCC with external capacitor at AREF pin
|
||||||
|
|
||||||
|
void adcInit()
|
||||||
|
{
|
||||||
|
ADMUX = ADC_VREF_TYPE;
|
||||||
|
ADCSRA = 0x85; // ADC enabled, pre-scaler division=32 (no interrupt, no auto-triggering)
|
||||||
|
#if defined(CPUM2560)
|
||||||
|
ADCSRB = (1 << MUX5);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void adcPrepareBandgap()
|
||||||
|
{
|
||||||
|
#if defined(CPUM2560)
|
||||||
|
// For PCB V4, use our own 1.2V, external reference (connected to ADC3)
|
||||||
|
ADCSRB &= ~(1<<MUX5);
|
||||||
|
ADMUX = 0x03|ADC_VREF_TYPE; // Switch MUX to internal reference
|
||||||
|
#else
|
||||||
|
ADMUX = 0x1E|ADC_VREF_TYPE; // Switch MUX to internal reference
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void getADC()
|
||||||
|
{
|
||||||
|
for (uint8_t adc_input=0; adc_input<8; adc_input++) {
|
||||||
|
uint16_t temp_ana;
|
||||||
|
ADMUX = adc_input|ADC_VREF_TYPE;
|
||||||
|
ADCSRA |= 1 << ADSC; // Start the AD conversion
|
||||||
|
while (ADCSRA & (1 << ADSC)); // Wait for the AD conversion to complete
|
||||||
|
temp_ana = ADC;
|
||||||
|
ADCSRA |= 1 << ADSC; // Start the second AD conversion
|
||||||
|
while (ADCSRA & (1 << ADSC)); // Wait for the AD conversion to complete
|
||||||
|
temp_ana += ADC;
|
||||||
|
s_anaFilt[adc_input] = temp_ana;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if defined(TELEMETRY_MOD_14051) || defined(TELEMETRY_MOD_14051_SWAPPED)
|
||||||
|
processMultiplexAna();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void getADC_bandgap()
|
||||||
|
{
|
||||||
|
#if defined(PCBGRUVIN9X)
|
||||||
|
static uint8_t s_bgCheck = 0;
|
||||||
|
static uint16_t s_bgSum = 0;
|
||||||
|
ADCSRA |= (1 << ADSC); // request sample
|
||||||
|
s_bgCheck += 32;
|
||||||
|
while ((ADCSRA & (1 << ADIF))==0); // wait for sample
|
||||||
|
ADCSRA |= (1 << ADIF);
|
||||||
|
if (s_bgCheck == 0) { // 8x over-sample (256/32=8)
|
||||||
|
BandGap = s_bgSum+ADC;
|
||||||
|
s_bgSum = 0;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
s_bgSum += ADC;
|
||||||
|
}
|
||||||
|
ADCSRB |= (1 << MUX5);
|
||||||
|
#elif defined(PCBMEGA2560)
|
||||||
|
BandGap = 2000;
|
||||||
|
#else
|
||||||
|
/*
|
||||||
|
MCUCR|=0x28; // enable Sleep (bit5) enable ADC Noise Reduction (bit2)
|
||||||
|
asm volatile(" sleep \n\t"); // if _SLEEP() is not defined use this
|
||||||
|
// ADCSRA|=0x40;
|
||||||
|
while ((ADCSRA & 0x10)==0);
|
||||||
|
ADCSRA|=0x10; // take sample clear flag?
|
||||||
|
BandGap=ADC;
|
||||||
|
MCUCR&=0x08; // disable sleep
|
||||||
|
*/
|
||||||
|
|
||||||
|
ADCSRA |= (1 << ADSC);
|
||||||
|
while (ADCSRA & (1 << ADSC));
|
||||||
|
BandGap = ADC;
|
||||||
|
#endif
|
||||||
|
}
|
|
@ -34,6 +34,79 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
// ADC driver
|
||||||
|
void adcInit();
|
||||||
|
void adcPrepareBandgap();
|
||||||
|
void getADC();
|
||||||
|
void getADC_bandgap();
|
||||||
|
|
||||||
|
// USART driver (static register dispatcher)
|
||||||
|
#define RXD_DDR1 DDRD
|
||||||
|
#define RXD_DDR_PIN1 DDD2
|
||||||
|
#define RXD_PORT1 PORTD
|
||||||
|
#define RXD_PORT_PIN1 PORTD2
|
||||||
|
#define RXD_DDR0 DDRE
|
||||||
|
#define RXD_DDR_PIN0 DDE0
|
||||||
|
#define RXD_PORT0 PORTE
|
||||||
|
#define RXD_PORT_PIN0 PORTE0
|
||||||
|
|
||||||
|
#define _DOR_N(usart_no) DOR ## usart_no
|
||||||
|
#define _FE_N(usart_no) FE ## usart_no
|
||||||
|
#define _RXCIE_N(usart_no) RXCIE ## usart_no
|
||||||
|
#define _RXC_N(usart_no) RXC ## usart_no
|
||||||
|
#define _RXD_DDR_N(usart_no) RXD_DDR ## usart_no
|
||||||
|
#define _RXD_DDR_PIN_N(usart_no) RXD_DDR ## usart_no
|
||||||
|
#define _RXD_PORT_N(usart_no) RXD_DDR ## usart_no
|
||||||
|
#define _RXD_PORT_PIN_N(usart_no) RXD_DDR ## usart_no
|
||||||
|
#define _RXEN_N(usart_no) RXEN ## usart_no
|
||||||
|
#define _TXCIE_N(usart_no) TXCIE ## usart_no
|
||||||
|
#define _TXEN_N(usart_no) TXEN ## usart_no
|
||||||
|
#define _U2X_N(usart_no) U2X ## usart_no
|
||||||
|
#define _UBRRH_N(usart_no) UBRR ## usart_no ## H
|
||||||
|
#define _UBRRL_N(usart_no) UBRR ## usart_no ## L
|
||||||
|
#define _UCSRA_N(usart_no) UCSR ## usart_no ## A
|
||||||
|
#define _UCSRB_N(usart_no) UCSR ## usart_no ## B
|
||||||
|
#define _UCSRC_N(usart_no) UCSR ## usart_no ## C
|
||||||
|
#define _UCSZ0_N(usart_no) UCSZ ## usart_no ## 0
|
||||||
|
#define _UCSZ1_N(usart_no) UCSZ ## usart_no ## 1
|
||||||
|
#define _UCSZ2_N(usart_no) UCSZ ## usart_no ## 2
|
||||||
|
#define _UDRIE_N(usart_no) UDRIE ## usart_no
|
||||||
|
#define _UDR_N(usart_no) UDR ## usart_no
|
||||||
|
#define _UPE_N(usart_no) UPE ## usart_no
|
||||||
|
#define _USART_RX_vect_N(usart_no) USART ## usart_no ## _RX_vect
|
||||||
|
#define _USART_UDRE_vect_N(usart_no) USART ## usart_no ## _UDRE_vect
|
||||||
|
|
||||||
|
#define DOR_N(usart_no) _DOR_N(usart_no)
|
||||||
|
#define FE_N(usart_no) _FE_N(usart_no)
|
||||||
|
#define RXCIE_N(usart_no) _RXCIE_N(usart_no)
|
||||||
|
#define RXC_N(usart_no) _RXC_N(usart_no)
|
||||||
|
#define RXD_DDR_N(usart_no) _RXD_DDR_N(usart_no)
|
||||||
|
#define RXD_DDR_PIN_N(usart_no) _RXD_DDR_PIN_N(usart_no)
|
||||||
|
#define RXD_PORT_N(usart_no) _RXD_PORT_N(usart_no)
|
||||||
|
#define RXD_PORT_PIN_N(usart_no) _RXD_PORT_PIN_N(usart_no)
|
||||||
|
#define RXEN_N(usart_no) _RXEN_N(usart_no)
|
||||||
|
#define TXCIE_N(usart_no) _TXCIE_N(usart_no)
|
||||||
|
#define TXEN_N(usart_no) _TXEN_N(usart_no)
|
||||||
|
#define U2X_N(usart_no) _U2X_N(usart_no)
|
||||||
|
#define UBRRH_N(usart_no) _UBRRH_N(usart_no)
|
||||||
|
#define UBRRL_N(usart_no) _UBRRL_N(usart_no)
|
||||||
|
#define UCSRA_N(usart_no) _UCSRA_N(usart_no)
|
||||||
|
#define UCSRB_N(usart_no) _UCSRB_N(usart_no)
|
||||||
|
#define UCSRC_N(usart_no) _UCSRC_N(usart_no)
|
||||||
|
#define UCSZ0_N(usart_no) _UCSZ0_N(usart_no)
|
||||||
|
#define UCSZ1_N(usart_no) _UCSZ1_N(usart_no)
|
||||||
|
#define UCSZ2_N(usart_no) _UCSZ2_N(usart_no)
|
||||||
|
#define UDRIE_N(usart_no) _UDRIE_N(usart_no)
|
||||||
|
#define UDR_N(usart_no) _UDR_N(usart_no)
|
||||||
|
#define UPE_N(usart_no) _UPE_N(usart_no)
|
||||||
|
#define USART_RX_vect_N(usart_no) _USART_RX_vect_N(usart_no)
|
||||||
|
#define USART_UDRE_vect_N(usart_no) _USART_UDRE_vect_N(usart_no)
|
||||||
|
|
||||||
// Telemetry driver
|
// Telemetry driver
|
||||||
|
#if defined(TELEMETRY_MOD_14051_SWAPPED)
|
||||||
|
#define TLM_USART 1
|
||||||
|
#else
|
||||||
|
#define TLM_USART 0
|
||||||
|
#endif
|
||||||
void telemetryPortInit();
|
void telemetryPortInit();
|
||||||
void telemetryTransmitBuffer();
|
void telemetryTransmitBuffer();
|
||||||
|
|
|
@ -40,27 +40,27 @@
|
||||||
|
|
||||||
void telemetryEnableTx(void)
|
void telemetryEnableTx(void)
|
||||||
{
|
{
|
||||||
UCSR0B |= (1 << TXEN0); // enable TX
|
UCSRB_N(TLM_USART) |= (1 << TXEN_N(TLM_USART)); // enable TX
|
||||||
}
|
}
|
||||||
|
|
||||||
void telemetryEnableRx(void)
|
void telemetryEnableRx(void)
|
||||||
{
|
{
|
||||||
UCSR0B |= (1 << RXEN0); // enable RX
|
UCSRB_N(TLM_USART) |= (1 << RXEN_N(TLM_USART)); // enable RX
|
||||||
UCSR0B |= (1 << RXCIE0); // enable Interrupt
|
UCSRB_N(TLM_USART) |= (1 << RXCIE_N(TLM_USART)); // enable Interrupt
|
||||||
}
|
}
|
||||||
|
|
||||||
void processSerialData(uint8_t data);
|
void processSerialData(uint8_t data);
|
||||||
extern uint8_t frskyRxBufferCount; // TODO not driver, change name
|
extern uint8_t frskyRxBufferCount; // TODO not driver, change name
|
||||||
|
|
||||||
ISR(USART0_RX_vect)
|
ISR(USART_RX_vect_N(TLM_USART))
|
||||||
{
|
{
|
||||||
uint8_t stat;
|
uint8_t stat;
|
||||||
uint8_t data;
|
uint8_t data;
|
||||||
|
|
||||||
UCSR0B &= ~(1 << RXCIE0); // disable Interrupt
|
UCSRB_N(TLM_USART) &= ~(1 << RXCIE_N(TLM_USART)); // disable Interrupt
|
||||||
sei();
|
sei();
|
||||||
|
|
||||||
stat = UCSR0A; // USART control and Status Register 0 A
|
stat = UCSRA_N(TLM_USART); // USART control and Status Register 0/1 A
|
||||||
|
|
||||||
/*
|
/*
|
||||||
bit 7 6 5 4 3 2 1 0
|
bit 7 6 5 4 3 2 1 0
|
||||||
|
@ -75,7 +75,7 @@ ISR(USART0_RX_vect)
|
||||||
U2X0: Double Tx Speed
|
U2X0: Double Tx Speed
|
||||||
PCM0: MultiProcessor Comms Mode
|
PCM0: MultiProcessor Comms Mode
|
||||||
*/
|
*/
|
||||||
// rh = UCSR0B; //USART control and Status Register 0 B
|
// rh = UCSRB_N(TLM_USART); //USART control and Status Register 0/1 B
|
||||||
|
|
||||||
/*
|
/*
|
||||||
bit 7 6 5 4 3 2 1 0
|
bit 7 6 5 4 3 2 1 0
|
||||||
|
@ -91,9 +91,9 @@ ISR(USART0_RX_vect)
|
||||||
TXB80: Tx data bit 8
|
TXB80: Tx data bit 8
|
||||||
*/
|
*/
|
||||||
|
|
||||||
data = UDR0; // USART data register 0
|
data = UDR_N(TLM_USART); // USART data register 0
|
||||||
|
|
||||||
if (stat & ((1 << FE0) | (1 << DOR0) | (1 << UPE0))) {
|
if (stat & ((1 << FE_N(TLM_USART)) | (1 << DOR_N(TLM_USART)) | (1 << UPE_N(TLM_USART)))) {
|
||||||
// discard buffer and start fresh on any comms error
|
// discard buffer and start fresh on any comms error
|
||||||
frskyRxBufferCount = 0;
|
frskyRxBufferCount = 0;
|
||||||
}
|
}
|
||||||
|
@ -102,29 +102,29 @@ ISR(USART0_RX_vect)
|
||||||
}
|
}
|
||||||
|
|
||||||
cli() ;
|
cli() ;
|
||||||
UCSR0B |= (1 << RXCIE0); // enable Interrupt
|
UCSRB_N(TLM_USART) |= (1 << RXCIE_N(TLM_USART)); // enable Interrupt
|
||||||
}
|
}
|
||||||
|
|
||||||
void telemetryPortInit()
|
void telemetryPortInit()
|
||||||
{
|
{
|
||||||
#if !defined(SIMU)
|
#if !defined(SIMU)
|
||||||
DDRE &= ~(1 << DDE0); // set RXD0 pin as input
|
RXD_DDR_N(TLM_USART) &= ~(1 << RXD_DDR_PIN_N(TLM_USART)); // set RXD pin as input
|
||||||
PORTE &= ~(1 << PORTE0); // disable pullup on RXD0 pin
|
RXD_PORT_N(TLM_USART) &= ~(1 << RXD_PORT_PIN_N(TLM_USART)); // disable pullup on RXD pin
|
||||||
|
|
||||||
#undef BAUD
|
#undef BAUD
|
||||||
#define BAUD 9600
|
#define BAUD 9600
|
||||||
#include <util/setbaud.h>
|
#include <util/setbaud.h>
|
||||||
|
|
||||||
UBRR0H = UBRRH_VALUE;
|
UBRRH_N(TLM_USART) = UBRRH_VALUE;
|
||||||
UBRR0L = UBRRL_VALUE;
|
UBRRL_N(TLM_USART) = UBRRL_VALUE;
|
||||||
UCSR0A &= ~(1 << U2X0); // disable double speed operation.
|
UCSRA_N(TLM_USART) &= ~(1 << U2X_N(TLM_USART)); // disable double speed operation.
|
||||||
|
|
||||||
// set 8N1
|
// set 8N1
|
||||||
UCSR0B = 0 | (0 << RXCIE0) | (0 << TXCIE0) | (0 << UDRIE0) | (0 << RXEN0) | (0 << TXEN0) | (0 << UCSZ02);
|
UCSRB_N(TLM_USART) = 0 | (0 << RXCIE_N(TLM_USART)) | (0 << TXCIE_N(TLM_USART)) | (0 << UDRIE_N(TLM_USART)) | (0 << RXEN_N(TLM_USART)) | (0 << TXEN_N(TLM_USART)) | (0 << UCSZ2_N(TLM_USART));
|
||||||
UCSR0C = 0 | (1 << UCSZ01) | (1 << UCSZ00);
|
UCSRC_N(TLM_USART) = 0 | (1 << UCSZ1_N(TLM_USART)) | (1 << UCSZ0_N(TLM_USART));
|
||||||
|
|
||||||
|
|
||||||
while (UCSR0A & (1 << RXC0)) UDR0; // flush receive buffer
|
while (UCSRA_N(TLM_USART) & (1 << RXC_N(TLM_USART))) UDR_N(TLM_USART); // flush receive buffer
|
||||||
|
|
||||||
// These should be running right from power up on a FrSky enabled '9X.
|
// These should be running right from power up on a FrSky enabled '9X.
|
||||||
telemetryEnableTx(); // enable FrSky-Telemetry emission
|
telemetryEnableTx(); // enable FrSky-Telemetry emission
|
||||||
|
@ -136,7 +136,7 @@ void telemetryPortInit()
|
||||||
|
|
||||||
void telemetryTransmitBuffer()
|
void telemetryTransmitBuffer()
|
||||||
{
|
{
|
||||||
UCSR0B |= (1 << UDRIE0); // enable UDRE0 interrupt
|
UCSRB_N(TLM_USART) |= (1 << UDRIE_N(TLM_USART)); // enable UDRE1 interrupt
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -65,9 +65,7 @@ inline void boardInit()
|
||||||
DDRL = 0x80; PORTL = 0xff; // 7: Hold_PWR_On (1=On, default Off), 6:Jack_Presence_TTL, 5-0: User Button inputs
|
DDRL = 0x80; PORTL = 0xff; // 7: Hold_PWR_On (1=On, default Off), 6:Jack_Presence_TTL, 5-0: User Button inputs
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
ADMUX=ADC_VREF_TYPE;
|
adcInit();
|
||||||
ADCSRA=0x85; // ADC enabled, pre-scaler division=32 (no interrupt, no auto-triggering)
|
|
||||||
ADCSRB=(1<<MUX5);
|
|
||||||
|
|
||||||
/**** Set up timer/counter 0 ****/
|
/**** Set up timer/counter 0 ****/
|
||||||
/** Move old 64A Timer0 functions to Timer2 and use WGM on OC0(A) (PB7) for spkear tone output **/
|
/** Move old 64A Timer0 functions to Timer2 and use WGM on OC0(A) (PB7) for spkear tone output **/
|
||||||
|
|
|
@ -53,9 +53,7 @@ inline void boardInit()
|
||||||
DDRK = 0b00000000; PORTK = 0b00000000; // Analogic input (no pull-ups)
|
DDRK = 0b00000000; PORTK = 0b00000000; // Analogic input (no pull-ups)
|
||||||
DDRL = 0b00000000; PORTL = 0b11111111; // 7:TRN_SW 6:EleDR_SW, 5:ESC, 4:MENU 3:Keyb_Left, 2:Keyb_Right, 1:Keyb_Up, 0:Keyb_Down
|
DDRL = 0b00000000; PORTL = 0b11111111; // 7:TRN_SW 6:EleDR_SW, 5:ESC, 4:MENU 3:Keyb_Left, 2:Keyb_Right, 1:Keyb_Up, 0:Keyb_Down
|
||||||
|
|
||||||
ADMUX=ADC_VREF_TYPE;
|
adcInit();
|
||||||
ADCSRA=0x85; // ADC enabled, pre-scaler division=32 (no interrupt, no auto-triggering)
|
|
||||||
ADCSRB=(1<<MUX5);
|
|
||||||
|
|
||||||
/**** Set up timer/counter 0 ****/
|
/**** Set up timer/counter 0 ****/
|
||||||
// TCNT0 10ms = 16MHz/1024/156(.25) periodic timer (100ms interval)
|
// TCNT0 10ms = 16MHz/1024/156(.25) periodic timer (100ms interval)
|
||||||
|
|
|
@ -99,14 +99,17 @@ inline void boardInit()
|
||||||
// Set up I/O port data directions and initial states
|
// Set up I/O port data directions and initial states
|
||||||
DDRA = 0xff; PORTA = 0x00; // LCD data
|
DDRA = 0xff; PORTA = 0x00; // LCD data
|
||||||
DDRB = 0x81; PORTB = 0x7e; //pullups keys+nc
|
DDRB = 0x81; PORTB = 0x7e; //pullups keys+nc
|
||||||
|
#if defined(TELEMETRY_MOD_14051) || defined(TELEMETRY_MOD_14051_SWAPPED)
|
||||||
|
DDRC = 0xff; PORTC = 0x00;
|
||||||
|
#else
|
||||||
DDRC = 0x3e; PORTC = 0xc1; //pullups nc
|
DDRC = 0x3e; PORTC = 0xc1; //pullups nc
|
||||||
|
#endif
|
||||||
DDRD = 0x00; PORTD = 0xff; //pullups keys
|
DDRD = 0x00; PORTD = 0xff; //pullups keys
|
||||||
DDRE = (1<<OUT_E_BUZZER); PORTE = 0xff-(1<<OUT_E_BUZZER); //pullups + buzzer 0
|
DDRE = (1<<OUT_E_BUZZER); PORTE = 0xff-(1<<OUT_E_BUZZER); //pullups + buzzer 0
|
||||||
DDRF = 0x00; PORTF = 0x00; //anain
|
DDRF = 0x00; PORTF = 0x00; //anain
|
||||||
DDRG = 0x14; PORTG = 0xfb; //pullups + SIM_CTL=1 = phonejack = ppm_in, Haptic output and off (0)
|
DDRG = 0x14; PORTG = 0xfb; //pullups + SIM_CTL=1 = phonejack = ppm_in, Haptic output and off (0)
|
||||||
|
|
||||||
ADMUX = ADC_VREF_TYPE;
|
adcInit();
|
||||||
ADCSRA = 0x85; // ADC enabled, pre-scaler division=32 (no interrupt, no auto-triggering)
|
|
||||||
|
|
||||||
#if defined(CPUM2561)
|
#if defined(CPUM2561)
|
||||||
TCCR2B = (0b111 << CS20); // Norm mode, clk/1024 (differs from ATmega64 chip)
|
TCCR2B = (0b111 << CS20); // Norm mode, clk/1024 (differs from ATmega64 chip)
|
||||||
|
@ -161,10 +164,49 @@ uint8_t keyDown()
|
||||||
return ((~PINB) & 0x7E) | ROTENC_DOWN();
|
return ((~PINB) & 0x7E) | ROTENC_DOWN();
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(TELEMETRY_MOD_14051)
|
#if defined(TELEMETRY_MOD_14051) || defined(TELEMETRY_MOD_14051_SWAPPED)
|
||||||
extern uint8_t pf7_digital[2];
|
uint8_t pf7_digital[MUX_PF7_DIGITAL_MAX - MUX_PF7_DIGITAL_MIN + 1];
|
||||||
#define THR_STATE() pf7_digital[0]
|
/**
|
||||||
#define AIL_STATE() pf7_digital[1]
|
* Update ADC PF7 using 14051 multiplexer
|
||||||
|
* X0 : Battery voltage
|
||||||
|
* X1 : AIL SW
|
||||||
|
* X2 : THR SW
|
||||||
|
* X3 : TRIM LEFT VERTICAL UP
|
||||||
|
* X4 : TRIM LEFT VERTICAL DOWN
|
||||||
|
*/
|
||||||
|
void processMultiplexAna()
|
||||||
|
{
|
||||||
|
static uint8_t muxNum = MUX_BATT;
|
||||||
|
uint8_t nextMuxNum = muxNum-1;
|
||||||
|
|
||||||
|
switch (muxNum) {
|
||||||
|
case MUX_BATT:
|
||||||
|
s_anaFilt[TX_VOLTAGE] = s_anaFilt[X14051];
|
||||||
|
nextMuxNum = MUX_MAX;
|
||||||
|
break;
|
||||||
|
case MUX_AIL:
|
||||||
|
case MUX_THR:
|
||||||
|
case MUX_TRM_LV_UP:
|
||||||
|
case MUX_TRM_LV_DWN:
|
||||||
|
// Digital switch depend from input voltage
|
||||||
|
// take half voltage to determine digital state
|
||||||
|
pf7_digital[muxNum - MUX_PF7_DIGITAL_MIN] = (s_anaFilt[X14051] >= (s_anaFilt[TX_VOLTAGE] / 2)) ? 1 : 0;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
// set the mux number for the next ADC convert,
|
||||||
|
// stabilize voltage before ADC read.
|
||||||
|
muxNum = nextMuxNum;
|
||||||
|
PORTC &= ~((1 << PC7) | (1 << PC6) | (1 << PC0));
|
||||||
|
if(muxNum & 1) PORTC |= (1 << PC7); // Mux CTRL A
|
||||||
|
if(muxNum & 2) PORTC |= (1 << PC6); // Mux CTRL B
|
||||||
|
if(muxNum & 4) PORTC |= (1 << PC0); // Mux CTRL C
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(TELEMETRY_MOD_14051) || defined(TELEMETRY_MOD_14051_SWAPPED)
|
||||||
|
#define THR_STATE() pf7_digital[PF7_THR]
|
||||||
|
#define AIL_STATE() pf7_digital[PF7_AIL]
|
||||||
#elif defined(JETI) || defined(FRSKY) || defined(ARDUPILOT) || defined(NMEA) || defined(MAVLINK)
|
#elif defined(JETI) || defined(FRSKY) || defined(ARDUPILOT) || defined(NMEA) || defined(MAVLINK)
|
||||||
#define THR_STATE() (PINC & (1<<INP_C_ThrCt))
|
#define THR_STATE() (PINC & (1<<INP_C_ThrCt))
|
||||||
#define AIL_STATE() (PINC & (1<<INP_C_AileDR))
|
#define AIL_STATE() (PINC & (1<<INP_C_AileDR))
|
||||||
|
@ -228,21 +270,29 @@ bool switchState(EnumKeys enuk)
|
||||||
}
|
}
|
||||||
|
|
||||||
// Trim switches ...
|
// Trim switches ...
|
||||||
static const pm_uchar crossTrim[] PROGMEM ={
|
uint8_t trimHelper(uint8_t neg_pind, uint8_t idx)
|
||||||
1<<INP_D_TRM_LH_DWN, // bit 7
|
{
|
||||||
1<<INP_D_TRM_LH_UP,
|
switch(idx){
|
||||||
1<<INP_D_TRM_LV_DWN,
|
case 0: return neg_pind & (1<<INP_D_TRM_LH_DWN);
|
||||||
1<<INP_D_TRM_LV_UP,
|
case 1: return neg_pind & (1<<INP_D_TRM_LH_UP);
|
||||||
1<<INP_D_TRM_RV_DWN,
|
#if defined(TELEMETRY_MOD_14051_SWAPPED)
|
||||||
1<<INP_D_TRM_RV_UP,
|
case 2: return !pf7_digital[PF7_TRM_LV_DWN];
|
||||||
1<<INP_D_TRM_RH_DWN,
|
case 3: return !pf7_digital[PF7_TRM_LV_UP];
|
||||||
1<<INP_D_TRM_RH_UP // bit 0
|
#else
|
||||||
};
|
case 2: return neg_pind & (1<<INP_D_TRM_LV_DWN);
|
||||||
|
case 3: return neg_pind & (1<<INP_D_TRM_LV_UP);
|
||||||
|
#endif
|
||||||
|
case 4: return neg_pind & (1<<INP_D_TRM_RV_DWN);
|
||||||
|
case 5: return neg_pind & (1<<INP_D_TRM_RV_UP);
|
||||||
|
case 6: return neg_pind & (1<<INP_D_TRM_RH_DWN);
|
||||||
|
case 7: return neg_pind & (1<<INP_D_TRM_RH_UP);
|
||||||
|
default: return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
uint8_t trimDown(uint8_t idx)
|
uint8_t trimDown(uint8_t idx)
|
||||||
{
|
{
|
||||||
uint8_t in = ~PIND;
|
return trimHelper(~PIND, idx);
|
||||||
return (in & pgm_read_byte(crossTrim+idx));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
FORCEINLINE void readKeysAndTrims()
|
FORCEINLINE void readKeysAndTrims()
|
||||||
|
@ -261,7 +311,7 @@ FORCEINLINE void readKeysAndTrims()
|
||||||
in = ~PIND;
|
in = ~PIND;
|
||||||
for (int i=0; i<8; i++) {
|
for (int i=0; i<8; i++) {
|
||||||
// INP_D_TRM_RH_UP 0 .. INP_D_TRM_LH_UP 7
|
// INP_D_TRM_RH_UP 0 .. INP_D_TRM_LH_UP 7
|
||||||
keys[enuk].input(in & pgm_read_byte(crossTrim+i));
|
keys[enuk].input(trimHelper(in, i));
|
||||||
++enuk;
|
++enuk;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -210,7 +210,34 @@ void backlightFade();
|
||||||
#define INP_G_RuddDR 0
|
#define INP_G_RuddDR 0
|
||||||
|
|
||||||
// Keys driver
|
// Keys driver
|
||||||
|
#if defined(TELEMETRY_MOD_14051) || defined(TELEMETRY_MOD_14051_SWAPPED)
|
||||||
|
enum MuxInput {
|
||||||
|
MUX_BATT,
|
||||||
|
MUX_AIL,
|
||||||
|
MUX_PF7_DIGITAL_MIN = MUX_AIL,
|
||||||
|
MUX_THR,
|
||||||
|
MUX_TRM_LV_UP,
|
||||||
|
MUX_TRM_LV_DWN,
|
||||||
|
MUX_PF7_DIGITAL_MAX = MUX_TRM_LV_DWN,
|
||||||
|
MUX_MAX = MUX_PF7_DIGITAL_MAX
|
||||||
|
};
|
||||||
|
|
||||||
|
enum Pf7Digital {
|
||||||
|
PF7_AIL = MUX_AIL - MUX_PF7_DIGITAL_MIN,
|
||||||
|
PF7_THR = MUX_THR - MUX_PF7_DIGITAL_MIN,
|
||||||
|
PF7_TRM_LV_UP = MUX_TRM_LV_UP - MUX_PF7_DIGITAL_MIN,
|
||||||
|
PF7_TRM_LV_DWN = MUX_TRM_LV_DWN - MUX_PF7_DIGITAL_MIN,
|
||||||
|
};
|
||||||
|
|
||||||
|
extern uint8_t pf7_digital[MUX_PF7_DIGITAL_MAX - MUX_PF7_DIGITAL_MIN + 1];
|
||||||
|
void processMultiplexAna();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(TELEMETRY_MOD_14051_SWAPPED)
|
||||||
|
#define TRIMS_PRESSED() (~PIND & ~0x0c || pf7_digital[PF7_TRM_LV_UP] || pf7_digital[PF7_TRM_LV_DWN])
|
||||||
|
#else
|
||||||
#define TRIMS_PRESSED() (~PIND)
|
#define TRIMS_PRESSED() (~PIND)
|
||||||
|
#endif
|
||||||
#define KEYS_PRESSED() (~PINB)
|
#define KEYS_PRESSED() (~PINB)
|
||||||
#define DBLKEYS_PRESSED_RGT_LFT(i) ((in & ((1<<INP_B_KEY_RGT) + (1<<INP_B_KEY_LFT))) == ((1<<INP_B_KEY_RGT) + (1<<INP_B_KEY_LFT)))
|
#define DBLKEYS_PRESSED_RGT_LFT(i) ((in & ((1<<INP_B_KEY_RGT) + (1<<INP_B_KEY_LFT))) == ((1<<INP_B_KEY_RGT) + (1<<INP_B_KEY_LFT)))
|
||||||
#define DBLKEYS_PRESSED_UP_DWN(i) ((in & ((1<<INP_B_KEY_UP) + (1<<INP_B_KEY_DWN))) == ((1<<INP_B_KEY_UP) + (1<<INP_B_KEY_DWN)))
|
#define DBLKEYS_PRESSED_UP_DWN(i) ((in & ((1<<INP_B_KEY_UP) + (1<<INP_B_KEY_DWN))) == ((1<<INP_B_KEY_UP) + (1<<INP_B_KEY_DWN)))
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue