1
0
Fork 0
mirror of https://github.com/opentx/opentx.git synced 2025-07-23 16:25:16 +03:00

Flash on Beep doesn't beep on Keys / Trims

TH% not inverted when throttle stick inverted
Rotary Encoders as Mixer Sources on v4 board
Pulses on ersky9x board port
Telemetry on ersky9x board port
This commit is contained in:
bsongis 2012-04-02 17:31:40 +00:00
parent b31b040903
commit 01d05d7d96
28 changed files with 1301 additions and 371 deletions

View file

@ -161,7 +161,7 @@ FORMAT = ihex
TARGET = open9x TARGET = open9x
# List C++ source files here. (C dependencies are automatically generated.) # List C++ source files here. (C dependencies are automatically generated.)
CPPSRC = open9x.cpp pulses.cpp stamp.cpp menus.cpp model_menus.cpp general_menus.cpp main_views.cpp statistics_views.cpp $(EEPROMSRC) lcd.cpp drivers.cpp o9xstrings.cpp CPPSRC = open9x.cpp $(PULSESSRC) stamp.cpp menus.cpp model_menus.cpp general_menus.cpp main_views.cpp statistics_views.cpp $(EEPROMSRC) lcd.cpp drivers.cpp o9xstrings.cpp
ifeq ($(EXT), JETI) ifeq ($(EXT), JETI)
CPPSRC += jeti.cpp CPPSRC += jeti.cpp
@ -268,6 +268,7 @@ ifeq ($(PCB), ARM)
BOARDSRC = board_ersky9x.cpp BOARDSRC = board_ersky9x.cpp
EXTRABOARDSRC = ersky9x/core_cm3.c ersky9x/board_lowlevel.c ersky9x/crt.c ersky9x/vectors_sam3s.c EXTRABOARDSRC = ersky9x/core_cm3.c ersky9x/board_lowlevel.c ersky9x/crt.c ersky9x/vectors_sam3s.c
EEPROMSRC = eeprom_arm.cpp EEPROMSRC = eeprom_arm.cpp
PULSESSRC = pulses_arm.cpp
CPPSRC += ersky9x/sound.cpp CPPSRC += ersky9x/sound.cpp
CPPSRC += beeper.cpp CPPSRC += beeper.cpp
endif endif
@ -279,6 +280,7 @@ ifeq ($(PCB), V4)
EXTRAINCDIRS += gruvin9x EXTRAINCDIRS += gruvin9x
BOARDSRC += board_gruvin9x.cpp BOARDSRC += board_gruvin9x.cpp
EEPROMSRC = eeprom_avr.cpp EEPROMSRC = eeprom_avr.cpp
PULSESSRC = pulses_avr.cpp
CPPSRC += audio.cpp CPPSRC += audio.cpp
CPPSRC += gruvin9x/gtime.cpp CPPSRC += gruvin9x/gtime.cpp
CPPSRC += gruvin9x/rtc.cpp CPPSRC += gruvin9x/rtc.cpp
@ -308,6 +310,7 @@ ifeq ($(PCB), STD)
CPPDEFS += -DPCBSTD CPPDEFS += -DPCBSTD
BOARDSRC = board_stock.cpp BOARDSRC = board_stock.cpp
EEPROMSRC = eeprom_avr.cpp EEPROMSRC = eeprom_avr.cpp
PULSESSRC = pulses_avr.cpp
ifeq ($(AUDIO), YES) ifeq ($(AUDIO), YES)
CPPDEFS += -DAUDIO CPPDEFS += -DAUDIO

View file

@ -155,11 +155,11 @@ void audioQueue::playASAP(uint8_t tFreq, uint8_t tLen, uint8_t tPause,
void audioQueue::event(uint8_t e, uint8_t f) void audioQueue::event(uint8_t e, uint8_t f)
{ {
s_beeper = (g_eeGeneral.beeperMode>0 || (g_eeGeneral.beeperMode==0 && e>AU_MENUS) || (g_eeGeneral.beeperMode>=-1 && e<=AU_ERROR)); s_beeper = (g_eeGeneral.beeperMode>0 || (g_eeGeneral.beeperMode==0 && e>=AU_WARNING1) || (g_eeGeneral.beeperMode>=-1 && e<=AU_ERROR));
#if defined(HAPTIC) #if defined(HAPTIC)
s_haptic = (g_eeGeneral.hapticMode>0 || (g_eeGeneral.hapticMode==0 && e>AU_MENUS) || (g_eeGeneral.hapticMode>=-1 && e<=AU_ERROR)); s_haptic = (g_eeGeneral.hapticMode>0 || (g_eeGeneral.hapticMode==0 && e>=AU_WARNING1) || (g_eeGeneral.hapticMode>=-1 && e<=AU_ERROR));
#endif #endif
if(g_eeGeneral.flashBeep) g_LightOffCounter = FLASH_DURATION; // we got an event do we need to flash the display ? if (g_eeGeneral.flashBeep && (e <= AU_ERROR || e >= AU_WARNING1)) g_LightOffCounter = FLASH_DURATION; // we got an event do we need to flash the display ?
if (e < AU_FRSKY_FIRST || empty()) { if (e < AU_FRSKY_FIRST || empty()) {
switch (e) { switch (e) {
// inactivity timer alert // inactivity timer alert

View file

@ -55,7 +55,8 @@ static const pm_uint8_t beepTab[] PROGMEM = {
void beep(uint8_t val) void beep(uint8_t val)
{ {
checkFlashOnBeep(); if(g_eeGeneral.flashBeep && val > 1) g_LightOffCounter = FLASH_DURATION;
if (g_eeGeneral.beeperMode>0 || (g_eeGeneral.beeperMode==0 && val!=0) || (g_eeGeneral.beeperMode==-1 && val>=3)) { if (g_eeGeneral.beeperMode>0 || (g_eeGeneral.beeperMode==0 && val!=0) || (g_eeGeneral.beeperMode==-1 && val>=3)) {
_beep(pgm_read_byte(beepTab+5*(2+g_eeGeneral.beeperLength)+val)); _beep(pgm_read_byte(beepTab+5*(2+g_eeGeneral.beeperLength)+val));
} }

View file

@ -63,17 +63,17 @@ volatile uint32_t Tenms ;
#ifdef REVB #ifdef REVB
inline void init_soft_power() inline void init_soft_power()
{ {
register Pio *pioptr ; register Pio *pioptr = PIOC ;
// Configure RF_power (PC17)
pioptr = PIOC ;
// Configure RF_power (PC17) but not PPM-jack-in (PC22), neither need pullups
pioptr->PIO_PER = PIO_PC17 ; // Enable bit C17 pioptr->PIO_PER = PIO_PC17 ; // Enable bit C17
pioptr->PIO_ODR = PIO_PC17 ; // Set bit C17 as input pioptr->PIO_ODR = PIO_PC17 ; // Set bit C17 as input
pioptr->PIO_PUDR = PIO_PC17; // Disable pullup on bit C17
pioptr->PIO_PPDER = PIO_PC17; // Enable pulldown on bit C17
pioptr = PIOA ; pioptr = PIOA ;
pioptr->PIO_PER = PIO_PA8 ; // Enable bit A8 (Soft Power) pioptr->PIO_PER = PIO_PA8 ; // Enable bit A8 (Soft Power)
pioptr->PIO_ODR = PIO_PA8 ; // Set bit A8 as input pioptr->PIO_ODR = PIO_PA8 ; // Set bit A8 as input
pioptr->PIO_PUER = PIO_PA8 ; // Enable PA8 pullup pioptr->PIO_PUER = PIO_PA8 ; // Enable PA8 pullup
} }
// Returns non-zero if power is switched off // Returns non-zero if power is switched off
@ -124,20 +124,6 @@ void soft_power_off()
extern "C" void sam_boot( void ) ; extern "C" void sam_boot( void ) ;
void disable_ssc()
{
register Pio *pioptr ;
register Ssc *sscptr ;
// Revert back to pwm output
pioptr = PIOA ;
pioptr->PIO_PER = 0x00020000L ; // Assign A17 to PIO
sscptr = SSC ;
sscptr->SSC_CR = SSC_CR_TXDIS ;
}
// Prototype // Prototype
// Free pins (PA16 is stock buzzer) // Free pins (PA16 is stock buzzer)
// PA23, PA24, PA25, PB7, PB13 // PA23, PA24, PA25, PB7, PB13
@ -236,9 +222,9 @@ inline void UART_Configure( uint32_t baudrate, uint32_t masterClock)
/* Configure PIO */ /* Configure PIO */
pioptr = PIOA ; pioptr = PIOA ;
pioptr->PIO_ABCDSR[0] &= ~0x00000600 ; // Peripheral A pioptr->PIO_ABCDSR[0] &= ~(PIO_PA9 | PIO_PA10) ; // Peripheral A
pioptr->PIO_ABCDSR[1] &= ~0x00000600 ; // Peripheral A pioptr->PIO_ABCDSR[1] &= ~(PIO_PA9 | PIO_PA10) ; // Peripheral A
pioptr->PIO_PDR = 0x00000600 ; // Assign to peripheral pioptr->PIO_PDR = (PIO_PA9 | PIO_PA10) ; // Assign to peripheral
/* Configure PMC */ /* Configure PMC */
PMC->PMC_PCER0 = 1 << CONSOLE_ID; PMC->PMC_PCER0 = 1 << CONSOLE_ID;
@ -259,6 +245,7 @@ inline void UART_Configure( uint32_t baudrate, uint32_t masterClock)
/* Enable receiver and transmitter */ /* Enable receiver and transmitter */
pUart->UART_CR = UART_CR_RXEN | UART_CR_TXEN; pUart->UART_CR = UART_CR_RXEN | UART_CR_TXEN;
} }
inline void UART3_Configure( uint32_t baudrate, uint32_t masterClock) inline void UART3_Configure( uint32_t baudrate, uint32_t masterClock)
@ -308,9 +295,9 @@ inline void UART2_Configure( uint32_t baudrate, uint32_t masterClock)
/* Configure PIO */ /* Configure PIO */
pioptr = PIOA ; pioptr = PIOA ;
pioptr->PIO_ABCDSR[0] &= ~0x00000060 ; // Peripheral A pioptr->PIO_ABCDSR[0] &= ~(PIO_PA5 | PIO_PA6) ; // Peripheral A
pioptr->PIO_ABCDSR[1] &= ~0x00000060 ; // Peripheral A pioptr->PIO_ABCDSR[1] &= ~(PIO_PA5 | PIO_PA6) ; // Peripheral A
pioptr->PIO_PDR = 0x00000060 ; // Assign to peripheral pioptr->PIO_PDR = (PIO_PA5 | PIO_PA6) ; // Assign to peripheral
// /* Configure PMC */ // /* Configure PMC */
PMC->PMC_PCER0 = 1 << SECOND_ID; PMC->PMC_PCER0 = 1 << SECOND_ID;
@ -320,7 +307,7 @@ inline void UART2_Configure( uint32_t baudrate, uint32_t masterClock)
| US_CR_RXDIS | US_CR_TXDIS; | US_CR_RXDIS | US_CR_TXDIS;
// /* Configure mode */ // /* Configure mode */
pUsart->US_MR = 0x000008C0 ; // NORMAL, No Parity pUsart->US_MR = 0x000008C0 ; // NORMAL, No Parity, 8 bit
// /* Configure baudrate */ // /* Configure baudrate */
// /* Asynchronous, no oversampling */ // /* Asynchronous, no oversampling */
@ -333,7 +320,7 @@ inline void UART2_Configure( uint32_t baudrate, uint32_t masterClock)
pUsart->US_CR = US_CR_RXEN | US_CR_TXEN; pUsart->US_CR = US_CR_RXEN | US_CR_TXEN;
} }
// Test, starts TIMER0 at full speed (MCK/2) for delay timing // Starts TIMER0 at full speed (MCK/2) for delay timing
// @ 36MHz this is 18MHz // @ 36MHz this is 18MHz
// This was 6 MHz, we may need to slow it to TIMER_CLOCK2 (MCK/8=4.5 MHz) // This was 6 MHz, we may need to slow it to TIMER_CLOCK2 (MCK/8=4.5 MHz)
inline void start_timer0() inline void start_timer0()
@ -350,34 +337,29 @@ inline void start_timer0()
ptc->TC_CHANNEL[0].TC_RC = 0xFFF0 ; ptc->TC_CHANNEL[0].TC_RC = 0xFFF0 ;
ptc->TC_CHANNEL[0].TC_RA = 0 ; ptc->TC_CHANNEL[0].TC_RA = 0 ;
ptc->TC_CHANNEL[0].TC_CMR = 0x00008040 ; // 0000 0000 0000 0000 1000 0000 0100 0000, stop at regC ptc->TC_CHANNEL[0].TC_CMR = 0x00008040 ; // 0000 0000 0000 0000 1000 0000 0100 0000, stop at regC
ptc->TC_CHANNEL[0].TC_CCR = 5 ; // Enable clock and trigger it (may only need trigger) ptc->TC_CHANNEL[0].TC_CCR = 5 ; // Enable clock and trigger it (may only need trigger)
} }
// Starts TIMER2 at 100Hz, commentd out drive of TIOA2 (A26, EXT2) out // TIMER2 at 200Hz, provides 5mS for sound and 10mS tick on interrupt
// Starts TIMER2 at 200Hz, commentd out drive of TIOA2 (A26, EXT2)
inline void start_timer2() inline void start_timer2()
{ {
register Pio *pioptr ;
register Tc *ptc ; register Tc *ptc ;
register uint32_t timer ; register uint32_t timer ;
// Enable peripheral clock TC0 = bit 23 thru TC5 = bit 28 // Enable peripheral clock TC0 = bit 23 thru TC5 = bit 28
PMC->PMC_PCER0 |= 0x02000000L ; // Enable peripheral clock to TC2 PMC->PMC_PCER0 |= 0x02000000L ; // Enable peripheral clock to TC2
timer = Master_frequency / 12800 ; // MCK/128 and 100 Hz timer = Master_frequency / 12800 / 2; // MCK/128 and 200 Hz
ptc = TC0 ; // Tc block 0 (TC0-2) ptc = TC0 ; // Tc block 0 (TC0-2)
ptc->TC_BCR = 0 ; // No sync ptc->TC_BCR = 0 ; // No sync
ptc->TC_BMR = 0 ; ptc->TC_BMR = 0 ;
ptc->TC_CHANNEL[2].TC_CMR = 0x00008000 ; // Waveform mode ptc->TC_CHANNEL[2].TC_CMR = 0x00008000 ; // Waveform mode
ptc->TC_CHANNEL[2].TC_RC = timer ; // 10 Hz ptc->TC_CHANNEL[2].TC_RC = timer ; // 10 Hz
ptc->TC_CHANNEL[2].TC_RA = timer >> 1 ; ptc->TC_CHANNEL[2].TC_RA = timer >> 1 ;
ptc->TC_CHANNEL[2].TC_CMR = 0x0009C003 ; // 0000 0000 0000 1001 1100 0000 0000 0011 ptc->TC_CHANNEL[2].TC_CMR = 0x0009C003 ; // 0000 0000 0000 1001 1100 0000 0000 0011
// MCK/128, set @ RA, Clear @ RC waveform ptc->TC_CHANNEL[2].TC_CCR = 5 ; // Enable clock and trigger it (may only need trigger)
pioptr = PIOC ;
pioptr->PIO_PER = 0x00080000L ; // Enable bits C19
pioptr->PIO_OER = 0x00080000L ; // Set as output
ptc->TC_CHANNEL[2].TC_CCR = 5 ; // Enable clock and trigger it (may only need trigger)
NVIC_EnableIRQ(TC2_IRQn) ; NVIC_EnableIRQ(TC2_IRQn) ;
TC0->TC_CHANNEL[2].TC_IER = TC_IER0_CPCS ; TC0->TC_CHANNEL[2].TC_IER = TC_IER0_CPCS ;
@ -495,28 +477,23 @@ void end_ppm_capture()
extern "C" void TC2_IRQHandler() extern "C" void TC2_IRQHandler()
{ {
register uint32_t dummy; register uint32_t dummy;
static uint32_t pre_scale ; // Used to get 10 Hz counter static uint32_t pre_scale ; // Used to get 10 Hz counter
/* Clear status bit to acknowledge interrupt */ /* Clear status bit to acknowledge interrupt */
dummy = TC0->TC_CHANNEL[2].TC_SR; dummy = TC0->TC_CHANNEL[2].TC_SR;
(void) dummy ; // Discard value - prevents compiler warning (void) dummy ; // Discard value - prevents compiler warning
/* TODO if ( Buzzer_count ) sound_5ms() ;
{
if ( --Buzzer_count == 0 )
{
buzzer_off() ;
}
} */
if ( ++pre_scale >= 10 ) if ( ++pre_scale >= 2 ) {
{ Tenms |= 1 ; // 10 mS has passed
// TODO needed? Timer2_count += 1 ; if ( Buzzer_count ) {
pre_scale = 0 ; if ( --Buzzer_count == 0 )
} buzzer_off() ;
per10ms(); }
pre_scale = 0 ;
// heartbeat |= HEART_TIMER10ms; per10ms();
}
} }
// Settings for mode register ADC_MR // Settings for mode register ADC_MR
@ -581,10 +558,8 @@ void init_pwm()
pioptr = PIOB ; pioptr = PIOB ;
pioptr->PIO_PER = 0x00000020L ; // Enable bit B5 pioptr->PIO_PER = 0x00000020L ; // Enable bit B5
pioptr->PIO_ODR = 0x00000020L ; // set as input pioptr->PIO_ODR = 0x00000020L ; // set as input
#endif #else
pioptr = PIOA ;
#ifdef REVB
pioptr = PIOB ;
pioptr->PIO_ABCDSR[0] &= ~PIO_PA16 ; // Peripheral C pioptr->PIO_ABCDSR[0] &= ~PIO_PA16 ; // Peripheral C
pioptr->PIO_ABCDSR[1] |= PIO_PA16 ; // Peripheral C pioptr->PIO_ABCDSR[1] |= PIO_PA16 ; // Peripheral C
pioptr->PIO_PDR = PIO_PA16 ; // Disable bit A16 Assign to peripheral pioptr->PIO_PDR = PIO_PA16 ; // Disable bit A16 Assign to peripheral
@ -758,7 +733,6 @@ void board_init()
eeprom_init(); eeprom_init();
} }
#endif #endif
// keys: // keys:
@ -821,73 +795,76 @@ uint32_t read_keys()
return y ; return y ;
} }
uint32_t read_trims() uint32_t read_trims()
{ {
uint32_t trims = 0; uint32_t trims;
uint32_t trima;
trims = 0;
trima = PIOA->PIO_PDSR;
// TRIM_LH_DOWN PA7 (PA23) // TRIM_LH_DOWN PA7 (PA23)
#ifdef REVB #ifdef REVB
if ( ( PIOA->PIO_PDSR & 0x00800000 ) == 0 ) if ((trima & 0x00800000) == 0)
#else #else
if ((PIOA->PIO_PDSR & 0x0080) == 0) if ( ( trima & 0x0080 ) == 0 )
#endif #endif
{ {
trims |= 1; trims |= 1;
} }
// TRIM_LV_DOWN PA27 (PA24)
#ifdef REVB
if ((trima & 0x01000000) == 0)
#else
if ( ( trima & 0x08000000 ) == 0 )
#endif
{
trims |= 4;
}
// TRIM_RV_UP PA30 (PA1)
#ifdef REVB
if ((trima & 0x00000002) == 0)
#else
if ( ( trima & 0x40000000 ) == 0 )
#endif
{
trims |= 0x20;
}
// TRIM_RH_DOWN PA29 (PA0)
#ifdef REVB
if ((trima & 0x00000001) == 0)
#else
if ( ( trima & 0x20000000 ) == 0 )
#endif
{
trims |= 0x40;
}
// TRIM_LH_UP PB4 // TRIM_LH_UP PB4
if ((PIOB->PIO_PDSR & 0x10) == 0) { if ((PIOB->PIO_PDSR & 0x10) == 0) {
trims |= 2; trims |= 2;
} }
// TRIM_LV_DOWN PA27 (PA24) trima = PIOC->PIO_PDSR;
#ifdef REVB
if ( ( PIOA->PIO_PDSR & 0x01000000 ) == 0 )
#else
if ((PIOA->PIO_PDSR & 0x08000000) == 0)
#endif
{
trims |= 4;
}
// TRIM_LV_UP PC28 // TRIM_LV_UP PC28
if ((PIOC->PIO_PDSR & 0x10000000) == 0) { if ((trima & 0x10000000) == 0) {
trims |= 8; trims |= 8;
} }
// TRIM_RV_DOWN PC10 // TRIM_RV_DOWN PC10
if ((PIOC->PIO_PDSR & 0x00000400) == 0) { if ((trima & 0x00000400) == 0) {
trims |= 0x10; trims |= 0x10;
} }
// TRIM_RV_UP PA30 (PA1)
#ifdef REVB
if ( ( PIOA->PIO_PDSR & 0x00000002 ) == 0 )
#else
if ((PIOA->PIO_PDSR & 0x40000000) == 0)
#endif
{
trims |= 0x20;
}
// TRIM_RH_DOWN PA29 (PA0)
#ifdef REVB
if ( ( PIOA->PIO_PDSR & 0x00000001 ) == 0 )
#else
if ((PIOA->PIO_PDSR & 0x20000000) == 0)
#endif
{
trims |= 0x40;
}
// TRIM_RH_UP PC9 // TRIM_RH_UP PC9
if ((PIOC->PIO_PDSR & 0x00000200) == 0) { if ((trima & 0x00000200) == 0) {
trims |= 0x80; trims |= 0x80;
} }
return trims ; return trims;
} }
uint8_t keyDown() uint8_t keyDown()
@ -1012,12 +989,13 @@ void readKeysAndTrims()
{ {
register uint32_t i; register uint32_t i;
/* Fix pulldown resistor on RF-POWER
if (PIOC->PIO_ODSR & 0x00080000) { if (PIOC->PIO_ODSR & 0x00080000) {
PIOC->PIO_CODR = 0x00200000L; // Set bit C19 OFF PIOC->PIO_CODR = 0x00200000L; // Set bit C19 OFF
} }
else { else {
PIOC->PIO_SODR = 0x00200000L; // Set bit C19 ON PIOC->PIO_SODR = 0x00200000L; // Set bit C19 ON
} } */
uint8_t enuk = KEY_MENU; uint8_t enuk = KEY_MENU;
uint8_t in = ~read_keys(); uint8_t in = ~read_keys();
@ -1045,22 +1023,121 @@ void readKeysAndTrims()
} }
} }
#define RX_UART_BUFFER_SIZE 32
struct t_rxUartBuffer
{
uint8_t fifo[RX_UART_BUFFER_SIZE] ;
uint8_t *outPtr ;
} ;
struct t_rxUartBuffer TelemetryInBuffer[2] ;
uint32_t TelemetryActiveBuffer ;
void startPdcUsartReceive()
{
register Usart *pUsart = SECOND_USART;
TelemetryInBuffer[0].outPtr = TelemetryInBuffer[0].fifo ;
TelemetryInBuffer[1].outPtr = TelemetryInBuffer[1].fifo ;
pUsart->US_RPR = (uint32_t)TelemetryInBuffer[0].fifo ;
pUsart->US_RNPR = (uint32_t)TelemetryInBuffer[1].fifo ;
pUsart->US_RCR = RX_UART_BUFFER_SIZE ;
pUsart->US_RNCR = RX_UART_BUFFER_SIZE ;
pUsart->US_PTCR = US_PTCR_RXTEN ;
TelemetryActiveBuffer = 0 ;
}
void endPdcUsartReceive()
{
register Usart *pUsart = SECOND_USART;
pUsart->US_PTCR = US_PTCR_RXTDIS ;
}
void rxPdcUsart( void (*pChProcess)(uint8_t x) )
{
#if !defined(SIMU)
register Usart *pUsart = SECOND_USART;
uint8_t *ptr ;
uint8_t *endPtr ;
// uint32_t bufIndex ;
// uint32_t i ;
uint32_t j ;
//Find out where the DMA has got to
__disable_irq() ;
pUsart->US_PTCR = US_PTCR_RXTDIS ; // Freeze DMA
ptr = (uint8_t *)pUsart->US_RPR ;
j = pUsart->US_RNCR ;
pUsart->US_PTCR = US_PTCR_RXTEN ; // DMA active again
__enable_irq() ;
endPtr = ptr - 1 ;
ptr = TelemetryInBuffer[TelemetryActiveBuffer].outPtr ;
if ( j == 0 ) // First buf is full
{
endPtr = &TelemetryInBuffer[TelemetryActiveBuffer].fifo[RX_UART_BUFFER_SIZE-1] ; // last byte
}
while ( ptr <= endPtr )
{
(*pChProcess)(*ptr++) ;
}
TelemetryInBuffer[TelemetryActiveBuffer].outPtr = ptr ;
if ( j == 0 ) // First buf is full
{
TelemetryInBuffer[TelemetryActiveBuffer].outPtr = TelemetryInBuffer[TelemetryActiveBuffer].fifo ;
pUsart->US_RNPR = (uint32_t)TelemetryInBuffer[TelemetryActiveBuffer].fifo ;
pUsart->US_RNCR = RX_UART_BUFFER_SIZE ;
TelemetryActiveBuffer ^= 1 ; // Other buffer is active
rxPdcUsart( pChProcess ) ; // Get any chars from second buffer
}
#endif
}
uint32_t txPdcUsart( uint8_t *buffer, uint32_t size )
{
register Usart *pUsart = SECOND_USART;
if ( pUsart->US_TNCR == 0 )
{
pUsart->US_TNPR = (uint32_t)buffer ;
pUsart->US_TNCR = size ;
pUsart->US_PTCR = US_PTCR_TXTEN ;
return 1 ;
}
return 0 ;
}
uint32_t txPdcPending()
{
register Usart *pUsart = SECOND_USART;
uint32_t x ;
__disable_irq() ;
pUsart->US_PTCR = US_PTCR_TXTDIS ; // Freeze DMA
x = pUsart->US_TNCR ; // Total
x += pUsart->US_TCR ; // Still to send
pUsart->US_PTCR = US_PTCR_TXTEN ; // DMA active again
__enable_irq() ;
return x ;
}
void usb_mode() void usb_mode()
{ {
// This might be replaced by a software reset // This might be replaced by a software reset
// Any interrupts that have been enabled must be disabled here // Any interrupts that have been enabled must be disabled here
// BEFORE calling sam_boot() // BEFORE calling sam_boot()
// TODO endPdcUsartReceive() ; // Terminate any serial reception endPdcUsartReceive() ; // Terminate any serial reception
#ifdef REVB // TODO in ersky9x soft_power_off() ; is called before endPdcUsartReceive
soft_power_off() ;
#endif
end_ppm_capture() ; end_ppm_capture() ;
end_spi() ; end_spi() ;
end_sound() ; end_sound() ;
TC0->TC_CHANNEL[2].TC_IDR = TC_IDR0_CPCS ; TC0->TC_CHANNEL[2].TC_IDR = TC_IDR0_CPCS ;
NVIC_DisableIRQ(TC2_IRQn) ; NVIC_DisableIRQ(TC2_IRQn) ;
// PWM->PWM_IDR1 = PWM_IDR1_CHID0 ; // PWM->PWM_IDR1 = PWM_IDR1_CHID0 ;
// TODO disable_main_ppm() ; disable_main_ppm() ;
// PWM->PWM_IDR1 = PWM_IDR1_CHID3 ; // PWM->PWM_IDR1 = PWM_IDR1_CHID3 ;
// NVIC_DisableIRQ(PWM_IRQn) ; // NVIC_DisableIRQ(PWM_IRQn) ;
disable_ssc() ; disable_ssc() ;

View file

@ -152,42 +152,12 @@ void per10ms()
readKeysAndTrims(); readKeysAndTrims();
#ifdef MAVLINK #if defined(MAVLINK) && !defined(PCBARM)
check_mavlink() ; check_mavlink();
#endif #endif
#if defined (FRSKY) #if defined (FRSKY) && !defined(PCBARM)
check_frsky();
// TODO everything here in check_frsky() ;
// TODO it would be better in frsky.h / .cpp!
// Attempt to transmit any waiting Fr-Sky alarm set packets every 50ms (subject to packet buffer availability)
static uint8_t FrskyDelay = 5;
if (FrskyAlarmSendState && (--FrskyDelay == 0))
{
FrskyDelay = 5; // 50ms
FRSKY10mspoll();
}
#ifndef SIMU
if (frskyUsrStreaming > 0)
frskyUsrStreaming--;
if (frskyStreaming > 0) {
frskyStreaming--;
}
else if (g_eeGeneral.enableTelemetryAlarm && (g_model.frsky.channels[0].ratio || g_model.frsky.channels[1].ratio)) {
#if defined (AUDIO)
if (!(g_tmr10ms % 30)) {
audioDefevent(AU_WARNING1);
}
#else
if (!(g_tmr10ms % 30)) {
warble = !(g_tmr10ms % 60);
AUDIO_WARNING2();
}
#endif
}
#endif
#endif #endif
// These moved here from perOut() to improve beep trigger reliability. // These moved here from perOut() to improve beep trigger reliability.
@ -195,33 +165,4 @@ void per10ms()
if(mixWarning & 2) if(((g_tmr10ms&0xFF)== 64) || ((g_tmr10ms&0xFF)== 72)) AUDIO_MIX_WARNING_2(); if(mixWarning & 2) if(((g_tmr10ms&0xFF)== 64) || ((g_tmr10ms&0xFF)== 72)) AUDIO_MIX_WARNING_2();
if(mixWarning & 4) if(((g_tmr10ms&0xFF)==128) || ((g_tmr10ms&0xFF)==136) || ((g_tmr10ms&0xFF)==144)) AUDIO_MIX_WARNING_3(); if(mixWarning & 4) if(((g_tmr10ms&0xFF)==128) || ((g_tmr10ms&0xFF)==136) || ((g_tmr10ms&0xFF)==144)) AUDIO_MIX_WARNING_3();
#if defined(FRSKY_HUB) || defined(WS_HOW_HIGH)
static uint16_t s_varioTmr = 0;
if (isFunctionActive(FUNC_VARIO)) {
#if defined(AUDIO)
uint8_t warble = 0;
#endif
int8_t verticalSpeed = limit((int16_t)-100, (int16_t)(frskyHubData.varioSpeed/10), (int16_t)+100);
uint16_t interval;
if (verticalSpeed == 0) {
interval = 300;
}
else {
if (verticalSpeed < 0) {
verticalSpeed = -verticalSpeed;
warble = 1;
}
interval = (uint8_t)200 / verticalSpeed;
}
if (g_tmr10ms - s_varioTmr > interval) {
s_varioTmr = g_tmr10ms;
if (warble)
AUDIO_VARIO_DOWN();
else
AUDIO_VARIO_UP();
}
}
#endif
} }

View file

@ -1322,6 +1322,7 @@ typedef struct {
RoReg PIO_PCIMR; /**< \brief (Pio Offset: 0x15C) Parallel Capture Interrupt Mask Register */ RoReg PIO_PCIMR; /**< \brief (Pio Offset: 0x15C) Parallel Capture Interrupt Mask Register */
RoReg PIO_PCISR; /**< \brief (Pio Offset: 0x160) Parallel Capture Interrupt Status Register */ RoReg PIO_PCISR; /**< \brief (Pio Offset: 0x160) Parallel Capture Interrupt Status Register */
RoReg PIO_PCRHR; /**< \brief (Pio Offset: 0x164) Parallel Capture Reception Holding Register */ RoReg PIO_PCRHR; /**< \brief (Pio Offset: 0x164) Parallel Capture Reception Holding Register */
RwReg Reserved14[38];
} Pio; } Pio;
#endif /* __ASSEMBLY__ */ #endif /* __ASSEMBLY__ */
/* -------- PIO_PER : (PIO Offset: 0x0000) PIO Enable Register -------- */ /* -------- PIO_PER : (PIO Offset: 0x0000) PIO Enable Register -------- */
@ -6744,6 +6745,11 @@ typedef struct {
#define WDT CAST(Wdt , 0x400E1450U) /**< \brief (WDT ) Base Address */ #define WDT CAST(Wdt , 0x400E1450U) /**< \brief (WDT ) Base Address */
#define RTC CAST(Rtc , 0x400E1460U) /**< \brief (RTC ) Base Address */ #define RTC CAST(Rtc , 0x400E1460U) /**< \brief (RTC ) Base Address */
#define GPBR CAST(Gpbr , 0x400E1490U) /**< \brief (GPBR ) Base Address */ #define GPBR CAST(Gpbr , 0x400E1490U) /**< \brief (GPBR ) Base Address */
// indices for three pio structures
#define iPIOA 0
#define iPIOB 1
#define iPIOC 2
/*@}*/ /*@}*/
/* ***************************************************************************** */ /* ***************************************************************************** */

View file

@ -50,12 +50,19 @@ void set_volume( register uint8_t volume ) ;
extern "C" void TWI0_IRQHandler (void) ; extern "C" void TWI0_IRQHandler (void) ;
void audioDefevent( uint8_t e ) ; void audioDefevent( uint8_t e ) ;
extern uint32_t Master_frequency ; // TODO in a .h? extern uint32_t Master_frequency ; // TODO in a .h?
volatile uint32_t Tone_timer ; // Modified in interrupt routine
volatile uint8_t Buzzer_count ; volatile uint8_t Buzzer_count ;
struct t_sound_globals
{
uint32_t Freq ;
uint32_t Sound_time ;
uint32_t Frequency ;
volatile uint32_t Tone_timer ; // Modified in interrupt routine
volatile uint8_t Tone_ms_timer ;
} Sound_g ;
// Must NOT be in flash, PDC needs a RAM source. // Must NOT be in flash, PDC needs a RAM source.
uint16_t Sine_values[] = uint16_t Sine_values[] =
{ {
@ -72,17 +79,18 @@ uint16_t Sine_values[] =
} ; } ;
// Must NOT be in flash, PDC needs a RAM source. // Must NOT be in flash, PDC needs a RAM source.
uint16_t Sine_values64[] = // We'll use these for higher frequencies
{ //uint16_t Sine_values64[] =
2048,2244,2438,2628,2813,2990,3159,3316, //{
3462,3594,3710,3811,3895,3961,4009,4038, //2048,2244,2438,2628,2813,2990,3159,3316,
4048,4038,4009,3961,3895,3811,3710,3594, //3462,3594,3710,3811,3895,3961,4009,4038,
3462,3316,3159,2990,2813,2628,2438,2244, //4048,4038,4009,3961,3895,3811,3710,3594,
2048,1851,1657,1467,1282,1105, 936, 779, //3462,3316,3159,2990,2813,2628,2438,2244,
633, 501, 385, 284, 200, 134, 86, 57, //2048,1851,1657,1467,1282,1105, 936, 779,
48, 57, 86, 134, 200, 284, 385, 501, // 633, 501, 385, 284, 200, 134, 86, 57,
633, 779, 936,1105,1282,1467,1657,1851 // 48, 57, 86, 134, 200, 284, 385, 501,
} ; // 633, 779, 936,1105,1282,1467,1657,1851
//} ;
const uint16_t PianoTones[] = const uint16_t PianoTones[] =
{ {
@ -149,14 +157,12 @@ void buzzer_sound( uint8_t time )
} }
static uint32_t Frequency ;
void set_frequency( uint32_t frequency ) void set_frequency( uint32_t frequency )
{ {
register Tc *ptc ; register Tc *ptc ;
register uint32_t timer ; register uint32_t timer ;
Frequency = frequency ; Sound_g.Frequency = frequency ;
timer = Master_frequency / (800 * frequency) ; // MCK/8 and 100 000 Hz timer = Master_frequency / (800 * frequency) ; // MCK/8 and 100 000 Hz
if ( timer > 65535 ) if ( timer > 65535 )
{ {
@ -193,7 +199,7 @@ void start_timer1()
ptc->TC_CHANNEL[1].TC_CMR = 0x0009C001 ; // 0000 0000 0000 1001 1100 0000 0000 0001 ptc->TC_CHANNEL[1].TC_CMR = 0x0009C001 ; // 0000 0000 0000 1001 1100 0000 0000 0001
// MCK/8, set @ RA, Clear @ RC waveform // MCK/8, set @ RA, Clear @ RC waveform
ptc->TC_CHANNEL[1].TC_CCR = 5 ; // Enable clock and trigger it (may only need trigger) ptc->TC_CHANNEL[1].TC_CCR = 5 ; // Enable clock and trigger it (may only need trigger)
Frequency = 1000 ; Sound_g.Frequency = 1000 ;
} }
@ -232,13 +238,18 @@ extern "C" void DAC_IRQHandler()
// Data for PDC must NOT be in flash, PDC needs a RAM source. // Data for PDC must NOT be in flash, PDC needs a RAM source.
DACC->DACC_TNPR = (uint32_t) Sine_values ; DACC->DACC_TNPR = (uint32_t) Sine_values ;
DACC->DACC_TNCR = 50 ; // words, 100 16 bit values DACC->DACC_TNCR = 50 ; // words, 100 16 bit values
if ( Tone_timer ) if ( Sound_g.Tone_timer )
{ {
if ( --Tone_timer == 0 ) if ( --Sound_g.Tone_timer == 0 )
{ {
DACC->DACC_IDR = DACC_IDR_ENDTX ; DACC->DACC_IDR = DACC_IDR_ENDTX ;
} }
} }
// if ( Tone_ms_timer == 0 )
// {
// Tone_ms_timer = -1 ;
// DACC->DACC_IDR = DACC_IDR_ENDTX ;
// }
} }
void end_sound() void end_sound()
@ -251,11 +262,42 @@ void end_sound()
PMC->PMC_PCER0 &= ~0x40000000L ; // Disable peripheral clock to DAC PMC->PMC_PCER0 &= ~0x40000000L ; // Disable peripheral clock to DAC
} }
// Called every 5mS from interrupt routine
void sound_5ms()
{
if ( Sound_g.Tone_ms_timer > 0 )
{
Sound_g.Tone_ms_timer -= 1 ;
}
if ( Sound_g.Tone_ms_timer == 0 )
{
if ( Sound_g.Sound_time )
{
Sound_g.Tone_ms_timer = ( Sound_g.Sound_time + 4 ) / 5 ;
if ( Sound_g.Freq ) // 0 => silence for time
{
set_frequency( Sound_g.Freq ) ;
tone_start( 0 ) ;
}
Sound_g.Sound_time = 0 ;
}
else
{
DACC->DACC_IDR = DACC_IDR_ENDTX ; // Disable interrupt
Sound_g.Tone_timer = 0 ;
}
}
}
// frequency in Hz, time in mS
void playTone( uint32_t frequency, uint32_t time ) void playTone( uint32_t frequency, uint32_t time )
{ {
set_frequency( frequency ) ; Sound_g.Freq = frequency ;
tone_start( time ) ; Sound_g.Sound_time = time ;
// set_frequency( frequency ) ;
// Tone_ms_timer = ( time + 4 ) / 5 ;
// tone_start( 0 ) ;
} }
@ -263,14 +305,14 @@ void playTone( uint32_t frequency, uint32_t time )
void tone_start( register uint32_t time ) void tone_start( register uint32_t time )
{ {
PMC->PMC_PCER0 |= 0x40000000L ; // Enable peripheral clock to DAC PMC->PMC_PCER0 |= 0x40000000L ; // Enable peripheral clock to DAC
Tone_timer = Frequency * time / 1000 ; Sound_g.Tone_timer = Sound_g.Frequency * time / 1000 ;
DACC->DACC_IER = DACC_IER_ENDTX ; DACC->DACC_IER = DACC_IER_ENDTX ;
} }
void tone_stop() void tone_stop()
{ {
DACC->DACC_IDR = DACC_IDR_ENDTX ; // Disable interrupt DACC->DACC_IDR = DACC_IDR_ENDTX ; // Disable interrupt
Tone_timer = 0 ; Sound_g.Tone_timer = 0 ;
} }
@ -298,7 +340,7 @@ void init_twi()
TWI0->TWI_CR = TWI_CR_MSEN | TWI_CR_SVDIS ; // Master mode enable TWI0->TWI_CR = TWI_CR_MSEN | TWI_CR_SVDIS ; // Master mode enable
TWI0->TWI_MMR = 0x002F0000 ; // Device 5E (>>1) and master is writing TWI0->TWI_MMR = 0x002F0000 ; // Device 5E (>>1) and master is writing
NVIC_EnableIRQ(TWI0_IRQn) ; NVIC_EnableIRQ(TWI0_IRQn) ;
set_volume( 2 ) ;
} }
static int16_t Volume_required ; static int16_t Volume_required ;
@ -310,7 +352,7 @@ static const uint8_t Volume_scale[NUM_VOL_LEVELS] =
void set_volume( register uint8_t volume ) void set_volume( register uint8_t volume )
{ {
PMC->PMC_PCER0 |= 0x00080000L ; // Enable peripheral clock to TWI0 // PMC->PMC_PCER0 |= 0x00080000L ; // Enable peripheral clock to TWI0
if ( volume >= NUM_VOL_LEVELS ) if ( volume >= NUM_VOL_LEVELS )
{ {
@ -350,7 +392,7 @@ extern "C" void TWI0_IRQHandler()
void audioDefevent(uint8_t e) void audioDefevent(uint8_t e)
{ {
buzzer_sound( 4 ) ; playTone( 2000, 60 ) ; // 2KHz, 60mS
// audio.event(e,BEEP_DEFAULT_FREQ); // audio.event(e,BEEP_DEFAULT_FREQ);
} }

View file

@ -54,6 +54,7 @@ extern void init_twi( void ) ;
extern void set_volume( register uint8_t volume ) ; extern void set_volume( register uint8_t volume ) ;
extern "C" void TWI0_IRQHandler (void) ; extern "C" void TWI0_IRQHandler (void) ;
extern void audioDefevent( uint8_t e ) ; extern void audioDefevent( uint8_t e ) ;
extern void sound_5ms( void ) ;

View file

@ -189,7 +189,7 @@ void TC4_IRQHandler (void) { while(1); }
void TC5_IRQHandler (void) { while(1); } void TC5_IRQHandler (void) { while(1); }
void ADC_IRQHandler (void) { while(1); } void ADC_IRQHandler (void) { while(1); }
// void DAC_IRQHandler (void) { while(1); } // void DAC_IRQHandler (void) { while(1); }
void PWM_IRQHandler (void) { while(1); } // void PWM_IRQHandler (void) { while(1); }
void CRCCU_IRQHandler (void) { while(1); } void CRCCU_IRQHandler (void) { while(1); }
void ACC_IRQHandler (void) { while(1); } void ACC_IRQHandler (void) { while(1); }
void USBD_IRQHandler (void) { while(1); } void USBD_IRQHandler (void) { while(1); }

View file

@ -52,7 +52,9 @@
uint8_t frskyRxBuffer[FRSKY_RX_PACKET_SIZE]; // Receive buffer. 9 bytes (full packet), worst case 18 bytes with byte-stuffing (+1) uint8_t frskyRxBuffer[FRSKY_RX_PACKET_SIZE]; // Receive buffer. 9 bytes (full packet), worst case 18 bytes with byte-stuffing (+1)
uint8_t frskyTxBuffer[FRSKY_TX_PACKET_SIZE]; // Ditto for transmit buffer uint8_t frskyTxBuffer[FRSKY_TX_PACKET_SIZE]; // Ditto for transmit buffer
#if !defined(PCBARM)
uint8_t frskyTxBufferCount = 0; uint8_t frskyTxBufferCount = 0;
#endif
uint8_t FrskyRxBufferReady = 0; uint8_t FrskyRxBufferReady = 0;
int8_t frskyStreaming = -1; int8_t frskyStreaming = -1;
uint8_t frskyUsrStreaming = 0; uint8_t frskyUsrStreaming = 0;
@ -408,67 +410,72 @@ void processFrskyPacket(uint8_t *packet)
a second buffer to receive data while one buffer is being processed (slowly). a second buffer to receive data while one buffer is being processed (slowly).
*/ */
#ifndef SIMU #if defined(PCBARM)
void processSerialData(uint8_t data)
#else
NOINLINE void processSerialData(uint8_t stat, uint8_t data) NOINLINE void processSerialData(uint8_t stat, uint8_t data)
#endif
{ {
static uint8_t numPktBytes = 0; static uint8_t numPktBytes = 0;
static uint8_t dataState = frskyDataIdle; static uint8_t dataState = frskyDataIdle;
if (stat & ((1 << FE0) | (1 << DOR0) | (1 << UPE0))) #if !defined(PCBARM)
{ // discard buffer and start fresh on any comms error if (stat & ((1 << FE0) | (1 << DOR0) | (1 << UPE0))) {
FrskyRxBufferReady = 0; // discard buffer and start fresh on any comms error
numPktBytes = 0; FrskyRxBufferReady = 0;
} numPktBytes = 0;
else }
else
#endif
{
if (FrskyRxBufferReady == 0) // can't get more data if the buffer hasn't been cleared
{ {
if (FrskyRxBufferReady == 0) // can't get more data if the buffer hasn't been cleared switch (dataState)
{ {
switch (dataState) case frskyDataStart:
{ if (data == START_STOP) break; // Remain in userDataStart if possible 0x7e,0x7e doublet found.
case frskyDataStart:
if (data == START_STOP) break; // Remain in userDataStart if possible 0x7e,0x7e doublet found.
if (numPktBytes < FRSKY_RX_PACKET_SIZE) if (numPktBytes < FRSKY_RX_PACKET_SIZE)
frskyRxBuffer[numPktBytes++] = data; frskyRxBuffer[numPktBytes++] = data;
dataState = frskyDataInFrame; dataState = frskyDataInFrame;
break; break;
case frskyDataInFrame: case frskyDataInFrame:
if (data == BYTESTUFF) if (data == BYTESTUFF)
{ {
dataState = frskyDataXOR; // XOR next byte dataState = frskyDataXOR; // XOR next byte
break;
}
if (data == START_STOP) // end of frame detected
{
processFrskyPacket(frskyRxBuffer); // FrskyRxBufferReady = 1;
dataState = frskyDataIdle;
break; break;
} }
if (numPktBytes < FRSKY_RX_PACKET_SIZE) if (data == START_STOP) // end of frame detected
frskyRxBuffer[numPktBytes++] = data; {
processFrskyPacket(frskyRxBuffer); // FrskyRxBufferReady = 1;
dataState = frskyDataIdle;
break; break;
}
if (numPktBytes < FRSKY_RX_PACKET_SIZE)
frskyRxBuffer[numPktBytes++] = data;
break;
case frskyDataXOR: case frskyDataXOR:
if (numPktBytes < FRSKY_RX_PACKET_SIZE) if (numPktBytes < FRSKY_RX_PACKET_SIZE)
frskyRxBuffer[numPktBytes++] = data ^ STUFF_MASK; frskyRxBuffer[numPktBytes++] = data ^ STUFF_MASK;
dataState = frskyDataInFrame; dataState = frskyDataInFrame;
break; break;
case frskyDataIdle: case frskyDataIdle:
if (data == START_STOP) if (data == START_STOP)
{ {
numPktBytes = 0; numPktBytes = 0;
dataState = frskyDataStart; dataState = frskyDataStart;
} }
break; break;
} // switch } // switch
} // if (FrskyRxBufferReady == 0) } // if (FrskyRxBufferReady == 0)
} }
} }
#if !defined(PCBARM) && !defined(SIMU)
ISR(USART0_RX_vect) ISR(USART0_RX_vect)
{ {
uint8_t stat; uint8_t stat;
@ -516,20 +523,30 @@ ISR(USART0_RX_vect)
cli() ; cli() ;
UCSR0B |= (1 << RXCIE0); // enable Interrupt UCSR0B |= (1 << RXCIE0); // enable Interrupt
} }
#endif #endif
/******************************************/ /******************************************/
#if defined(PCBARM)
void frskyTransmitBuffer( uint32_t size )
{
txPdcUsart( frskyTxBuffer, size ) ;
}
#else
// TODO inline ? pass parameter? to avoid #ifdef?
void frskyTransmitBuffer() void frskyTransmitBuffer()
{ {
UCSR0B |= (1 << UDRIE0); // enable UDRE0 interrupt UCSR0B |= (1 << UDRIE0); // enable UDRE0 interrupt
} }
#endif
uint8_t FrskyAlarmSendState = 0 ; uint8_t FrskyAlarmSendState = 0 ;
void FRSKY10mspoll(void) inline void FRSKY10mspoll(void)
{ {
#if defined(PCBARM)
if (txPdcPending())
#else
if (frskyTxBufferCount) if (frskyTxBufferCount)
#endif
return; // we only have one buffer. If it's in use, then we can't send yet. return; // we only have one buffer. If it's in use, then we can't send yet.
uint8_t *ptr = &frskyTxBuffer[0]; uint8_t *ptr = &frskyTxBuffer[0];
@ -560,8 +577,78 @@ void FRSKY10mspoll(void)
*ptr++ = START_STOP; // Start of packet *ptr++ = START_STOP; // Start of packet
#if defined(PCBARM)
frskyTransmitBuffer(ptr - &frskyTxBuffer[0]);
#else
frskyTxBufferCount = ptr - &frskyTxBuffer[0]; frskyTxBufferCount = ptr - &frskyTxBuffer[0];
frskyTransmitBuffer(); frskyTransmitBuffer();
#endif
}
void check_frsky()
{
#if defined(PCBARM)
rxPdcUsart(processSerialData); // Send serial data here
#endif
// Attempt to transmit any waiting Fr-Sky alarm set packets every 50ms (subject to packet buffer availability)
static uint8_t FrskyDelay = 5;
if (FrskyAlarmSendState && (--FrskyDelay == 0)) {
FrskyDelay = 5; // 50ms
FRSKY10mspoll();
}
#ifndef SIMU
if (frskyUsrStreaming > 0) {
frskyUsrStreaming--;
}
if (frskyStreaming > 0) {
frskyStreaming--;
}
else if (g_eeGeneral.enableTelemetryAlarm && (g_model.frsky.channels[0].ratio || g_model.frsky.channels[1].ratio)) {
#if defined (AUDIO)
if (!(g_tmr10ms % 30)) {
audioDefevent(AU_WARNING1);
}
#else
if (!(g_tmr10ms % 30)) {
warble = !(g_tmr10ms % 60);
AUDIO_WARNING2();
}
#endif
}
#endif
#if defined(FRSKY_HUB) || defined(WS_HOW_HIGH)
static uint16_t s_varioTmr = 0;
if (isFunctionActive(FUNC_VARIO)) {
#if defined(AUDIO)
uint8_t warble = 0;
#endif
int8_t verticalSpeed = limit((int16_t)-100, (int16_t)(frskyHubData.varioSpeed/10), (int16_t)+100);
uint16_t interval;
if (verticalSpeed == 0) {
interval = 300;
}
else {
if (verticalSpeed < 0) {
verticalSpeed = -verticalSpeed;
warble = 1;
}
interval = (uint8_t)200 / verticalSpeed;
}
if (g_tmr10ms - s_varioTmr > interval) {
s_varioTmr = g_tmr10ms;
if (warble)
AUDIO_VARIO_DOWN();
else
AUDIO_VARIO_UP();
}
}
#endif
} }
bool FRSKY_alarmRaised(uint8_t idx) bool FRSKY_alarmRaised(uint8_t idx)
@ -581,6 +668,7 @@ bool FRSKY_alarmRaised(uint8_t idx)
return false; return false;
} }
#if !defined(PCBARM)
inline void FRSKY_EnableTXD(void) inline void FRSKY_EnableTXD(void)
{ {
frskyTxBufferCount = 0; frskyTxBufferCount = 0;
@ -592,6 +680,7 @@ inline void FRSKY_EnableRXD(void)
UCSR0B |= (1 << RXEN0); // enable RX UCSR0B |= (1 << RXEN0); // enable RX
UCSR0B |= (1 << RXCIE0); // enable Interrupt UCSR0B |= (1 << RXCIE0); // enable Interrupt
} }
#endif
void FRSKY_Init(void) void FRSKY_Init(void)
{ {
@ -599,12 +688,15 @@ void FRSKY_Init(void)
memset(frskyAlarms, 0, sizeof(frskyAlarms)); memset(frskyAlarms, 0, sizeof(frskyAlarms));
resetTelemetry(); resetTelemetry();
#if defined(PCBARM)
startPdcUsartReceive() ;
#elif !defined(SIMU)
DDRE &= ~(1 << DDE0); // set RXD0 pin as input DDRE &= ~(1 << DDE0); // set RXD0 pin as input
PORTE &= ~(1 << PORTE0); // disable pullup on RXD0 pin PORTE &= ~(1 << PORTE0); // disable pullup on RXD0 pin
#undef BAUD #undef BAUD
#define BAUD 9600 #define BAUD 9600
#ifndef SIMU
#include <util/setbaud.h> #include <util/setbaud.h>
UBRR0H = UBRRH_VALUE; UBRR0H = UBRRH_VALUE;
@ -618,11 +710,10 @@ void FRSKY_Init(void)
while (UCSR0A & (1 << RXC0)) UDR0; // flush receive buffer while (UCSR0A & (1 << RXC0)) UDR0; // flush receive buffer
#endif
// 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.
FRSKY_EnableTXD(); // enable FrSky-Telemetry reception FRSKY_EnableTXD(); // enable FrSky-Telemetry reception
FRSKY_EnableRXD(); // enable FrSky-Telemetry reception FRSKY_EnableRXD(); // enable FrSky-Telemetry reception
#endif
} }
#if 0 #if 0

View file

@ -161,7 +161,7 @@ extern uint8_t frskyTxBuffer[FRSKY_TX_PACKET_SIZE];
extern uint8_t frskyTxBufferCount; extern uint8_t frskyTxBufferCount;
void FRSKY_Init(void); void FRSKY_Init(void);
void FRSKY10mspoll(void); void check_frsky(void);
inline void FRSKY_setModelAlarms(void) inline void FRSKY_setModelAlarms(void)
{ {

View file

@ -461,28 +461,28 @@ void putsChnRaw(uint8_t x, uint8_t y, uint8_t idx, uint8_t att)
{ {
if (idx==0) if (idx==0)
lcd_putsiAtt(x, y, STR_MMMINV, 0, att); lcd_putsiAtt(x, y, STR_MMMINV, 0, att);
else if (idx<=NUM_STICKS+NUM_POTS+2+3) else if (idx<=NUM_STICKS+NUM_POTS+NUM_ROTARY_ENCODERS+2+3)
lcd_putsiAtt(x, y, STR_VSRCRAW, idx-1, att); lcd_putsiAtt(x, y, STR_VSRCRAW, idx-1, att);
else if (idx<=NUM_STICKS+NUM_POTS+2+3+NUM_PPM) else if (idx<=NUM_STICKS+NUM_POTS+NUM_ROTARY_ENCODERS+2+3+NUM_PPM)
putsStrIdx(x, y, STR_PPM, idx - (NUM_STICKS+NUM_POTS+2+3), att); putsStrIdx(x, y, STR_PPM, idx - (NUM_STICKS+NUM_POTS+NUM_ROTARY_ENCODERS+2+3), att);
else if (idx<=NUM_STICKS+NUM_POTS+2+3+NUM_PPM+NUM_CHNOUT) else if (idx<=NUM_STICKS+NUM_POTS+NUM_ROTARY_ENCODERS+2+3+NUM_PPM+NUM_CHNOUT)
putsStrIdx(x, y, STR_CH, idx - (NUM_STICKS+NUM_POTS+2+3+NUM_PPM), att); putsStrIdx(x, y, STR_CH, idx - (NUM_STICKS+NUM_POTS+NUM_ROTARY_ENCODERS+2+3+NUM_PPM), att);
else else
lcd_putsiAtt(x, y, STR_VTELEMCHNS, idx-(NUM_STICKS+NUM_POTS+2+3+NUM_PPM+NUM_CHNOUT), att); lcd_putsiAtt(x, y, STR_VTELEMCHNS, idx-(NUM_STICKS+NUM_POTS+NUM_ROTARY_ENCODERS+2+3+NUM_PPM+NUM_CHNOUT), att);
} }
void putsChn(uint8_t x, uint8_t y, uint8_t idx, uint8_t att) void putsChn(uint8_t x, uint8_t y, uint8_t idx, uint8_t att)
{ {
if (idx > 0 && idx <= NUM_CHNOUT) if (idx > 0 && idx <= NUM_CHNOUT)
putsChnRaw(x, y, idx+20, att); putsChnRaw(x, y, idx+(NUM_STICKS+NUM_POTS+NUM_ROTARY_ENCODERS+2+3+NUM_PPM), att);
} }
void putsMixerSource(uint8_t x, uint8_t y, uint8_t idx, uint8_t att) void putsMixerSource(uint8_t x, uint8_t y, uint8_t idx, uint8_t att)
{ {
if (idx<=NUM_STICKS+NUM_POTS+2) if (idx<=NUM_STICKS+NUM_POTS+NUM_ROTARY_ENCODERS+2)
putsChnRaw(x, y, idx, att); putsChnRaw(x, y, idx, att);
else if (idx<=NUM_STICKS+NUM_POTS+2+MAX_SWITCH) else if (idx<=NUM_STICKS+NUM_POTS+NUM_ROTARY_ENCODERS+2+MAX_SWITCH)
putsSwitches(x, y, idx-NUM_STICKS-NUM_POTS-2, att); putsSwitches(x, y, idx-NUM_STICKS-NUM_POTS-NUM_ROTARY_ENCODERS-2, att);
else else
putsChnRaw(x, y, idx-MAX_SWITCH, att); putsChnRaw(x, y, idx-MAX_SWITCH, att);
} }
@ -572,6 +572,22 @@ void putsTrimMode(uint8_t x, uint8_t y, uint8_t phase, uint8_t idx, uint8_t att)
} }
} }
#if defined(PCBV4)
void putsRotaryEncoderMode(uint8_t x, uint8_t y, uint8_t phase, uint8_t idx, uint8_t att)
{
int16_t v = phaseaddress(phase)->rotaryEncoders[idx];
if (v > ROTARY_ENCODER_MAX) {
uint8_t p = v - ROTARY_ENCODER_MAX - 1;
if (p >= phase) p++;
lcd_putcAtt(x, y, '0'+p, att);
}
else {
lcd_putcAtt(x, y, 'A'+idx, att);
}
}
#endif
#ifdef PCBARM #ifdef PCBARM
// LCD i/o pins // LCD i/o pins
@ -819,14 +835,16 @@ void refreshDisplay()
} }
pioptr->PIO_SODR = LCD_CS1; // Deselect LCD pioptr->PIO_SODR = LCD_CS1; // Deselect LCD
} }
pioptr->PIO_ODSR = 0xFF ; // Drive lines high
#ifdef REVB #ifdef REVB
pioptr->PIO_ODR = 0x0000003AL; // Set bits 1, 3, 4, 5 input pioptr->PIO_PUER = 0x0000003AL ; // Set bits 1, 3, 4, 5 with pullups
pioptr->PIO_PUER = 0x0000003AL;// Set bits 1, 3, 4, 5 with pullups pioptr->PIO_ODR = 0x0000003AL ; // Set bits 1, 3, 4, 5 input
#else #else
pioptr->PIO_ODR = 0x0000003CL; // Set bits 2, 3, 4, 5 input pioptr->PIO_PUER = 0x0000003CL ; // Set bits 2, 3, 4, 5 with pullups
pioptr->PIO_PUER = 0x0000003CL; // Set bits 2, 3, 4, 5 with pullups pioptr->PIO_ODR = 0x0000003CL ; // Set bits 2, 3, 4, 5 input
#endif #endif
pioptr->PIO_ODSR = 0 ; // Drive D0 low pioptr->PIO_ODSR = 0xFE ; // Drive D0 low
} }
#endif #endif

View file

@ -106,6 +106,9 @@ extern void putsFlightPhase(uint8_t x, uint8_t y, int8_t idx, uint8_t att=0);
extern void putsCurve(uint8_t x, uint8_t y, int8_t idx, uint8_t att=0); extern void putsCurve(uint8_t x, uint8_t y, int8_t idx, uint8_t att=0);
extern void putsTmrMode(uint8_t x, uint8_t y, int8_t mode, uint8_t att); extern void putsTmrMode(uint8_t x, uint8_t y, int8_t mode, uint8_t att);
extern void putsTrimMode(uint8_t x, uint8_t y, uint8_t phase, uint8_t idx, uint8_t att); extern void putsTrimMode(uint8_t x, uint8_t y, uint8_t phase, uint8_t idx, uint8_t att);
#if defined(PCBV4)
void putsRotaryEncoderMode(uint8_t x, uint8_t y, uint8_t phase, uint8_t idx, uint8_t att);
#endif
extern void putsChnRaw(uint8_t x,uint8_t y,uint8_t idx1,uint8_t att); extern void putsChnRaw(uint8_t x,uint8_t y,uint8_t idx1,uint8_t att);
extern void putsChn(uint8_t x,uint8_t y,uint8_t idx1,uint8_t att); extern void putsChn(uint8_t x,uint8_t y,uint8_t idx1,uint8_t att);
@ -133,6 +136,7 @@ inline void lcd_square(uint8_t x, uint8_t y, uint8_t w, uint8_t att=0) { lcd_rec
lcd_vline(xx,yy-ww/2,ww); \ lcd_vline(xx,yy-ww/2,ww); \
lcd_hline(xx-ww/2,yy,ww); lcd_hline(xx-ww/2,yy,ww);
// TODO optimization here!!!
#define V_BAR(xx,yy,ll) \ #define V_BAR(xx,yy,ll) \
lcd_vline(xx-1,yy-ll,ll); \ lcd_vline(xx-1,yy-ll,ll); \
lcd_vline(xx ,yy-ll,ll); \ lcd_vline(xx ,yy-ll,ll); \

View file

@ -179,7 +179,7 @@ void menuMainView(uint8_t event)
{ {
uint8_t phase = getFlightPhase(); uint8_t phase = getFlightPhase();
lcd_putsnAtt(6*FW+2, 2*FH, g_model.phaseData[phase].name, sizeof(g_model.phaseData[phase].name), ZCHAR); lcd_putsnAtt(6*FW, 2*FH, g_model.phaseData[phase].name, sizeof(g_model.phaseData[phase].name), ZCHAR);
uint8_t att = (g_vbat100mV < g_eeGeneral.vBatWarn ? BLINK|INVERS : 0) | DBLSIZE; uint8_t att = (g_vbat100mV < g_eeGeneral.vBatWarn ? BLINK|INVERS : 0) | DBLSIZE;
putsModelName(2*FW-2, 0*FH, g_model.name, g_eeGeneral.currModel, DBLSIZE); putsModelName(2*FW-2, 0*FH, g_model.name, g_eeGeneral.currModel, DBLSIZE);
@ -289,8 +289,19 @@ void menuMainView(uint8_t event)
for (uint8_t i=0; i<8; i++) { for (uint8_t i=0; i<8; i++) {
int16_t val = g_chans512[8+i]; int16_t val = g_chans512[8+i];
int8_t len = limit((int16_t)0, (int16_t)(((val+1024) * BAR_HEIGHT) / 2048), (int16_t)BAR_HEIGHT); int8_t len = limit((int16_t)0, (int16_t)(((val+1024) * BAR_HEIGHT) / 2048), (int16_t)BAR_HEIGHT);
#if defined(PCBV4)
V_BAR(SCREEN_WIDTH/2-5*3+5+i*5, SCREEN_HEIGHT-8, len)
#else
V_BAR(SCREEN_WIDTH/2-5*4+2+i*5, SCREEN_HEIGHT-8, len) V_BAR(SCREEN_WIDTH/2-5*4+2+i*5, SCREEN_HEIGHT-8, len)
#endif
} }
#if defined(PCBV4)
for (uint8_t i=0; i<NUM_ROTARY_ENCODERS; i++) {
int16_t val = getRotaryEncoder(i);
int8_t len = limit((int16_t)0, (int16_t)(((val+1024) * BAR_HEIGHT) / 2048), (int16_t)BAR_HEIGHT);
V_BAR(SCREEN_WIDTH/2-5*6+5+i*5, SCREEN_HEIGHT-8, len)
}
#endif
for (uint8_t i=0; i<12; i++) { for (uint8_t i=0; i<12; i++) {
if ((i%6) < 3) lcd_puts(i<6 ? 2*FW-2 : 16*FW-2, (i%3)*FH+4*FH, STR_SW); if ((i%6) < 3) lcd_puts(i<6 ? 2*FW-2 : 16*FW-2, (i%3)*FH+4*FH, STR_SW);
lcd_putcAtt((i<6 ? 2*FW-2 : 16*FW-2) + 2 * FW + ((i%6) < 3 ? 0 : FW), (i%3)*FH+4*FH, i<9 ? '1'+i : 'A'+i-9, getSwitch(10+i, 0) ? INVERS : 0); lcd_putcAtt((i<6 ? 2*FW-2 : 16*FW-2) + 2 * FW + ((i%6) < 3 ? 0 : FW), (i%3)*FH+4*FH, i<9 ? '1'+i : 'A'+i-9, getSwitch(10+i, 0) ? INVERS : 0);

View file

@ -594,7 +594,13 @@ void menuProcPhaseOne(uint8_t event)
PhaseData *phase = phaseaddress(s_currIdx); PhaseData *phase = phaseaddress(s_currIdx);
putsFlightPhase(13*FW, 0, s_currIdx+1, 0); putsFlightPhase(13*FW, 0, s_currIdx+1, 0);
SUBMENU(STR_MENUFLIGHTPHASE, (s_currIdx==0 ? 3 : 5), {ZCHAR|(sizeof(phase->name)-1), 0, 3, 0/*, 0*/}); #if defined(PCBV4)
#define MAX_TRIM_LINE 5
#else
#define MAX_TRIM_LINE 3
#endif
SUBMENU(STR_MENUFLIGHTPHASE, (s_currIdx==0 ? 3 : 5), {ZCHAR|(sizeof(phase->name)-1), 0, MAX_TRIM_LINE, 0/*, 0*/});
int8_t sub = m_posVert; int8_t sub = m_posVert;
@ -625,6 +631,20 @@ void menuProcPhaseOne(uint8_t event)
} }
} }
} }
#if defined(PCBV4)
for (uint8_t t=0; t<NUM_ROTARY_ENCODERS; t++) {
putsRotaryEncoderMode((14+t)*FW+2, y, s_currIdx, t, (attr && m_posHorz==4+t) ? ((s_editMode>0) ? BLINK|INVERS : INVERS) : 0);
if (attr && m_posHorz==4+t && ((s_editMode>0) || p1valdiff)) {
int16_t v = phaseaddress(s_currIdx)->rotaryEncoders[t];
if (v < ROTARY_ENCODER_MAX) v = ROTARY_ENCODER_MAX;
v = checkIncDec(event, v, ROTARY_ENCODER_MAX, ROTARY_ENCODER_MAX+MAX_PHASES-1, EE_MODEL);
if (checkIncDec_Ret) {
if (v == ROTARY_ENCODER_MAX) v = 0;
phaseaddress(s_currIdx)->rotaryEncoders[t] = v;
}
}
}
#endif
break; break;
case 3: case 3:
lcd_putsLeft( y, STR_FADEIN); lcd_putsLeft( y, STR_FADEIN);
@ -670,19 +690,32 @@ void menuProcPhasesAll(uint8_t event)
att = i==sub ? INVERS : 0; att = i==sub ? INVERS : 0;
PhaseData *p = phaseaddress(i); PhaseData *p = phaseaddress(i);
putsFlightPhase(0, y, i+1, att); putsFlightPhase(0, y, i+1, att);
lcd_putsnAtt(4*FW, y, p->name, 6, ZCHAR); #if defined PCBV4
#define NAME_OFS (-4)
#define SWITCH_OFS (-FW/2-2)
#define TRIMS_OFS (-FW/2-4)
#else
#define NAME_OFS 0
#define SWITCH_OFS (FW/2)
#define TRIMS_OFS (FW/2)
#endif
lcd_putsnAtt(4*FW+NAME_OFS, y, p->name, 6, ZCHAR);
if (i == 0) { if (i == 0) {
lcd_puts(11*FW+FW/2, y, STR_DEFAULT); lcd_puts(11*FW+SWITCH_OFS, y, STR_DEFAULT);
} }
else { else {
putsSwitches(11*FW+FW/2, y, p->swtch, 0); putsSwitches(11*FW+SWITCH_OFS, y, p->swtch, 0);
for (uint8_t t=0; t<NUM_STICKS; t++) { for (uint8_t t=0; t<NUM_STICKS; t++) {
putsTrimMode((16+t)*FW-FW/2, y, i, t, 0); putsTrimMode((15+t)*FW+TRIMS_OFS, y, i, t, 0);
} }
#if defined PCBV4
for (uint8_t t=0; t<NUM_ROTARY_ENCODERS; t++) {
putsRotaryEncoderMode((19+t)*FW+TRIMS_OFS+2, y, i, t, 0);
}
#endif
} }
if (p->fadeIn) lcd_putc(20*FW+2, y, 'I'); if (p->fadeIn || p->fadeOut)
if (p->fadeOut) lcd_putc(20*FW+2, y, 'O'); lcd_putc(20*FW+2, y, (p->fadeIn && p->fadeOut) ? '*' : (p->fadeIn ? 'I' : 'O'));
if (p->fadeIn && p->fadeOut) lcd_putc(20*FW+2, y, '*');
} }
att = (sub==MAX_PHASES && !trimsCheckTimer) ? INVERS : 0; att = (sub==MAX_PHASES && !trimsCheckTimer) ? INVERS : 0;

View file

@ -156,6 +156,10 @@ enum MixSources {
MIXSRC_P1, MIXSRC_P1,
MIXSRC_P2, MIXSRC_P2,
MIXSRC_P3, MIXSRC_P3,
#if defined(PCBV4)
MIXSRC_RE1,
MIXSRC_RE2,
#endif
MIXSRC_MAX , MIXSRC_MAX ,
MIXSRC_3POS, MIXSRC_3POS,
MIXSRC_THR, MIXSRC_THR,
@ -364,13 +368,25 @@ PACK(typedef struct t_SwashRingData { // Swash Ring data
#define TRIM_MAX 125 #define TRIM_MAX 125
#define TRIM_MIN (-TRIM_MAX) #define TRIM_MIN (-TRIM_MAX)
#if defined(PCBV4)
#define NUM_ROTARY_ENCODERS 2
#define ROTARY_ENCODER_MAX 1024
#else
#define NUM_ROTARY_ENCODERS 0
#endif
PACK(typedef struct t_PhaseData { PACK(typedef struct t_PhaseData {
// TODO perhaps not a so good idea to have 10bits trims instead of 16bits ...
int8_t trim[4]; // -500..500 => trim value, 501 => use trim of phase 0, 502, 503, 504 => use trim of phases 1|2|3|4 instead int8_t trim[4]; // -500..500 => trim value, 501 => use trim of phase 0, 502, 503, 504 => use trim of phases 1|2|3|4 instead
int8_t trim_ext:8; // 2 less significant extra bits per trim (10bits trims) int8_t trim_ext:8; // 2 less significant extra bits per trim (10bits trims)
int8_t swtch; // swtch of phase[0] is not used int8_t swtch; // swtch of phase[0] is not used
char name[6]; char name[6];
uint8_t fadeIn:4; uint8_t fadeIn:4;
uint8_t fadeOut:4; uint8_t fadeOut:4;
#if defined(PCBV4)
int16_t rotaryEncoders[NUM_ROTARY_ENCODERS];
#endif
}) PhaseData; }) PhaseData;
#define MAX_MODELS 16 #define MAX_MODELS 16

View file

@ -50,8 +50,10 @@ gtime_t g_unixTime; // Global date/time register, incremented each second in per
EEGeneral g_eeGeneral; EEGeneral g_eeGeneral;
ModelData g_model; ModelData g_model;
#if !defined(PCBARM)
uint8_t g_tmr1Latency_max; uint8_t g_tmr1Latency_max;
uint8_t g_tmr1Latency_min; uint8_t g_tmr1Latency_min;
#endif
uint16_t g_timeMain; uint16_t g_timeMain;
#ifdef DEBUG #ifdef DEBUG
uint16_t g_time_per10; uint16_t g_time_per10;
@ -392,11 +394,15 @@ int16_t ex_chans[NUM_CHNOUT] = {0}; // Outputs (before LIMITS) of the last perMa
#ifdef HELI #ifdef HELI
int16_t cyc_anas[3] = {0}; int16_t cyc_anas[3] = {0};
#endif #endif
int16_t getValue(uint8_t i) int16_t getValue(uint8_t i)
{ {
/*srcRaw is shifted +1!*/ /*srcRaw is shifted +1!*/
if(i<NUM_STICKS+NUM_POTS) return calibratedStick[i]; if(i<NUM_STICKS+NUM_POTS) return calibratedStick[i];
#if defined(PCBV4)
else if(i<NUM_STICKS+NUM_POTS+NUM_ROTARY_ENCODERS) return getRotaryEncoder(i-(NUM_STICKS+NUM_POTS));
#endif
else if(i<MIXSRC_MAX) return 1024; else if(i<MIXSRC_MAX) return 1024;
else if(i<MIXSRC_3POS) return (keyState(SW_ID0) ? -1024 : (keyState(SW_ID1) ? 0 : 1024)); else if(i<MIXSRC_3POS) return (keyState(SW_ID0) ? -1024 : (keyState(SW_ID1) ? 0 : 1024));
else if(i<MIXSRC_3POS+3) else if(i<MIXSRC_3POS+3)
@ -615,6 +621,35 @@ uint8_t getTrimFlightPhase(uint8_t phase, uint8_t idx)
return 0; return 0;
} }
#if defined(PCBV4)
uint8_t s_perOut_flight_phase;
uint8_t getRotaryEncoderFlightPhase(uint8_t idx)
{
uint8_t phase = s_perOut_flight_phase;
for (uint8_t i=0; i<MAX_PHASES; i++) {
if (phase == 0) return 0;
int16_t value = phaseaddress(phase)->rotaryEncoders[idx];
if (value <= ROTARY_ENCODER_MAX) return phase;
uint8_t result = value-ROTARY_ENCODER_MAX-1;
if (result >= phase) result++;
phase = result;
}
return 0;
}
int16_t getRotaryEncoder(uint8_t idx)
{
return phaseaddress(getRotaryEncoderFlightPhase(idx))->rotaryEncoders[idx];
}
void incRotaryEncoder(uint8_t idx, int8_t inc)
{
phaseaddress(getRotaryEncoderFlightPhase(idx))->rotaryEncoders[idx] += inc;
}
#endif
void clearKeyEvents() void clearKeyEvents()
{ {
#ifdef SIMU #ifdef SIMU
@ -674,6 +709,8 @@ void doSplash()
if(keyDown() || (tsum!=inacSum)) return; //wait for key release if(keyDown() || (tsum!=inacSum)) return; //wait for key release
if (check_power()) return; // Usb on or power off
checkBacklight(); checkBacklight();
} }
} }
@ -785,11 +822,9 @@ void alert(const pm_char * s)
sleep(1/*ms*/); sleep(1/*ms*/);
#endif #endif
#if defined(PCBARM)
if (check_power()) return; // Usb on or power off if (check_power()) return; // Usb on or power off
#endif
if(keyDown()) return; // wait for key release if (keyDown()) return; // wait for key release
checkBacklight(); checkBacklight();
@ -909,6 +944,10 @@ uint16_t anaIn(uint8_t chan)
// Google Translate (German): // if table already, then it must also be worthwhile // Google Translate (German): // if table already, then it must also be worthwhile
#if defined(PCBARM) #if defined(PCBARM)
static const uint8_t crossAna[]={1,5,7,0,4,6,2,3,8}; static const uint8_t crossAna[]={1,5,7,0,4,6,2,3,8};
if ( chan == 8 ) {
return Current_analogue ;
}
#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 #endif
@ -1194,11 +1233,16 @@ uint8_t evalSticks(uint8_t phase)
} }
#endif #endif
for (uint8_t i=0; i<NUM_STICKS+NUM_POTS; i++) { for (uint8_t i=0; i<NUM_STICKS+NUM_POTS+NUM_ROTARY_ENCODERS; i++) {
// normalization [0..2048] -> [-1024..1024] // normalization [0..2048] -> [-1024..1024]
uint8_t ch = (i < NUM_STICKS ? CONVERT_MODE(i+1) - 1 : i); uint8_t ch = (i < NUM_STICKS ? CONVERT_MODE(i+1) - 1 : i);
#if defined(PCBV4)
int16_t v = ((i < NUM_STICKS+NUM_POTS) ? anaIn(i) : getRotaryEncoder(i-(NUM_STICKS+NUM_POTS)));
#else
int16_t v = anaIn(i); int16_t v = anaIn(i);
#endif
#ifndef SIMU #ifndef SIMU
v -= g_eeGeneral.calibMid[i]; v -= g_eeGeneral.calibMid[i];
@ -1213,7 +1257,9 @@ uint8_t evalSticks(uint8_t phase)
if (g_eeGeneral.throttleReversed && ch==THR_STICK) if (g_eeGeneral.throttleReversed && ch==THR_STICK)
v = -v; v = -v;
calibratedStick[ch] = v; //for show in expo if (i < NUM_STICKS+NUM_POTS)
calibratedStick[ch] = v; //for show in expo
uint8_t tmp = (uint16_t)abs(v) / 16; uint8_t tmp = (uint16_t)abs(v) / 16;
if (tmp <= 1) anaCenter |= (tmp==0 ? 1<<ch : bpanaCenter & (1<<ch)); if (tmp <= 1) anaCenter |= (tmp==0 ? 1<<ch : bpanaCenter & (1<<ch));
@ -1338,6 +1384,10 @@ void evalFunctions()
void perOut(uint8_t phase) void perOut(uint8_t phase)
{ {
#if defined(PCBV4)
s_perOut_flight_phase = phase;
#endif
uint8_t anaCenter = evalSticks(phase); uint8_t anaCenter = evalSticks(phase);
if (s_perout_mode == e_perout_mode_normal) { if (s_perout_mode == e_perout_mode_normal) {
@ -1595,11 +1645,6 @@ char userDataDisplayBuf[TELEM_SCREEN_BUFFER_SIZE];
#define TIME_TO_WRITE s_eeDirtyMsk #define TIME_TO_WRITE s_eeDirtyMsk
#endif #endif
void checkFlashOnBeep()
{
if(g_eeGeneral.flashBeep) g_LightOffCounter = FLASH_DURATION;
}
int32_t sum_chans512[NUM_CHNOUT] = {0}; int32_t sum_chans512[NUM_CHNOUT] = {0};
void perMain() void perMain()
{ {
@ -1691,19 +1736,19 @@ void perMain()
if (!tick10ms) return; //make sure the rest happen only every 10ms. if (!tick10ms) return; //make sure the rest happen only every 10ms.
uint16_t val; int16_t val;
if (g_model.thrTraceSrc == 0) { if (g_model.thrTraceSrc == 0) {
val = calibratedStick[THR_STICK]; // get throttle channel value val = calibratedStick[THR_STICK]; // get throttle channel value
val = (g_eeGeneral.throttleReversed ? RESX-val : val+RESX);
} }
else if (g_model.thrTraceSrc > NUM_POTS) { else if (g_model.thrTraceSrc > NUM_POTS) {
val = RESX + g_chans512[g_model.thrTraceSrc-NUM_POTS-1]; val = g_chans512[g_model.thrTraceSrc-NUM_POTS-1];
} }
else { else {
val = RESX + calibratedStick[g_model.thrTraceSrc+NUM_STICKS-1]; val = calibratedStick[g_model.thrTraceSrc+NUM_STICKS-1];
} }
val += RESX;
val /= (RESX/16); // calibrate it val /= (RESX/16); // calibrate it
// Throttle trace start // Throttle trace start
@ -1916,7 +1961,7 @@ void perMain()
uint8_t evt = getEvent(); uint8_t evt = getEvent();
evt = checkTrim(evt); evt = checkTrim(evt);
// TODO port lightOnStickMove from er9x // TODO port lightOnStickMove from er9x + flash saving, call checkBacklight()
if(g_LightOffCounter) g_LightOffCounter--; if(g_LightOffCounter) g_LightOffCounter--;
if(evt) g_LightOffCounter = g_eeGeneral.lightAutoOff*500; // on keypress turn the light on 5*100 if(evt) g_LightOffCounter = g_eeGeneral.lightAutoOff*500; // on keypress turn the light on 5*100
@ -1925,6 +1970,10 @@ void perMain()
else else
BACKLIGHT_OFF; BACKLIGHT_OFF;
#if defined(PCBARM) && defined(FRSKY)
check_frsky();
#endif
g_menuStack[g_menuStackPtr](evt); g_menuStack[g_menuStackPtr](evt);
refreshDisplay(); refreshDisplay();
@ -2160,7 +2209,9 @@ extern uint16_t g_timeMain;
Used to transmit FrSky data packets and DSM2 protocol Used to transmit FrSky data packets and DSM2 protocol
*/ */
#if defined (FRSKY) // TODO serial_arm and serial_avr
#if defined (FRSKY) && !defined(PCBARM)
FORCEINLINE void FRSKY_USART0_vect() FORCEINLINE void FRSKY_USART0_vect()
{ {
if (frskyTxBufferCount > 0) { if (frskyTxBufferCount > 0) {
@ -2172,7 +2223,7 @@ FORCEINLINE void FRSKY_USART0_vect()
} }
#endif #endif
#if defined (DSM2_SERIAL) #if defined (DSM2_SERIAL) && !defined(PCBARM)
FORCEINLINE void DSM2_USART0_vect() FORCEINLINE void DSM2_USART0_vect()
{ {
UDR0 = *((uint16_t*)pulses2MHzRPtr); UDR0 = *((uint16_t*)pulses2MHzRPtr);
@ -2184,7 +2235,7 @@ FORCEINLINE void DSM2_USART0_vect()
} }
#endif #endif
#ifndef SIMU #if !defined(SIMU) && !defined(PCBARM)
#if defined (FRSKY) or defined(DSM2_SERIAL) #if defined (FRSKY) or defined(DSM2_SERIAL)
ISR(USART0_UDRE_vect) ISR(USART0_UDRE_vect)
{ {
@ -2305,23 +2356,23 @@ volatile uint8_t g_rotenc[2] = {0};
ISR(INT2_vect) ISR(INT2_vect)
{ {
uint8_t input = PIND & 0b00001100; uint8_t input = PIND & 0b00001100;
if (input == 0 || input == 0b00001100) g_rotenc[0]--; if (input == 0 || input == 0b00001100) incRotaryEncoder(0, -1);
} }
ISR(INT3_vect) ISR(INT3_vect)
{ {
uint8_t input = PIND & 0b00001100; uint8_t input = PIND & 0b00001100;
if (input == 0 || input == 0b00001100) g_rotenc[0]++; if (input == 0 || input == 0b00001100) incRotaryEncoder(0, +1);
} }
ISR(INT5_vect) ISR(INT5_vect)
{ {
uint8_t input = PINE & 0b01100000; uint8_t input = PINE & 0b01100000;
if (input == 0 || input == 0b01100000) g_rotenc[1]++; if (input == 0 || input == 0b01100000) incRotaryEncoder(1, +1);
} }
ISR(INT6_vect) ISR(INT6_vect)
{ {
uint8_t input = PINE & 0b01100000; uint8_t input = PINE & 0b01100000;
if (input == 0 || input == 0b01100000) g_rotenc[1]--; if (input == 0 || input == 0b01100000) incRotaryEncoder(1, -1);
} }
#endif #endif
@ -2474,21 +2525,16 @@ int main(void)
TCCR4B = (1 << WGM42) | (3<<CS40); // CTC OCR1A, 16MHz / 64 (4us ticks) TCCR4B = (1 << WGM42) | (3<<CS40); // CTC OCR1A, 16MHz / 64 (4us ticks)
#endif #endif
#if !defined(PCBARM)
startPulses();
#endif
// TODO init_main_ppm( 3000, 1 ) ; // Default for now, initial period 1.5 mS, output on
#if defined(PCBARM) #if defined(PCBARM)
start_ppm_capture(); start_ppm_capture();
// TODO inside startPulses? // TODO inside startPulses?
#endif #endif
// FrSky testing serial receive startPulses();
// TODO startPdcUsartReceive() ;
wdt_enable(WDTO_500MS); if (check_power() != e_power_usb) {
wdt_enable(WDTO_500MS);
}
#if defined(PCBARM) #if defined(PCBARM)
register uint32_t shutdown_state = 0; register uint32_t shutdown_state = 0;
@ -2554,6 +2600,8 @@ int main(void)
lcd_clear() ; lcd_clear() ;
displayPopup(STR_SHUTDOWN); displayPopup(STR_SHUTDOWN);
eeCheck(true); eeCheck(true);
soft_power_off(); // Only turn power off if necessary
#endif
#if defined(PCBARM) #if defined(PCBARM)
if (shutdown_state == e_power_usb) { if (shutdown_state == e_power_usb) {
@ -2564,14 +2612,6 @@ int main(void)
refreshDisplay() ; refreshDisplay() ;
usb_mode(); usb_mode();
} }
#ifdef REVB
else
#endif
#endif
{
soft_power_off(); // Only turn power off if necessary
}
#endif #endif
} }

View file

@ -60,14 +60,14 @@ typedef const uint16_t pm_uint16_t;
typedef const uint8_t pm_uint8_t; typedef const uint8_t pm_uint8_t;
typedef const int16_t pm_int16_t; typedef const int16_t pm_int16_t;
typedef const int8_t pm_int8_t; typedef const int8_t pm_int8_t;
#define wdt_reset()
#define pgm_read_byte(address_short) (*(uint8_t*)(address_short)) #define pgm_read_byte(address_short) (*(uint8_t*)(address_short))
#define PSTR(adr) adr #define PSTR(adr) adr
#define PROGMEM #define PROGMEM
#define pgm_read_adr(x) *(x) #define pgm_read_adr(x) *(x)
#define cli() #define cli()
#define sei() #define sei()
#define wdt_enable(x) #define wdt_enable(x) WDT->WDT_MR = 0x3FFF2FFF
#define wdt_reset() WDT->WDT_CR = 0xA5000001
extern void board_init(); extern void board_init();
#else #else
#include <avr/io.h> #include <avr/io.h>
@ -87,8 +87,10 @@ extern void board_init();
#if defined(PCBARM) #if defined(PCBARM)
#include "eeprom_arm.h" #include "eeprom_arm.h"
#include "pulses_arm.h"
#else #else
#include "eeprom_avr.h" #include "eeprom_avr.h"
#include "pulses_avr.h"
#endif #endif
#include "lcd.h" #include "lcd.h"
@ -401,7 +403,7 @@ extern Key keys[NUM_KEYS];
#define NUM_TELEMETRY TELEM_TM2 #define NUM_TELEMETRY TELEM_TM2
#endif #endif
#define NUM_XCHNRAW (NUM_STICKS+NUM_POTS+1/*MAX*/+1/*ID3*/+3/*CYC1-CYC3*/+NUM_PPM+NUM_CHNOUT) #define NUM_XCHNRAW (NUM_STICKS+NUM_POTS+NUM_ROTARY_ENCODERS+1/*MAX*/+1/*ID3*/+3/*CYC1-CYC3*/+NUM_PPM+NUM_CHNOUT)
#define NUM_XCHNCSW (NUM_XCHNRAW+NUM_TELEMETRY) #define NUM_XCHNCSW (NUM_XCHNRAW+NUM_TELEMETRY)
#define NUM_XCHNMIX (NUM_XCHNRAW+MAX_SWITCH) #define NUM_XCHNMIX (NUM_XCHNRAW+MAX_SWITCH)
@ -426,27 +428,26 @@ extern Key keys[NUM_KEYS];
#define TRM_BASE TRM_LH_DWN #define TRM_BASE TRM_LH_DWN
//#define _MSK_KEY_FIRST (_MSK_KEY_REPT|0x20) #define _MSK_KEY_DBL 0x10
//#define EVT_KEY_GEN_BREAK(key) ((key)|0x20) #define _MSK_KEY_BREAK 0x20
#define _MSK_KEY_REPT 0x40 #define _MSK_KEY_REPT 0x40
#define _MSK_KEY_DBL 0x10 #define _MSK_KEY_LONG 0x80
#define IS_KEY_BREAK(key) (((key)&0xf0) == 0x20) #define IS_KEY_BREAK(key) (((key)&0xf0) == 0x20)
#define EVT_KEY_BREAK(key) ((key)| 0x20) #define EVT_KEY_BREAK(key) ((key)|_MSK_KEY_BREAK)
#define EVT_KEY_FIRST(key) ((key)| _MSK_KEY_REPT|0x20) #define EVT_KEY_FIRST(key) ((key)|_MSK_KEY_REPT|0x20)
#define EVT_KEY_REPT(key) ((key)| _MSK_KEY_REPT ) #define EVT_KEY_REPT(key) ((key)|_MSK_KEY_REPT)
#define EVT_KEY_LONG(key) ((key)|0x80) #define EVT_KEY_LONG(key) ((key)|_MSK_KEY_LONG)
#define EVT_KEY_DBL(key) ((key)|_MSK_KEY_DBL) #define EVT_KEY_DBL(key) ((key)|_MSK_KEY_DBL)
//#define EVT_KEY_DBL(key) ((key)|0x10) #define EVT_ENTRY (0xff - _MSK_KEY_REPT)
#define EVT_ENTRY (0xff - _MSK_KEY_REPT) #define EVT_ENTRY_UP (0xfe - _MSK_KEY_REPT)
#define EVT_ENTRY_UP (0xfe - _MSK_KEY_REPT) #define EVT_KEY_MASK (0x0f)
#define EVT_KEY_MASK 0x0f
#define HEART_TIMER2Mhz 1 #define HEART_TIMER_PULSES 1
#define HEART_TIMER10ms 2 #define HEART_TIMER10ms 2
extern uint8_t heartbeat;
#define MAX_ALERT_TIME 60 #define MAX_ALERT_TIME 60
extern uint8_t heartbeat;
extern uint32_t inacCounter; extern uint32_t inacCounter;
#if defined(PXX) #if defined(PXX)
@ -467,19 +468,20 @@ void putEvent(uint8_t evt);
uint8_t keyDown(); uint8_t keyDown();
#if defined(PCBARM)
uint32_t keyState(EnumKeys enuk);
enum PowerState { enum PowerState {
e_power_on, e_power_on,
e_power_usb, e_power_usb,
e_power_off e_power_off
}; };
#if defined(PCBARM)
uint32_t keyState(EnumKeys enuk);
uint32_t check_power(); uint32_t check_power();
#else #else
#if defined(PCBV4) #if defined(PCBV4)
uint8_t check_power(); uint8_t check_power();
#else #else
#define check_power() (0) #define check_power() (e_power_on)
#endif #endif
bool keyState(EnumKeys enuk); bool keyState(EnumKeys enuk);
@ -488,15 +490,10 @@ void readKeysAndTrims();
uint16_t evalChkSum(); uint16_t evalChkSum();
/// Gibt Alarm Maske auf lcd aus.
/// Die Maske wird so lange angezeigt bis eine beliebige Taste gedrueckt wird.
extern void alert(const pm_char * s); extern void alert(const pm_char * s);
extern void message(const pm_char *title, const pm_char *s, const pm_char *t, const char *last); extern void message(const pm_char *title, const pm_char *s, const pm_char *t, const char *last);
/// periodisches Hauptprogramm
void perMain(); void perMain();
/// Bearbeitet alle zeitkritischen Jobs.
/// wie z.B. einlesen aller Eingaenge, Entprellung, Key-Repeat..
void per10ms(); void per10ms();
int16_t getValue(uint8_t i); int16_t getValue(uint8_t i);
@ -508,6 +505,12 @@ extern int16_t getRawTrimValue(uint8_t phase, uint8_t idx);
extern int16_t getTrimValue(uint8_t phase, uint8_t idx); extern int16_t getTrimValue(uint8_t phase, uint8_t idx);
extern void setTrimValue(uint8_t phase, uint8_t idx, int16_t trim); extern void setTrimValue(uint8_t phase, uint8_t idx, int16_t trim);
#if defined(PCBV4)
extern uint8_t s_perOut_flight_phase;
int16_t getRotaryEncoder(uint8_t idx);
void incRotaryEncoder(uint8_t idx, int8_t inc);
#endif
extern uint16_t s_timeCumTot; extern uint16_t s_timeCumTot;
extern uint16_t s_timeCumThr; //gewichtete laufzeit in 1/16 sec extern uint16_t s_timeCumThr; //gewichtete laufzeit in 1/16 sec
extern uint16_t s_timeCum16ThrP; //gewichtete laufzeit in 1/16 sec extern uint16_t s_timeCum16ThrP; //gewichtete laufzeit in 1/16 sec
@ -690,14 +693,6 @@ extern inline uint16_t get_tmr10ms()
#define TMR_VAROFS 5 #define TMR_VAROFS 5
void startPulses();
void setupPulses();
void DSM2_Init();
void DSM2_Done();
extern uint8_t *pulses2MHzRPtr;
extern uint8_t *pulses2MHzWPtr;
extern const char stamp1[]; extern const char stamp1[];
extern const char stamp2[]; extern const char stamp2[];
extern const char stamp3[]; extern const char stamp3[];

535
src/pulses_arm.cpp Normal file
View file

@ -0,0 +1,535 @@
/*
* Authors (alphabetical order)
* - Bertrand Songis <bsongis@gmail.com>
* - Bryan J. Rentoul (Gruvin) <gruvin@gmail.com>
* - Cameron Weeks <th9xer@gmail.com>
* - Erez Raviv
* - Jean-Pierre Parisy
* - Karl Szmutny <shadow@privy.de>
* - Michael Blandford
* - Michal Hlavinka
* - Pat Mackenzie
* - Philip Moss
* - Rob Thomson
* - Romolo Manfredini <romolo.manfredini@gmail.com>
* - Thomas Husterer
*
* open9x 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 "open9x.h"
uint8_t Current_protocol ;
uint8_t pxxFlag = 0 ;
uint16_t Pulses[18] = { 2000, 2200, 2400, 2600, 2800, 3000, 3200, 3400, 9000, 0, 0, 0,0,0,0,0,0, 0 } ;
volatile uint32_t Pulses_index = 0 ; // Modified in interrupt routine
uint8_t Bit_pulses[64] ; // Likely more than we need
uint8_t *Pulses2MHzptr ;
// DSM2 control bits
#define DSM2_CHANS 6
#define BIND_BIT 0x80
#define RANGECHECK_BIT 0x20
#define FRANCE_BIT 0x10
#define DSMX_BIT 0x08
#define BAD_DATA 0x47
uint8_t Serial_byte ;
uint8_t Serial_bit_count;
uint8_t Serial_byte_count ;
void setupPulses();
void setupPulsesPPM();
void setupPulsesDsm2(uint8_t chns);
void setupPulsesPXX();
static void init_main_ppm( uint32_t period, uint32_t out_enable )
{
register Pio *pioptr ;
register Pwm *pwmptr ;
// TODO ? perOut(g_chans512, 0) ;
setupPulsesPPM() ;
if ( out_enable )
{
pioptr = PIOA ;
pioptr->PIO_ABCDSR[0] &= ~PIO_PA17 ; // Peripheral C
pioptr->PIO_ABCDSR[1] |= PIO_PA17 ; // Peripheral C
pioptr->PIO_PDR = PIO_PA17 ; // Disable bit A17 Assign to peripheral
}
pwmptr = PWM ;
// PWM3 for PPM output
pwmptr->PWM_CH_NUM[3].PWM_CMR = 0x0000000B ; // CLKA
pwmptr->PWM_CH_NUM[3].PWM_CPDR = period ; // Period in half uS
pwmptr->PWM_CH_NUM[3].PWM_CPDRUPD = period ; // Period in half uS
pwmptr->PWM_CH_NUM[3].PWM_CDTY = 600 ; // Duty in half uS
pwmptr->PWM_CH_NUM[3].PWM_CDTYUPD = 600 ; // Duty in half uS
pwmptr->PWM_ENA = PWM_ENA_CHID3 ; // Enable channel 3
NVIC_EnableIRQ(PWM_IRQn) ;
pwmptr->PWM_IER1 = PWM_IER1_CHID3 ;
}
void disable_main_ppm()
{
register Pio *pioptr ;
pioptr = PIOA ;
pioptr->PIO_PER = PIO_PA17 ; // Assign A17 to PIO
PWM->PWM_IDR1 = PWM_IDR1_CHID3 ;
NVIC_DisableIRQ(PWM_IRQn) ;
}
// Initialise the SSC to allow PXX output.
// TD is on PA17, peripheral A
void init_ssc()
{
register Pio *pioptr ;
register Ssc *sscptr ;
PMC->PMC_PCER0 |= 0x00400000L ; // Enable peripheral clock to SSC
pioptr = PIOA ;
pioptr->PIO_ABCDSR[0] &= ~0x00020000 ; // Peripheral A bit 17
pioptr->PIO_ABCDSR[1] &= ~0x00020000 ; // Peripheral A
pioptr->PIO_PDR = 0x00020000 ; // Assign to peripheral
sscptr = SSC ;
sscptr->SSC_CMR = Master_frequency / (125000*2) ; // 8uS per bit
sscptr->SSC_TCMR = 0 ; // 0000 0000 0000 0000 0000 0000 0000 0000
sscptr->SSC_TFMR = 0x00000027 ; // 0000 0000 0000 0000 0000 0000 1010 0111 (8 bit data, lsb)
sscptr->SSC_CR = SSC_CR_TXEN ;
}
void disable_ssc()
{
register Pio *pioptr ;
register Ssc *sscptr ;
// Revert back to pwm output
pioptr = PIOA ;
pioptr->PIO_PER = 0x00020000L ; // Assign A17 to PIO
sscptr = SSC ;
sscptr->SSC_CR = SSC_CR_TXDIS ;
}
void startPulses()
{
init_main_ppm( 3000, 1 ) ; // Default for now, initial period 1.5 mS, output on
}
void setupPulsesPPM() // Don't enable interrupts through here
{
register Pwm *pwmptr;
pwmptr = PWM;
// Now set up pulses
#define PPM_CENTER 1500*2
int16_t PPM_range = g_model.extendedLimits ? 640 * 2 : 512 * 2; //range of 0.7..1.7msec
//Total frame length = 22.5msec
//each pulse is 0.7..1.7ms long with a 0.3ms stop tail
//The pulse ISR is 2mhz that's why everything is multiplied by 2
uint16_t *ptr;
ptr = Pulses;
uint32_t p = 8 + g_model.ppmNCH * 2; //Channels *2
pwmptr->PWM_CH_NUM[3].PWM_CDTYUPD = (g_model.ppmDelay * 50 + 300) * 2; //Stoplen *2
uint16_t rest = 22500u * 2; //Minimum Framelen=22.5 ms
rest += (int16_t(g_model.ppmFrameLength)) * 1000;
// if(p>9) rest=p*(1720u*2 + q) + 4000u*2; //for more than 9 channels, frame must be longer
for (uint32_t i = 0; i < p; i++) { //NUM_CHNOUT
int16_t v = max((int) min(g_chans512[i], PPM_range),
-PPM_range) + PPM_CENTER;
rest -= (v);
// *ptr++ = q; //moved down two lines
// pulses2MHz[j++] = q;
*ptr++ = v; /* as Pat MacKenzie suggests */
// pulses2MHz[j++] = v - q + 600; /* as Pat MacKenzie suggests */
// *ptr++ = q; //to here
}
// *ptr=q; //reverse these two assignments
// *(ptr+1)=rest;
*ptr = rest;
*(ptr + 1) = 0;
}
void put_serial_bit( uint8_t bit )
{
Serial_byte >>= 1 ;
if ( bit & 1 )
{
Serial_byte |= 0x80 ;
}
if ( ++Serial_bit_count >= 8 )
{
*Pulses2MHzptr++ = Serial_byte ;
Serial_bit_count = 0 ;
Serial_byte_count += 1 ;
}
}
const uint16_t CRCTable[]=
{
0x0000,0x1189,0x2312,0x329b,0x4624,0x57ad,0x6536,0x74bf,
0x8c48,0x9dc1,0xaf5a,0xbed3,0xca6c,0xdbe5,0xe97e,0xf8f7,
0x1081,0x0108,0x3393,0x221a,0x56a5,0x472c,0x75b7,0x643e,
0x9cc9,0x8d40,0xbfdb,0xae52,0xdaed,0xcb64,0xf9ff,0xe876,
0x2102,0x308b,0x0210,0x1399,0x6726,0x76af,0x4434,0x55bd,
0xad4a,0xbcc3,0x8e58,0x9fd1,0xeb6e,0xfae7,0xc87c,0xd9f5,
0x3183,0x200a,0x1291,0x0318,0x77a7,0x662e,0x54b5,0x453c,
0xbdcb,0xac42,0x9ed9,0x8f50,0xfbef,0xea66,0xd8fd,0xc974,
0x4204,0x538d,0x6116,0x709f,0x0420,0x15a9,0x2732,0x36bb,
0xce4c,0xdfc5,0xed5e,0xfcd7,0x8868,0x99e1,0xab7a,0xbaf3,
0x5285,0x430c,0x7197,0x601e,0x14a1,0x0528,0x37b3,0x263a,
0xdecd,0xcf44,0xfddf,0xec56,0x98e9,0x8960,0xbbfb,0xaa72,
0x6306,0x728f,0x4014,0x519d,0x2522,0x34ab,0x0630,0x17b9,
0xef4e,0xfec7,0xcc5c,0xddd5,0xa96a,0xb8e3,0x8a78,0x9bf1,
0x7387,0x620e,0x5095,0x411c,0x35a3,0x242a,0x16b1,0x0738,
0xffcf,0xee46,0xdcdd,0xcd54,0xb9eb,0xa862,0x9af9,0x8b70,
0x8408,0x9581,0xa71a,0xb693,0xc22c,0xd3a5,0xe13e,0xf0b7,
0x0840,0x19c9,0x2b52,0x3adb,0x4e64,0x5fed,0x6d76,0x7cff,
0x9489,0x8500,0xb79b,0xa612,0xd2ad,0xc324,0xf1bf,0xe036,
0x18c1,0x0948,0x3bd3,0x2a5a,0x5ee5,0x4f6c,0x7df7,0x6c7e,
0xa50a,0xb483,0x8618,0x9791,0xe32e,0xf2a7,0xc03c,0xd1b5,
0x2942,0x38cb,0x0a50,0x1bd9,0x6f66,0x7eef,0x4c74,0x5dfd,
0xb58b,0xa402,0x9699,0x8710,0xf3af,0xe226,0xd0bd,0xc134,
0x39c3,0x284a,0x1ad1,0x0b58,0x7fe7,0x6e6e,0x5cf5,0x4d7c,
0xc60c,0xd785,0xe51e,0xf497,0x8028,0x91a1,0xa33a,0xb2b3,
0x4a44,0x5bcd,0x6956,0x78df,0x0c60,0x1de9,0x2f72,0x3efb,
0xd68d,0xc704,0xf59f,0xe416,0x90a9,0x8120,0xb3bb,0xa232,
0x5ac5,0x4b4c,0x79d7,0x685e,0x1ce1,0x0d68,0x3ff3,0x2e7a,
0xe70e,0xf687,0xc41c,0xd595,0xa12a,0xb0a3,0x8238,0x93b1,
0x6b46,0x7acf,0x4854,0x59dd,0x2d62,0x3ceb,0x0e70,0x1ff9,
0xf78f,0xe606,0xd49d,0xc514,0xb1ab,0xa022,0x92b9,0x8330,
0x7bc7,0x6a4e,0x58d5,0x495c,0x3de3,0x2c6a,0x1ef1,0x0f78
};
uint16_t PcmCrc ;
uint8_t PcmOnesCount ;
void crc( uint8_t data )
{
// uint8_t i ;
PcmCrc=(PcmCrc>>8)^(CRCTable[(PcmCrc^data) & 0xFF]);
}
// 8uS/bit 01 = 0, 001 = 1
void putPcmPart( uint8_t value )
{
put_serial_bit( 0 ) ;
if ( value )
{
put_serial_bit( 0 ) ;
}
put_serial_bit( 1 ) ;
}
void putPcmFlush()
{
while ( Serial_bit_count != 0 )
{
put_serial_bit( 1 ) ; // Line idle level
}
}
void putPcmBit( uint8_t bit )
{
if ( bit )
{
PcmOnesCount += 1 ;
putPcmPart( 1 ) ;
}
else
{
PcmOnesCount = 0 ;
putPcmPart( 0 ) ;
}
if ( PcmOnesCount >= 5 )
{
putPcmBit( 0 ) ; // Stuff a 0 bit in
}
}
void putPcmByte( uint8_t byte )
{
uint8_t i ;
crc( byte ) ;
for ( i = 0 ; i < 8 ; i += 1 )
{
putPcmBit( byte & 0x80 ) ;
byte <<= 1 ;
}
}
void putPcmHead()
{
// send 7E, do not CRC
// 01111110
putPcmPart( 0 ) ;
putPcmPart( 1 ) ;
putPcmPart( 1 ) ;
putPcmPart( 1 ) ;
putPcmPart( 1 ) ;
putPcmPart( 1 ) ;
putPcmPart( 1 ) ;
putPcmPart( 0 ) ;
}
void setupPulsesPXX()
{
uint8_t i ;
uint16_t chan ;
uint16_t chan_1 ;
Serial_byte = 0 ;
Serial_bit_count = 0 ;
Serial_byte_count = 0 ;
Pulses2MHzptr = Bit_pulses ;
PcmCrc = 0 ;
PcmOnesCount = 0 ;
putPcmHead( ) ; // sync byte
putPcmByte( g_model.ppmNCH ) ; // putPcmByte( g_model.rxnum ) ; //
putPcmByte( pxxFlag ) ; // First byte of flags
putPcmByte( 0 ) ; // Second byte of flags
pxxFlag = 0; // reset flag after send
for ( i = 0 ; i < 8 ; i += 2 ) // First 8 channels only
{ // Next 8 channels would have 2048 added
chan = g_chans512[i] *3 / 4 + 2250 ;
chan_1 = g_chans512[i+1] *3 / 4 + 2250 ;
// if ( chan > 2047 )
// {
// chan = 2047 ;
// }
// if ( chan_1 > 2047 )
// {
// chan_1 = 2047 ;
// }
putPcmByte( chan ) ; // Low byte of channel
putPcmByte( ( ( chan >> 8 ) & 0x0F ) | ( chan_1 << 4) ) ; // 4 bits each from 2 channels
putPcmByte( chan_1 >> 4 ) ; // High byte of channel
}
chan = PcmCrc ; // get the crc
putPcmByte( chan ) ; // Checksum lo
putPcmByte( chan >> 8 ) ; // Checksum hi
putPcmHead( ) ; // sync byte
putPcmFlush() ;
}
#define BITLEN_DSM2 (8*2) //125000 Baud => 8uS per bit
void sendByteDsm2(uint8_t b) //max 10changes 0 10 10 10 10 1
{
put_serial_bit( 0 ) ; // Start bit
for( uint8_t i=0; i<8; i++) // 8 data Bits
{
put_serial_bit( b & 1 ) ;
b >>= 1 ;
}
put_serial_bit( 1 ) ; // Stop bit
put_serial_bit( 1 ) ; // Stop bit
}
// This is the data stream to send, prepare after 19.5 mS
// Send after 22.5 mS
//static uint8_t *Dsm2_pulsePtr = pulses2MHz.pbyte ;
void setupPulsesDsm2(uint8_t chns)
{
static uint8_t dsmDat[2+6*2]={0xFF,0x00, 0x00,0xAA, 0x05,0xFF, 0x09,0xFF, 0x0D,0xFF, 0x13,0x54, 0x14,0xAA};
uint8_t counter ;
// CSwData &cs = g_model.customSw[NUM_CSW-1];
Serial_byte = 0 ;
Serial_bit_count = 0 ;
Serial_byte_count = 0 ;
Pulses2MHzptr = Bit_pulses ;
// If more channels needed make sure the pulses union/array is large enough
if (dsmDat[0]&BAD_DATA) //first time through, setup header
{
switch(g_model.ppmNCH)
{
case LPXDSM2:
dsmDat[0]= 0x80;
break;
case DSM2only:
dsmDat[0]=0x90;
break;
default:
dsmDat[0]=0x98; //dsmx, bind mode
break;
}
}
if ((dsmDat[0] & BIND_BIT) && (!keyState(SW_Trainer))) dsmDat[0] &= ~BIND_BIT; // clear bind bit if trainer not pulled
// TODO find a way to do that, FUNC SWITCH: if ((!(dsmDat[0] & BIND_BIT)) && getSwitch(MAX_DRSWITCH-1, 0, 0)) dsmDat[0] |= RANGECHECK_BIT; // range check function
// else dsmDat[0] &= ~RANGECHECK_BIT;
dsmDat[1]=g_eeGeneral.currModel+1; //DSM2 Header second byte for model match
for(uint8_t i=0; i<chns; i++)
{
uint16_t pulse = limit(0, ((g_chans512[i]*13)>>5)+512,1023);
dsmDat[2+2*i] = (i<<2) | ((pulse>>8)&0x03);
dsmDat[3+2*i] = pulse & 0xff;
}
for ( counter = 0 ; counter < 14 ; counter += 1 )
{
sendByteDsm2(dsmDat[counter]);
}
for ( counter = 0 ; counter < 16 ; counter += 1 )
{
put_serial_bit( 1 ) ; // 16 extra stop bits
}
}
extern "C" void PWM_IRQHandler(void)
{
register Pwm *pwmptr;
register Ssc *sscptr;
uint32_t period;
pwmptr = PWM;
if (pwmptr->PWM_ISR1 & PWM_ISR1_CHID3) {
switch (Current_protocol) // Use the current, don't switch until set_up_pulses
{
case PROTO_PPM:
case PROTO_PPM16:
pwmptr->PWM_CH_NUM[3].PWM_CPDRUPD = Pulses[Pulses_index++]; // Period in half uS
if (Pulses[Pulses_index] == 0) {
Pulses_index = 0;
setupPulses();
}
break;
case PROTO_PXX:
// Alternate periods of 15.5mS and 2.5 mS
period = pwmptr->PWM_CH_NUM[3].PWM_CPDR;
if (period == 5000) // 2.5 mS
{
period = 15500 * 2;
}
else {
period = 5000;
}
pwmptr->PWM_CH_NUM[3].PWM_CPDRUPD = period; // Period in half uS
if (period != 5000) // 2.5 mS
{
setupPulses();
}
else {
// Kick off serial output here
sscptr = SSC;
sscptr->SSC_TPR = (uint32_t) Bit_pulses;
sscptr->SSC_TCR = Serial_byte_count;
sscptr->SSC_PTCR = SSC_PTCR_TXTEN; // Start transfers
}
break;
case PROTO_DSM2:
// Alternate periods of 19.5mS and 2.5 mS
period = pwmptr->PWM_CH_NUM[3].PWM_CPDR;
if (period == 5000) // 2.5 mS
{
period = 19500 * 2;
}
else {
period = 5000;
}
pwmptr->PWM_CH_NUM[3].PWM_CPDRUPD = period; // Period in half uS
if (period != 5000) // 2.5 mS
{
setupPulses();
}
else {
// Kick off serial output here
sscptr = SSC;
sscptr->SSC_TPR = (uint32_t) Bit_pulses;
sscptr->SSC_TCR = Serial_byte_count;
sscptr->SSC_PTCR = SSC_PTCR_TXTEN; // Start transfers
}
break;
}
}
}
void setupPulses()
{
heartbeat |= HEART_TIMER_PULSES;
if (Current_protocol != g_model.protocol) {
switch (Current_protocol) { // stop existing protocol hardware
case PROTO_PPM:
disable_main_ppm();
break;
case PROTO_PXX:
disable_ssc();
break;
case PROTO_DSM2:
disable_ssc();
break;
case PROTO_PPM16:
disable_main_ppm();
break;
}
Current_protocol = g_model.protocol;
switch (Current_protocol) { // Start new protocol hardware here
case PROTO_PPM:
init_main_ppm(3000, 1); // Initial period 1.5 mS, output on
break;
case PROTO_PXX:
init_main_ppm(5000, 0); // Initial period 2.5 mS, output off
init_ssc();
break;
case PROTO_DSM2:
init_main_ppm(5000, 0); // Initial period 2.5 mS, output off
init_ssc();
break;
case PROTO_PPM16:
init_main_ppm(3000, 1); // Initial period 1.5 mS, output on
break;
}
}
// Set up output data here
switch (Current_protocol) {
case PROTO_PPM:
setupPulsesPPM(); // Don't enable interrupts through here
break;
case PROTO_PXX:
setupPulsesPXX();
break;
case PROTO_DSM2:
setupPulsesDsm2(6);
break;
case PROTO_PPM16:
setupPulsesPPM(); // Don't enable interrupts through here
break ;
}
}

43
src/pulses_arm.h Normal file
View file

@ -0,0 +1,43 @@
/*
* Authors (alphabetical order)
* - Bertrand Songis <bsongis@gmail.com>
* - Bryan J. Rentoul (Gruvin) <gruvin@gmail.com>
* - Cameron Weeks <th9xer@gmail.com>
* - Erez Raviv
* - Jean-Pierre Parisy
* - Karl Szmutny <shadow@privy.de>
* - Michael Blandford
* - Michal Hlavinka
* - Pat Mackenzie
* - Philip Moss
* - Rob Thomson
* - Romolo Manfredini <romolo.manfredini@gmail.com>
* - Thomas Husterer
*
* open9x 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.
*
*/
#ifndef pulses_arm_h
#define pulses_arm_h
void startPulses();
void disable_main_ppm();
void disable_ssc();
#endif
/*eof*/

View file

@ -33,10 +33,8 @@
#include "open9x.h" #include "open9x.h"
#ifndef PCBARM
// TODO!!!
#if defined(DSM2) #if defined(DSM2)
// DSM2 control bits
#define DSM2_CHANS 6 #define DSM2_CHANS 6
#define BIND_BIT 0x80 #define BIND_BIT 0x80
#define RANGECHECK_BIT 0x20 #define RANGECHECK_BIT 0x20
@ -190,7 +188,7 @@ ISR(TIMER1_COMPA_vect) //2MHz pulse generation
if (dt > g_tmr1Latency_max) g_tmr1Latency_max = dt; if (dt > g_tmr1Latency_max) g_tmr1Latency_max = dt;
if (dt < g_tmr1Latency_min) g_tmr1Latency_min = dt; if (dt < g_tmr1Latency_min) g_tmr1Latency_min = dt;
heartbeat |= HEART_TIMER2Mhz; heartbeat |= HEART_TIMER_PULSES;
} }
#endif #endif
@ -658,7 +656,7 @@ ISR(TIMER1_CAPT_vect) // 2MHz pulse generation
x = *pulses2MHzRPtr++; // Byte size x = *pulses2MHzRPtr++; // Byte size
ICR1 = x ; ICR1 = x ;
if (x > 200) PORTB |= (1<<OUT_B_PPM); // Make sure pulses are the correct way up if (x > 200) PORTB |= (1<<OUT_B_PPM); // Make sure pulses are the correct way up
heartbeat |= HEART_TIMER2Mhz; // TODO why not in TIMER1_COMPB_vect (in setupPulses)? heartbeat |= HEART_TIMER_PULSES; // TODO why not in TIMER1_COMPB_vect (in setupPulses)?
} }
#if defined(PXX) #if defined(PXX)
@ -687,7 +685,7 @@ ISR(TIMER1_COMPB_vect) // PXX main interrupt
*pulses2MHzRPtr = x; *pulses2MHzRPtr = x;
} }
heartbeat |= HEART_TIMER2Mhz; heartbeat |= HEART_TIMER_PULSES;
} }
#endif #endif
@ -795,7 +793,7 @@ ISR(TIMER3_COMPA_vect) //2MHz pulse generation
pulsePol = g_model.pulsePol; pulsePol = g_model.pulsePol;
} }
heartbeat |= HEART_TIMER2Mhz; heartbeat |= HEART_TIMER_PULSES;
} }
ISR(TIMER3_COMPB_vect) //2MHz pulse generation ISR(TIMER3_COMPB_vect) //2MHz pulse generation
@ -831,5 +829,3 @@ void setupPulsesPPM16()
*(ptr+2) = 0; *(ptr+2) = 0;
} }
#endif #endif
#endif

46
src/pulses_avr.h Normal file
View file

@ -0,0 +1,46 @@
/*
* Authors (alphabetical order)
* - Bertrand Songis <bsongis@gmail.com>
* - Bryan J. Rentoul (Gruvin) <gruvin@gmail.com>
* - Cameron Weeks <th9xer@gmail.com>
* - Erez Raviv
* - Jean-Pierre Parisy
* - Karl Szmutny <shadow@privy.de>
* - Michael Blandford
* - Michal Hlavinka
* - Pat Mackenzie
* - Philip Moss
* - Rob Thomson
* - Romolo Manfredini <romolo.manfredini@gmail.com>
* - Thomas Husterer
*
* open9x 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.
*
*/
#ifndef pulses_avr_h
#define pulses_avr_h
void startPulses();
void setupPulses();
void DSM2_Init();
void DSM2_Done();
extern uint8_t *pulses2MHzRPtr;
extern uint8_t *pulses2MHzWPtr;
#endif
/*eof*/

View file

@ -40,9 +40,8 @@ const char *eepromFile = NULL;
FILE *fp = NULL; FILE *fp = NULL;
#if defined(PCBARM) #if defined(PCBARM)
Pio Pioa; Pio Pioa, Piob, Pioc;
Pio Piob; Usart Usart0;
Pio Pioc;
uint32_t eeprom_pointer; uint32_t eeprom_pointer;
char* eeprom_buffer_data; char* eeprom_buffer_data;
volatile int32_t eeprom_buffer_size; volatile int32_t eeprom_buffer_size;

View file

@ -97,6 +97,9 @@ typedef const int8_t pm_int8_t;
extern sem_t eeprom_write_sem; extern sem_t eeprom_write_sem;
#if defined(PCBARM) #if defined(PCBARM)
extern Pio Pioa, Piob, Pioc; extern Pio Pioa, Piob, Pioc;
extern Usart Usart0;
#undef USART0
#define USART0 (&Usart0)
#undef PIOA #undef PIOA
#define PIOA (&Pioa) #define PIOA (&Pioa)
#undef PIOB #undef PIOB
@ -108,6 +111,10 @@ extern char* eeprom_buffer_data;
extern volatile int32_t eeprom_buffer_size; extern volatile int32_t eeprom_buffer_size;
extern bool eeprom_read_operation; extern bool eeprom_read_operation;
extern volatile uint32_t Spi_complete; extern volatile uint32_t Spi_complete;
extern void startPdcUsartReceive() ;
extern uint32_t txPdcUsart( uint8_t *buffer, uint32_t size );
extern uint32_t txPdcPending();
extern void rxPdcUsart( void (*pChProcess)(uint8_t x) );
#else #else
#define PIOA 0 #define PIOA 0
#define PIOB 0 #define PIOB 0
@ -236,6 +243,9 @@ extern volatile uint32_t Spi_complete;
#define WGM10 0 #define WGM10 0
#define WGM12 0 #define WGM12 0
#define CS10 0 #define CS10 0
#define DOR0 0
#define UPE0 0
#define FE0 0
#if defined(PCBARM) #if defined(PCBARM)
extern volatile uint32_t Tenms; extern volatile uint32_t Tenms;

View file

@ -86,8 +86,10 @@ void menuProcDebug(uint8_t event)
switch(event) switch(event)
{ {
case EVT_KEY_FIRST(KEY_MENU): case EVT_KEY_FIRST(KEY_MENU):
#if !defined(PCBARM)
g_tmr1Latency_min = 0xff; g_tmr1Latency_min = 0xff;
g_tmr1Latency_max = 0; g_tmr1Latency_max = 0;
#endif
g_timeMain = 0; g_timeMain = 0;
AUDIO_KEYPAD_UP(); AUDIO_KEYPAD_UP();
break; break;
@ -99,12 +101,16 @@ void menuProcDebug(uint8_t event)
chainMenu(menuMainView); chainMenu(menuMainView);
break; break;
} }
#if !defined(PCBARM)
lcd_putsLeft(1*FH, STR_TMR1LATMAXUS); lcd_putsLeft(1*FH, STR_TMR1LATMAXUS);
lcd_outdez8(15*FW , 1*FH, g_tmr1Latency_max/2 ); lcd_outdez8(15*FW , 1*FH, g_tmr1Latency_max/2 );
lcd_putsLeft(2*FH, STR_TMR1LATMINUS); lcd_putsLeft(2*FH, STR_TMR1LATMINUS);
lcd_outdez8(15*FW , 2*FH, g_tmr1Latency_min/2 ); lcd_outdez8(15*FW , 2*FH, g_tmr1Latency_min/2 );
lcd_putsLeft(3*FH, STR_TMR1JITTERUS); lcd_putsLeft(3*FH, STR_TMR1JITTERUS);
lcd_outdez8(15*FW , 3*FH, (g_tmr1Latency_max - g_tmr1Latency_min) /2 ); lcd_outdez8(15*FW , 3*FH, (g_tmr1Latency_max - g_tmr1Latency_min) /2 );
#endif
lcd_putsLeft(4*FH, STR_TMAINMAXMS); lcd_putsLeft(4*FH, STR_TMAINMAXMS);
#if defined(PCBARM) #if defined(PCBARM)
lcd_outdezAtt(15*FW, 4*FH, (g_timeMain)/20, PREC2); lcd_outdezAtt(15*FW, 4*FH, (g_timeMain)/20, PREC2);
@ -124,6 +130,7 @@ void menuProcDebug(uint8_t event)
lcd_putsLeft(6*FH, STR_CURRENT); lcd_putsLeft(6*FH, STR_CURRENT);
lcd_outhex4(10*FW+3, 6*FH, Current ) ; lcd_outhex4(10*FW+3, 6*FH, Current ) ;
lcd_outdezAtt(18*FW, 6*FH, Current/22, 0 ) ; lcd_outdezAtt(18*FW, 6*FH, Current/22, 0 ) ;
// TODO mAh, Battery from ersky9x?
#endif #endif

View file

@ -137,7 +137,12 @@
#define TR_VSWITCHES "THR""RUD""ELE""ID0""ID1""ID2""AIL""GEA""TRN""SW1""SW2""SW3""SW4""SW5""SW6""SW7""SW8""SW9""SWA""SWB""SWC" #define TR_VSWITCHES "THR""RUD""ELE""ID0""ID1""ID2""AIL""GEA""TRN""SW1""SW2""SW3""SW4""SW5""SW6""SW7""SW8""SW9""SWA""SWB""SWC"
#define LEN_VSRCRAW "\004" #define LEN_VSRCRAW "\004"
#define TR_VSRCRAW "Rud ""Ele ""Thr ""Ail ""P1 ""P2 ""P3 ""MAX ""3POS""CYC1""CYC2""CYC3" #if defined(PCBV4)
#define TR_ROTARY_ENCODERS_VSRCRAW "REA ""REB "
#else
#define TR_ROTARY_ENCODERS_VSRCRAW
#endif
#define TR_VSRCRAW "Rud ""Ele ""Thr ""Ail ""P1 ""P2 ""P3 " TR_ROTARY_ENCODERS_VSRCRAW "MAX ""3POS""CYC1""CYC2""CYC3"
#define LEN_VTMRMODES "\003" #define LEN_VTMRMODES "\003"
#define TR_VTMRMODES "OFF""ABS""THs""TH%""THt" #define TR_VTMRMODES "OFF""ABS""THs""TH%""THt"

View file

@ -137,7 +137,12 @@
#define TR_VSWITCHES "GAZ""DIR""PRF""ID0""ID1""ID2""AIL""GEA""TRN""SW1""SW2""SW3""SW4""SW5""SW6""SW7""SW8""SW9""SWA""SWB""SWC" #define TR_VSWITCHES "GAZ""DIR""PRF""ID0""ID1""ID2""AIL""GEA""TRN""SW1""SW2""SW3""SW4""SW5""SW6""SW7""SW8""SW9""SWA""SWB""SWC"
#define LEN_VSRCRAW "\004" #define LEN_VSRCRAW "\004"
#define TR_VSRCRAW "Dir ""Prf ""Gaz ""Ail ""P1 ""P2 ""P3 ""MAX ""3POS""CYC1""CYC2""CYC3" #if defined(PCBV4)
#define TR_ROTARY_ENCODERS_VSRCRAW "REA ""REB "
#else
#define TR_ROTARY_ENCODERS_VSRCRAW
#endif
#define TR_VSRCRAW "Dir ""Prf ""Gaz ""Ail ""P1 ""P2 ""P3 " TR_ROTARY_ENCODERS_VSRCRAW "MAX ""3POS""CYC1""CYC2""CYC3"
#define LEN_VTMRMODES "\003" #define LEN_VTMRMODES "\003"
#define TR_VTMRMODES "OFF""ABS""GZs""GZ%""GZt" #define TR_VTMRMODES "OFF""ABS""GZs""GZ%""GZt"

View file

@ -137,7 +137,12 @@
#define TR_VSWITCHES "GAS""SID""H\205J""ID0""ID1""ID2""SKE""LAN""TRN""BR1""BR2""BR3""BR4""BR5""BR6""BR7""BR8""BR9""BRA""BRB""BRC" #define TR_VSWITCHES "GAS""SID""H\205J""ID0""ID1""ID2""SKE""LAN""TRN""BR1""BR2""BR3""BR4""BR5""BR6""BR7""BR8""BR9""BRA""BRB""BRC"
#define LEN_VSRCRAW "\004" #define LEN_VSRCRAW "\004"
#define TR_VSRCRAW "SID ""H\205J ""GAS ""SKE ""P1 ""P2 ""P3 ""MAX ""FULL""CYK1""CYK2""CYK3" #if defined(PCBV4)
#define TR_ROTARY_ENCODERS_VSRCRAW "REA ""REB "
#else
#define TR_ROTARY_ENCODERS_VSRCRAW
#endif
#define TR_VSRCRAW "SID ""H\205J ""GAS ""SKE ""P1 ""P2 ""P3 " TR_ROTARY_ENCODERS_VSRCRAW "MAX ""FULL""CYK1""CYK2""CYK3"
#define LEN_VTMRMODES "\003" #define LEN_VTMRMODES "\003"
#define TR_VTMRMODES "AV ""ABS""THs""TH%""THt" #define TR_VTMRMODES "AV ""ABS""THs""TH%""THt"