1
0
Fork 0
mirror of https://github.com/opentx/opentx.git synced 2025-07-21 07:15:12 +03:00

Soft Power Switch on both v4.1 and ersky9x boards

Delay before effective EEPROM write on these boards
Current displayed
This commit is contained in:
bsongis 2012-03-30 16:03:43 +00:00
parent 6113420a02
commit e7eaced156
24 changed files with 501 additions and 165 deletions

View file

@ -17,10 +17,14 @@
#----------- BUILD OPTIONS ---------------------------
#gruvin: PCB version -- OVERRIDES the following settings if not STD
# PCB version
# Values: STD, V4, ARM
PCB = STD
# PCB revision
# Values: REVA, REVB
PCBREV = REVB
# Enable JETI-Telemetry or FrSky Telemetry reception on UART0
# For this option you need to modify your hardware!
# More information at [insertURLhere]
@ -107,23 +111,34 @@ DEBUG = NO
# Define programs and commands.
SHELL = sh
IMG2LBM = python ../util/img2lbm.py
REV = $(shell sh -c "svnversion | egrep -o '[[:digit:]]+[[:alpha:]]*$$'")
SVNREV = $(shell sh -c "svnversion | egrep -o '[[:digit:]]+[[:alpha:]]*$$'")
CPPDEFS =
# MCU name
ifeq ($(PCB), STD)
TRGT = avr-
MCU = atmega64
CPPDEFS = -DF_CPU=$(F_CPU)UL
CPPDEFS += -DF_CPU=$(F_CPU)UL
endif
ifeq ($(PCB), V4)
ifeq ($(PCBREV), REV0)
CPPDEFS += -DREV0
else
CPPDEFS += -DREV1
endif
TRGT = avr-
MCU = atmega2560
CPPDEFS = -DF_CPU=$(F_CPU)UL
CPPDEFS += -DF_CPU=$(F_CPU)UL
endif
ifeq ($(PCB), ARM)
ifeq ($(PCBREV), REVA)
CPPDEFS += -DREVA
else
CPPDEFS += -DREVB
endif
TRGT = arm-none-eabi-
MCU = cortex-m3
CPPDEFS =
endif
CC = $(TRGT)gcc
@ -436,14 +451,14 @@ stamp_header:
@echo "#define DATE_STR \"`date +%Y-%m-%d`\"" >> stamp-open9x.h
@echo "#define TIME_STR \"`date +%H:%I:%S`\"" >> stamp-open9x.h
@echo "#define VERS_STR \"$(MAJ_VER).$(MIN_VER)-$(MODS)\"" >> stamp-open9x.h
@echo "#define SVN_STR \"open9x-r$(REV)\"" >> stamp-open9x.h
@echo "#define SVN_STR \"open9x-r$(SVNREV)\"" >> stamp-open9x.h
@cat stamp-open9x.h
stamp:
@echo "#define DATE_STR \"`date +%Y-%m-%d`\"" > ../stamp-open9x.txt
@echo "#define TIME_STR \"`date +%H:%I:%S`\"" >> ../stamp-open9x.txt
@echo "#define VERS_STR \"$(MAJ_VER).$(MIN_VER)\"" >> ../stamp-open9x.txt
@echo "#define SVN_VERS \"open9x-r$(REV)\"" >> ../stamp-open9x.txt
@echo "#define SVN_VERS \"open9x-r$(SVNREV)\"" >> ../stamp-open9x.txt
@cat ../stamp-open9x.txt
font.lbm: font_6x1.xbm

View file

@ -75,8 +75,69 @@ inline void init_soft_power()
pioptr->PIO_ODR = PIO_PA8 ; // Set bit A8 as input
pioptr->PIO_PUER = PIO_PA8 ; // Enable PA8 pullup
}
// Returns non-zero if power is switched off
uint32_t check_soft_power()
{
if ( PIOC->PIO_PDSR & PIO_PC17 ) // Power on
{
return 1 ;
}
if ( PIOA->PIO_PDSR & PIO_PA8 ) // Trainer plugged in
{
return 1 ;
}
return 0 ;
}
#endif
uint32_t check_power()
{
#ifdef REVB
if ( check_soft_power() == 0 ) // power now off
{
return e_power_off ;
}
#endif
if ( PIOC->PIO_PDSR & 0x02000000 )
{
return e_power_usb ; // Detected USB
}
return e_power_on;
}
// turn off soft power
void soft_power_off()
{
#ifdef REVB
register Pio *pioptr ;
pioptr = PIOA ;
pioptr->PIO_PUDR = PIO_PA8 ; // Disble PA8 pullup
pioptr->PIO_OER = PIO_PA8 ; // Set bit A8 as input
pioptr->PIO_CODR = PIO_PA8 ; // Set bit A8 OFF, disables soft power switch
#endif
}
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
// Free pins (PA16 is stock buzzer)
// PA23, PA24, PA25, PB7, PB13
@ -155,7 +216,10 @@ inline void setup_switches()
#endif
}
#ifndef SIMU
#ifdef SIMU
#define end_ppm_capture()
#define sam_boot()
#else
/**
* Configures a UART peripheral with the specified parameters.
@ -269,6 +333,26 @@ inline void UART2_Configure( uint32_t baudrate, uint32_t masterClock)
pUsart->US_CR = US_CR_RXEN | US_CR_TXEN;
}
// Test, starts TIMER0 at full speed (MCK/2) for delay timing
// @ 36MHz this is 18MHz
// This was 6 MHz, we may need to slow it to TIMER_CLOCK2 (MCK/8=4.5 MHz)
inline void start_timer0()
{
register Tc *ptc ;
// Enable peripheral clock TC0 = bit 23 thru TC5 = bit 28
PMC->PMC_PCER0 |= 0x00800000L ; // Enable peripheral clock to TC0
ptc = TC0 ; // Tc block 0 (TC0-2)
ptc->TC_BCR = 0 ; // No sync
ptc->TC_BMR = 2 ;
ptc->TC_CHANNEL[0].TC_CMR = 0x00008001 ; // Waveform mode MCK/8 for 36MHz osc.
ptc->TC_CHANNEL[0].TC_RC = 0xFFF0 ;
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_CCR = 5 ; // Enable clock and trigger it (may only need trigger)
}
// Starts TIMER2 at 100Hz, commentd out drive of TIOA2 (A26, EXT2) out
inline void start_timer2()
{
@ -299,22 +383,113 @@ inline void start_timer2()
TC0->TC_CHANNEL[2].TC_IER = TC_IER0_CPCS ;
}
// Test, starts TIMER0 at full speed (MCK/2) for delay timing
inline void start_timer0()
// Start TIMER3 for input capture
inline void start_timer3()
{
register Tc *ptc ;
register Pio *pioptr ;
pioptr = PIOC ;
// Enable peripheral clock TC0 = bit 23 thru TC5 = bit 28
PMC->PMC_PCER0 |= 0x00800000L ; // Enable peripheral clock to TC0
PMC->PMC_PCER0 |= 0x04000000L ; // Enable peripheral clock to TC3
ptc = TC0 ; // Tc block 0 (TC0-2)
ptc = TC1 ; // Tc block 1 (TC3-5)
ptc->TC_BCR = 0 ; // No sync
ptc->TC_BMR = 2 ;
ptc->TC_CHANNEL[0].TC_CMR = 0x00008000 ; // Waveform mode
ptc->TC_CHANNEL[0].TC_RC = 0xFFF0 ;
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 = 0x00000000 ; // Capture mode
ptc->TC_CHANNEL[0].TC_CMR = 0x00090005 ; // 0000 0000 0000 1001 0000 0000 0000 0101, XC0, A rise, b fall
ptc->TC_CHANNEL[0].TC_CCR = 5 ; // Enable clock and trigger it (may only need trigger)
pioptr->PIO_ABCDSR[0] |= 0x00800000 ; // Peripheral B = TIOA3
pioptr->PIO_ABCDSR[1] &= ~0x00800000 ; // Peripheral B
pioptr->PIO_PDR = 0x00800000L ; // Disable bit C23 (TIOA3) Assign to peripheral
NVIC_SetPriority( TC3_IRQn, 15 ) ; // Low ppiority interrupt
NVIC_EnableIRQ(TC3_IRQn) ;
ptc->TC_CHANNEL[0].TC_IER = TC_IER0_LDRAS ;
}
// Start Timer4 to provide 0.5uS clock for input capture
void start_timer4()
{
register Tc *ptc ;
register uint32_t timer ;
timer = Master_frequency / (2*2000000) ; // MCK/2 and 2MHz
// Enable peripheral clock TC0 = bit 23 thru TC5 = bit 28
PMC->PMC_PCER0 |= 0x08000000L ; // Enable peripheral clock to TC4
ptc = TC1 ; // Tc block 1 (TC3-5)
ptc->TC_BCR = 0 ; // No sync
ptc->TC_BMR = 0 ;
ptc->TC_CHANNEL[1].TC_CMR = 0x00008000 ; // Waveform mode
ptc->TC_CHANNEL[1].TC_RC = timer ;
ptc->TC_CHANNEL[1].TC_RA = timer >> 1 ;
ptc->TC_CHANNEL[1].TC_CMR = 0x0009C000 ; // 0000 0000 0000 1001 1100 0000 0100 0000
// MCK/2, set @ RA, Clear @ RC waveform
ptc->TC_CHANNEL[1].TC_CCR = 5 ; // Enable clock and trigger it (may only need trigger)
}
// Timer3 used for PPM_IN pulse width capture. Counter running at 16MHz / 8 = 2MHz
// equating to one count every half millisecond. (2 counts = 1ms). Control channel
// count delta values thus can range from about 1600 to 4400 counts (800us to 2200us),
// corresponding to a PPM signal in the range 0.8ms to 2.2ms (1.5ms at center).
// (The timer is free-running and is thus not reset to zero at each capture interval.)
// Timer 4 generates the 2MHz clock to clock Timer 3
uint16_t Temp_captures[8] ;
extern "C" void TC3_IRQHandler() //capture ppm in at 2MHz
{
uint16_t capture ;
static uint16_t lastCapt ;
uint16_t val ;
capture = TC1->TC_CHANNEL[0].TC_RA ;
(void) TC1->TC_CHANNEL[0].TC_SR ; // Acknowledgethe interrupt
// cli();
// ETIMSK &= ~(1<<TICIE3); //stop reentrance
// sei();
val = (capture - lastCapt) / 2 ;
lastCapt = capture;
// We prcoess g_ppmInsright here to make servo movement as smooth as possible
// while under trainee control
if (ppmInState && ppmInState<=8) {
if(val>800 && val<2200) {
Temp_captures[ppmInState - 1] = capture ;
g_ppmIns[ppmInState++ - 1] =
(int16_t)(val - 1500)*(g_eeGeneral.PPM_Multiplier+10)/10; //+-500 != 512, but close enough.
}
else {
ppmInState=0; // not triggered
}
}
else {
if (val>4000 && val < 16000) {
ppmInState=1; // triggered
}
}
// cli();
// ETIMSK |= (1<<TICIE3);
// sei();
}
void start_ppm_capture()
{
start_timer4() ;
start_timer3() ;
}
void end_ppm_capture()
{
TC1->TC_CHANNEL[0].TC_IDR = TC_IDR0_LDRAS ;
NVIC_DisableIRQ(TC3_IRQn) ;
}
extern "C" void TC2_IRQHandler()
@ -586,11 +761,6 @@ void board_init()
#endif
uint16_t getTmr2MHz()
{
return TC1->TC_CHANNEL[0].TC_CV ;
}
// keys:
// KEY_EXIT PA31 (PC24)
// KEY_MENU PB6 (PB5)
@ -727,55 +897,63 @@ uint8_t keyDown()
extern uint32_t keyState(EnumKeys enuk)
{
register uint32_t a ;
register uint32_t c ;
CPU_UINT xxx = 0;
if (enuk < (int) DIM(keys)) return keys[enuk].state() ? 1 : 0;
a = PIOA->PIO_PDSR ;
c = PIOC->PIO_PDSR ;
switch ((uint8_t) enuk) {
#ifdef REVB
case SW_ElevDR : xxx = PIOC->PIO_PDSR & 0x80000000; // ELE_DR PC31
case SW_ElevDR:
xxx = c & 0x80000000; // ELE_DR PC31
#else
case SW_ElevDR:
xxx = PIOA->PIO_PDSR & 0x00000100; // ELE_DR PA8
xxx = a & 0x00000100; // ELE_DR PA8
#endif
break;
case SW_AileDR:
xxx = PIOA->PIO_PDSR & 0x00000004; // AIL-DR PA2
xxx = a & 0x00000004; // AIL-DR PA2
break;
case SW_RuddDR:
xxx = PIOA->PIO_PDSR & 0x00008000; // RUN_DR PA15
xxx = a & 0x00008000; // RUN_DR PA15
break;
// INP_G_ID1 INP_E_ID2
// id0 0 1
// id1 1 1
// id2 1 0
case SW_ID0:
xxx = ~PIOC->PIO_PDSR & 0x00004000; // SW_IDL1 PC14
xxx = ~c & 0x00004000; // SW_IDL1 PC14
break;
case SW_ID1:
xxx = (PIOC->PIO_PDSR & 0x00004000);
if (xxx) xxx = (PIOC->PIO_PDSR & 0x00000800);
xxx = (c & 0x00004000);
if (xxx) xxx = (c & 0x00000800);
break;
case SW_ID2:
xxx = ~PIOC->PIO_PDSR & 0x00000800; // SW_IDL2 PC11
xxx = ~c & 0x00000800; // SW_IDL2 PC11
break;
case SW_Gear:
xxx = PIOC->PIO_PDSR & 0x00010000; // SW_GEAR PC16
xxx = c & 0x00010000; // SW_GEAR PC16
break;
#ifdef REVB
case SW_ThrCt : xxx = PIOC->PIO_PDSR & 0x00100000; // SW_TCUT PC20
case SW_ThrCt:
xxx = c & 0x00100000; // SW_TCUT PC20
#else
case SW_ThrCt:
xxx = PIOA->PIO_PDSR & 0x10000000; // SW_TCUT PA28
xxx = a & 0x10000000; // SW_TCUT PA28
#endif
break;
case SW_Trainer:
xxx = PIOC->PIO_PDSR & 0x00000100; // SW-TRAIN PC8
xxx = c & 0x00000100; // SW-TRAIN PC8
break;
default:
@ -867,9 +1045,24 @@ void readKeysAndTrims()
}
}
void end_ppm_capture()
void usb_mode()
{
TC1->TC_CHANNEL[0].TC_IDR = TC_IDR0_LDRAS ;
NVIC_DisableIRQ(TC3_IRQn) ;
// This might be replaced by a software reset
// Any interrupts that have been enabled must be disabled here
// BEFORE calling sam_boot()
// TODO endPdcUsartReceive() ; // Terminate any serial reception
#ifdef REVB
soft_power_off() ;
#endif
end_ppm_capture() ;
end_spi() ;
end_sound() ;
TC0->TC_CHANNEL[2].TC_IDR = TC_IDR0_CPCS ;
NVIC_DisableIRQ(TC2_IRQn) ;
// PWM->PWM_IDR1 = PWM_IDR1_CHID0 ;
// TODO disable_main_ppm() ;
// PWM->PWM_IDR1 = PWM_IDR1_CHID3 ;
// NVIC_DisableIRQ(PWM_IRQn) ;
disable_ssc() ;
sam_boot() ;
}

View file

@ -40,13 +40,17 @@ inline void board_init()
DDRB = 0b11000111; PORTB = 0b00111111; // 7:SPKR, 6:PPM_OUT, 5:TrainSW, 4:IDL2_SW, SDCARD[3:MISO 2:MOSI 1:SCK 0:CS]
DDRC = 0x3f; PORTC = 0xc0; // 7:AilDR, 6:EleDR, LCD[5,4,3,2,1], 0:BackLight
DDRD = 0b11000000; PORTD = 0b11111100; // 7:VIB, 6:LED BL, 5:RENC2_PUSH, 4:RENC1_PUSH, 3:RENC2_B, 2:RENC2_A, 1:I2C_SDA, 0:I2C_SCL
DDRE = 0b00001010; PORTE = 0b11110101; // 7:PPM_IN, 6: RENC1_B, 5:RENC1_A, 4:USB_DNEG, 3:BUZZER, 2:USB_DPOS, 1:TELEM_TX, 0:TELEM_RX
DDRE = 0b00001010; PORTE = 0b11110100; // 7:PPM_IN, 6: RENC1_B, 5:RENC1_A, 4:USB_DNEG, 3:BUZZER, 2:USB_DPOS, 1:TELEM_TX, 0:TELEM_RX(pull-up off)
DDRF = 0x00; PORTF = 0x00; // 7-4:JTAG, 3:ADC_REF_1.2V input, 2-0:ADC_SPARE_2-0
DDRG = 0b00010000; PORTG = 0xff; // 7-6:N/A, 5:GearSW, 4: Sim_Ctrl[out], 3:IDL1_Sw, 2:TCut_Sw, 1:RF_Power[in], 0: RudDr_Sw
DDRH = 0b00110000; PORTH = 0b11011111; // 7:0 Spare port [6:SOMO14D-BUSY 5:SOMO14D-DATA 4:SOMO14D-CLK] [2:VIB_OPTION -- setting to input for now]
DDRJ = 0x00; PORTJ = 0xff; // 7-0:Trim switch inputs
DDRK = 0x00; PORTK = 0x00; // anain. No pull-ups!
#ifdef REV0
DDRL = 0x80; PORTL = 0x7f; // 7: Hold_PWR_On (1=On, default Off), 6:Jack_Presence_TTL, 5-0: User Button inputs
#else
DDRL = 0x80; PORTL = 0xff; // 7: Hold_PWR_On (1=On, default Off), 6:Jack_Presence_TTL, 5-0: User Button inputs
#endif
ADMUX=ADC_VREF_TYPE;
ADCSRA=0x85; // ADC enabled, pre-scaler division=32 (no interrupt, no auto-triggering)
@ -69,6 +73,22 @@ inline void board_init()
}
#endif
uint8_t check_power()
{
#ifndef REV0
if ((PING & 0b00000010) && (~PINL & 0b01000000))
return 1;
#endif
return 0;
}
void soft_power_off()
{
#ifndef REV0
PORTL = 0x7f;
#endif
}
#ifndef SIMU
FORCEINLINE
#endif

View file

@ -41,9 +41,6 @@ uint16_t s_eeDirtyTime10ms;
// 'main' needs to load a model
#define WRITE_DELAY_10MS 100
// These may not be needed, or might just be smaller
uint8_t Spi_tx_buf[24] ;
uint8_t Spi_rx_buf[24] ;
@ -96,7 +93,7 @@ uint32_t Update_timer ;
void eeDirty(uint8_t msk)
{
s_eeDirtyMsk |= msk;
s_eeDirtyTime10ms = get_tmr10ms() ;
s_eeDirtyTime10ms = get_tmr10ms() ;
}
void handle_serial( void ) ;
@ -327,7 +324,11 @@ void read32_eeprom_data( uint32_t eeAddress, register uint8_t *buffer, uint32_t
if (immediate )
return ;
while (!Spi_complete) ;
while (!Spi_complete) {
#ifdef SIMU
sleep(5/*ms*/);
#endif
}
}
void write32_eeprom_block( uint32_t eeAddress, register uint8_t *buffer, uint32_t size, uint32_t immediate )
@ -354,7 +355,11 @@ void write32_eeprom_block( uint32_t eeAddress, register uint8_t *buffer, uint32_
if (immediate)
return;
while (!Spi_complete) ;
while (!Spi_complete) {
#ifdef SIMU
sleep(5/*ms*/);
#endif
}
}
uint8_t byte_checksum( uint8_t *p, uint32_t size )
@ -676,17 +681,18 @@ void eeWaitFinished()
{
while (Eeprom32_process_state != E32_IDLE) {
ee32_process();
#ifdef SIMU
sleep(5/*ms*/);
#endif
// TODO perMain()?
}
}
void eeCheck(bool immediately)
{
if (!immediately && (Eeprom32_process_state != E32_IDLE || (get_tmr10ms() - s_eeDirtyTime10ms) < WRITE_DELAY_10MS))
return;
if (Eeprom32_process_state != E32_IDLE)
if (immediately) {
eeWaitFinished();
}
if (s_eeDirtyMsk & EE_GENERAL) {
s_eeDirtyMsk -= EE_GENERAL;

View file

@ -20,6 +20,12 @@
#include <inttypes.h>
#include <stdint.h>
#ifdef REV0
#define WRITE_DELAY_10MS 100
#else
#define WRITE_DELAY_10MS 500
#endif
extern uint8_t s_eeDirtyMsk;
extern uint16_t s_eeDirtyTime10ms;

View file

@ -39,6 +39,9 @@
uint8_t s_write_err = 0; // error reasons
uint8_t s_sync_write = false;
uint8_t s_eeDirtyMsk;
#if defined(PCBV4) && !defined(REV0)
uint16_t s_eeDirtyTime10ms;
#endif
RlcFile theFile; //used for any file operation
@ -60,6 +63,9 @@ PACK(struct EeFs{
void eeDirty(uint8_t msk)
{
s_eeDirtyMsk |= msk;
#if defined(PCBV4) && !defined(REV0)
s_eeDirtyTime10ms = get_tmr10ms();
#endif
}
uint16_t eeprom_pointer;
@ -752,11 +758,13 @@ void eeCheck(bool immediately)
if (immediately) {
eeFlush();
}
if (s_eeDirtyMsk & EE_GENERAL) {
s_eeDirtyMsk -= EE_GENERAL;
theFile.writeRlc(FILE_GENERAL, FILE_TYP_GENERAL, (uint8_t*)&g_eeGeneral, sizeof(EEGeneral), immediately);
if (!immediately) return;
}
if (s_eeDirtyMsk & EE_MODEL) {
s_eeDirtyMsk = 0;
theFile.writeRlc(FILE_MODEL(g_eeGeneral.currModel), FILE_TYP_MODEL, (uint8_t*)&g_model, sizeof(g_model), immediately);

View file

@ -31,11 +31,16 @@
*
*/
#ifndef file_h
#define file_h
#ifndef eeprom_avr_h
#define eeprom_avr_h
#include <inttypes.h>
#if defined(PCBV4) && !defined(REV0)
#define WRITE_DELAY_10MS 500
extern uint16_t s_eeDirtyTime10ms;
#endif
//
// bs=16 128 blocks verlust link:128 16files:16*8 128 sum 256
// bs=32 64 blocks verlust link: 64 16files:16*16 256 sum 320

View file

@ -184,7 +184,7 @@ void SSC_IRQHandler (void) { while(1); }
void TC0_IRQHandler (void) { while(1); }
void TC1_IRQHandler (void) { while(1); }
// void TC2_IRQHandler (void) { while(1); }
void TC3_IRQHandler (void) { while(1); }
// void TC3_IRQHandler (void) { while(1); }
void TC4_IRQHandler (void) { while(1); }
void TC5_IRQHandler (void) { while(1); }
void ADC_IRQHandler (void) { while(1); }

View file

@ -163,11 +163,14 @@ void writeLogs()
{
// For now, append 'anything' as a test
// if data type == Hub
#ifdef FRSKY
f_printf(&g_oLogFile, "%d,", frskyStreaming);
f_printf(&g_oLogFile, "%d,", frskyRSSI[0].value);
f_printf(&g_oLogFile, "%d,", frskyRSSI[1].value);
f_printf(&g_oLogFile, "%d,", frskyTelemetry[0].value);
f_printf(&g_oLogFile, "%d,", frskyTelemetry[1].value);
#endif
#ifdef FRSKY_HUB
f_printf(&g_oLogFile, "%4d-%02d-%02d,", frskyHubData.year+2000, frskyHubData.month, frskyHubData.day);
f_printf(&g_oLogFile, "%02d:%02d:%02d,", frskyHubData.hour, frskyHubData.min, frskyHubData.sec);
f_printf(&g_oLogFile, "%03d.%04d%c,", frskyHubData.gpsLongitude_bp, frskyHubData.gpsLongitude_ap,
@ -186,6 +189,7 @@ void writeLogs()
f_printf(&g_oLogFile, "%d,", frskyHubData.accelX);
f_printf(&g_oLogFile, "%d,", frskyHubData.accelY);
f_printf(&g_oLogFile, "%d,", frskyHubData.accelZ);
#endif
f_printf(&g_oLogFile, "%d,", keyState(SW_ThrCt));
f_printf(&g_oLogFile, "%d,", keyState(SW_RuddDR));
f_printf(&g_oLogFile, "%d,", keyState(SW_ElevDR));

View file

@ -473,6 +473,11 @@ void pushMenu(MenuFuncP newMenu)
}
const pm_char * s_warning = 0;
const pm_char * s_warning_info;
uint8_t s_warning_info_len;
// uint8_t s_warning_info_att not needed now
uint8_t s_confirmation = 0;
void displayBox()
{
lcd_filled_rect(10, 16, 108, 40, SOLID, WHITE);
@ -481,6 +486,47 @@ void displayBox()
// could be a place for a s_warning_info
}
void displayPopup(const pm_char * pstr)
{
s_warning = pstr;
displayBox();
s_warning = 0;
refreshDisplay();
}
void displayWarning(uint8_t event)
{
if (s_warning) {
displayBox();
lcd_puts(16, 5*FH, STR_EXIT);
switch(event) {
case EVT_KEY_FIRST(KEY_EXIT):
killEvents(event);
s_warning = 0;
break;
}
}
}
void displayConfirmation(uint8_t event)
{
s_confirmation = false;
displayBox();
if (s_warning_info)
lcd_putsnAtt(16, 4*FH, s_warning_info, s_warning_info_len, ZCHAR);
lcd_puts(16, 5*FH, STR_POPUPS);
switch(event) {
case EVT_KEY_FIRST(KEY_MENU):
s_confirmation = true;
// no break
case EVT_KEY_FIRST(KEY_EXIT):
killEvents(event);
s_warning = 0;
break;
}
}
#ifdef NAVIGATION_RE1
int8_t *s_inflight_value = NULL;
int8_t s_inflight_min;

View file

@ -173,7 +173,13 @@ SIMPLE_SUBMENU_NOTITLE(lines_count); \
TITLE(title)
extern const pm_char * s_warning;
// TODO macro for s_warning
extern const pm_char * s_warning_info;
extern uint8_t s_warning_info_len;
extern uint8_t s_confirmation;
void displayBox();
void displayPopup(const pm_char * pstr);
void displayWarning(uint8_t event);
void displayConfirmation(uint8_t event);
#endif

View file

@ -99,53 +99,6 @@ const MenuFuncP_PROGMEM menuTabModel[] PROGMEM = {
#endif
};
const pm_char * s_warning_info;
uint8_t s_warning_info_len;
// uint8_t s_warning_info_att not needed now
uint8_t s_confirmation = 0;
void displayPopup(const pm_char * pstr)
{
s_warning = pstr;
displayBox();
s_warning = 0;
refreshDisplay();
}
void displayWarning(uint8_t event)
{
if (s_warning) {
displayBox();
lcd_puts(16, 5*FH, STR_EXIT);
switch(event) {
case EVT_KEY_FIRST(KEY_EXIT):
killEvents(event);
s_warning = 0;
break;
}
}
}
void displayConfirmation(uint8_t event)
{
s_confirmation = false;
displayBox();
if (s_warning_info)
lcd_putsnAtt(16, 4*FH, s_warning_info, s_warning_info_len, ZCHAR);
lcd_puts(16, 5*FH, STR_POPUPS);
switch(event) {
case EVT_KEY_FIRST(KEY_MENU):
s_confirmation = true;
// no break
case EVT_KEY_FIRST(KEY_EXIT):
killEvents(event);
s_warning = 0;
break;
}
}
#define COPY_MODE 1
#define MOVE_MODE 2
static uint8_t s_copyMode = 0;

View file

@ -288,6 +288,14 @@ const pm_char STR_LATITUDE[] PROGMEM = TR_LATITUDE;
const pm_char STR_LONGITUDE[] PROGMEM = TR_LONGITUDE;
#endif
#if defined(PCBARM) || defined(PCBV4)
const pm_char STR_SHUTDOWN[] PROGMEM = TR_SHUTDOWN;
#endif
#if defined(PCBARM)
const pm_char STR_CURRENT[] PROGMEM = TR_CURRENT;
#endif
const pm_uchar font[] PROGMEM = {
#include "font.lbm"
#ifdef TRANSLATIONS_SE

View file

@ -349,5 +349,13 @@ extern const pm_char STR_LATITUDE[];
extern const pm_char STR_LONGITUDE[];
#endif
#if defined(PCBARM) || defined(PCBV4)
extern const pm_char STR_SHUTDOWN[];
#endif
#if defined(PCBARM)
extern const pm_char STR_CURRENT[];
#endif
extern const pm_uchar font[];
extern const pm_uchar font_dblsize[];

View file

@ -722,6 +722,8 @@ void checkTHR()
int16_t v = anaIn(thrchn);
if (g_eeGeneral.throttleReversed) v = - v;
if (check_power()) return; // Usb on or power off
if(v<=lowLim || keyDown()) {
clearKeyEvents();
return;
@ -761,6 +763,8 @@ void checkSwitches()
first = false;
}
if (check_power()) return; // Usb on or power off
checkBacklight();
#ifdef SIMU
@ -780,7 +784,12 @@ void alert(const pm_char * s)
if (!main_thread_running) return;
sleep(1/*ms*/);
#endif
if(keyDown()) return; //wait for key release
#if defined(PCBARM)
if (check_power()) return; // Usb on or power off
#endif
if(keyDown()) return; // wait for key release
checkBacklight();
@ -887,6 +896,7 @@ uint16_t BandGap = 2040 ;
uint16_t BandGap ;
#endif
#if defined(PCBARM) and defined(REVB)
uint16_t Current_analogue;
#define NUMBER_ANALOG 9
#else
#define NUMBER_ANALOG 8
@ -1579,6 +1589,12 @@ void perOut(uint8_t phase)
char userDataDisplayBuf[TELEM_SCREEN_BUFFER_SIZE];
#endif
#if defined(PCBARM) || (defined(PCBV4) && !defined(REV0))
#define TIME_TO_WRITE (s_eeDirtyMsk && (get_tmr10ms() - s_eeDirtyTime10ms) >= WRITE_DELAY_10MS)
#else
#define TIME_TO_WRITE s_eeDirtyMsk
#endif
int32_t sum_chans512[NUM_CHNOUT] = {0};
void perMain()
{
@ -1652,18 +1668,18 @@ void perMain()
// TODO same code here + integrate the timer which could be common
#if defined(PCBARM)
if ( Tenms ) {
if (Tenms) {
Tenms = 0 ;
if (Eeprom32_process_state != E32_IDLE)
ee32_process();
else if (s_eeDirtyMsk)
else if (TIME_TO_WRITE)
eeCheck();
}
#else
if (!eeprom_buffer_size) {
if (theFile.isWriting())
theFile.nextWriteStep();
else if (s_eeDirtyMsk)
else if (TIME_TO_WRITE)
eeCheck();
}
#endif
@ -1935,7 +1951,10 @@ void perMain()
case 2:
{
int32_t instant_vbat = anaIn(7);
#if defined(PCBV4)
#if defined(PCBARM)
instant_vbat = ( instant_vbat + instant_vbat*(g_eeGeneral.vBatCalib)/128 ) * 4191 ;
instant_vbat /= 55296 ;
#elif defined(PCBV4)
instant_vbat = ((uint32_t)instant_vbat*1112 + (int32_t)instant_vbat*g_eeGeneral.vBatCalib + (BandGap<<2)) / (BandGap<<3);
#else
instant_vbat = (instant_vbat*16 + instant_vbat*g_eeGeneral.vBatCalib/8) / BandGap;
@ -2322,23 +2341,6 @@ uint16_t stack_free()
return p - &__bss_end ;
}
#else
// TODO in another file...
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 ;
}
#endif
int main(void)
@ -2479,22 +2481,29 @@ int main(void)
// TODO init_main_ppm( 3000, 1 ) ; // Default for now, initial period 1.5 mS, output on
// TODO start_ppm_capture() ;
#if defined(PCBARM)
start_ppm_capture();
// TODO inside startPulses?
#endif
// FrSky testing serial receive
// TODO startPdcUsartReceive() ;
wdt_enable(WDTO_500MS);
while(1) {
#if defined(PCBARM)
register Pio *pioptr = PIOC ;
if ( pioptr->PIO_PDSR & 0x02000000 ) {
// Detected USB
// TODO goto_usb = 1 ;
break;
}
register uint32_t shutdown_state = 0;
#elif defined(PCBV4)
uint8_t shutdown_state = 0;
#endif
while(1) {
#if defined(PCBARM) || defined(PCBV4)
if ((shutdown_state=check_power()))
break;
#endif
#if defined(PCBARM)
uint16_t t0 = getTmr2MHz();
#else
uint16_t t0 = getTmr16KHz();
@ -2510,7 +2519,9 @@ int main(void)
getADC_single() ;
}
#if defined(PCBV4)
#if defined(PCBARM) && defined(REVB)
Current_analogue = ( Current_analogue * 31 + s_anaFilt[8] ) >> 5 ;
#elif defined(PCBV4)
// 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
@ -2536,32 +2547,34 @@ int main(void)
t0 = getTmr16KHz() - t0;
#endif
g_timeMain = max(g_timeMain,t0);
g_timeMain = max(g_timeMain, t0);
}
#if defined(PCBARM)
#if defined(PCBARM) || defined(PCBV4)
// Time to switch off
lcd_clear() ;
lcd_putcAtt( 48, 24, 'U', DBLSIZE ) ;
lcd_putcAtt( 60, 24, 'S', DBLSIZE ) ;
lcd_putcAtt( 72, 24, 'B', DBLSIZE ) ;
refreshDisplay() ;
displayPopup(STR_SHUTDOWN);
eeCheck(true);
// This might be replaced by a software reset
// Any interrupts that have been enabled must be disabled here
// BEFORE calling sam_boot()
// TODO needed for REVB soft_power_off() ;
// TODO not started end_ppm_capture() ;
end_spi() ; // TODO in eeprom_arm ...
end_sound() ;
TC0->TC_CHANNEL[2].TC_IDR = TC_IDR0_CPCS ;
NVIC_DisableIRQ(TC2_IRQn) ;
// PWM->PWM_IDR1 = PWM_IDR1_CHID0 ;
// TODO disable_main_ppm() ;
// PWM->PWM_IDR1 = PWM_IDR1_CHID3 ;
// NVIC_DisableIRQ(PWM_IRQn) ;
disable_ssc() ;
sam_boot() ;
#if defined(PCBARM)
if (shutdown_state == e_power_usb) {
lcd_clear();
lcd_putcAtt( 48, 24, 'U', DBLSIZE ) ;
lcd_putcAtt( 60, 24, 'S', DBLSIZE ) ;
lcd_putcAtt( 72, 24, 'B', DBLSIZE ) ;
refreshDisplay() ;
usb_mode();
}
#ifdef REVB
else
#endif
#endif
{
soft_power_off(); // Only turn power off if necessary
}
#endif
}
#endif

View file

@ -466,9 +466,22 @@ uint8_t getEvent();
void putEvent(uint8_t evt);
uint8_t keyDown();
#if defined(PCBARM)
uint32_t keyState(EnumKeys enuk);
enum PowerState {
e_power_on,
e_power_usb,
e_power_off
};
uint32_t check_power();
#else
#if defined(PCBV4)
uint8_t check_power();
#else
#define check_power() (0)
#endif
bool keyState(EnumKeys enuk);
#endif
void readKeysAndTrims();
@ -527,7 +540,7 @@ extern int8_t s_traceCnt;
extern int8_t *s_trimPtr[NUM_STICKS];
#if defined(PCBARM)
uint16_t getTmr2MHz();
static inline uint16_t getTmr2MHz() { return TC1->TC_CHANNEL[0].TC_CV; }
#else
uint16_t getTmr16KHz();
#endif
@ -698,6 +711,7 @@ extern uint8_t g_beepVal[5];
#include "o9xstrings.h"
extern uint8_t ppmInState; //0=unsync 1..8= wait for value i-1
extern int16_t g_ppmIns[8];
extern int16_t g_chans512[NUM_CHNOUT];
extern volatile uint8_t tick10ms;

View file

@ -432,7 +432,7 @@ FORCEINLINE void setupPulsesDsm2()
void DSM2_Done()
{
UCSR0B &= ~((1 << TXEN0) | (1 << UDRIE0)); // disable TX pin and interrupt
UCSR0B &= ~((1 << TXEN0) | (1 << UDRIE0)); // disable UART TX and interrupt
}
void DSM2_Init(void)
@ -451,7 +451,7 @@ void DSM2_Init(void)
UBRR0L = UBRRL_VALUE;
UCSR0A &= ~(1 << U2X0); // disable double speed operation.
// set 8N1
// set 8N1 (leave TX and RX disabled for now)
UCSR0B = 0 | (0 << RXCIE0) | (0 << TXCIE0) | (0 << UDRIE0) | (0 << RXEN0) | (0 << TXEN0) | (0 << UCSZ02);
UCSR0C = 0 | (1 << UCSZ01) | (1 << UCSZ00);

View file

@ -88,11 +88,13 @@ void *eeprom_write_function(void *)
}
else {
#endif
if (fp) {
if (fseek(fp, eeprom_pointer, SEEK_SET) == -1)
perror("error in fseek");
}
while (--eeprom_buffer_size) {
assert(eeprom_buffer_size > 0);
if (fp) {
if (fseek(fp, eeprom_pointer, SEEK_SET) == -1)
perror("error in fseek");
if (fwrite(eeprom_buffer_data, 1, 1, fp) != 1)
perror("error in fwrite");
#if !defined(PCBARM)

View file

@ -260,7 +260,7 @@ void eeprom_read_block (void *pointer_ram,
const void *pointer_eeprom,
size_t size);
#define wdt_reset() sleep(1)
#define wdt_reset() sleep(1/*ms*/)
#define board_init()
#endif

View file

@ -288,7 +288,7 @@ void Open9xSim::refreshDiplay()
pinb &= ~ 0x7e;
pinl &= ~ 0x3f; // for v4
#if defined(PCBARM)
PIOC->PIO_PDSR = 0xFFFFFFFF;
PIOC->PIO_PDSR = 0xFDFFFFFF;
PIOB->PIO_PDSR = 0xFFFFFFFF;
PIOA->PIO_PDSR = 0xFFFFFFFF;
#endif

View file

@ -77,6 +77,9 @@ void menuProcStatistic(uint8_t event)
}
}
uint16_t Current ;
uint32_t Current_sum ;
uint8_t Current_count ;
void menuProcDebug(uint8_t event)
{
TITLE(STR_MENUDEBUG);
@ -96,14 +99,34 @@ void menuProcDebug(uint8_t event)
chainMenu(menuMainView);
break;
}
lcd_puts( 0*FW, 1*FH, STR_TMR1LATMAXUS);
lcd_putsLeft(1*FH, STR_TMR1LATMAXUS);
lcd_outdez8(15*FW , 1*FH, g_tmr1Latency_max/2 );
lcd_puts( 0*FW, 2*FH, STR_TMR1LATMINUS);
lcd_putsLeft(2*FH, STR_TMR1LATMINUS);
lcd_outdez8(15*FW , 2*FH, g_tmr1Latency_min/2 );
lcd_puts( 0*FW, 3*FH, STR_TMR1JITTERUS);
lcd_putsLeft(3*FH, STR_TMR1JITTERUS);
lcd_outdez8(15*FW , 3*FH, (g_tmr1Latency_max - g_tmr1Latency_min) /2 );
lcd_puts( 0*FW, 4*FH, STR_TMAINMAXMS);
lcd_putsLeft(4*FH, STR_TMAINMAXMS);
#if defined(PCBARM)
lcd_outdezAtt(15*FW, 4*FH, (g_timeMain)/20, PREC2);
#else
lcd_outdezAtt(15*FW, 4*FH, (g_timeMain*100)/16, PREC2);
#endif
#if defined(PCBARM) && defined(REVB)
// TODO then there are 2 means, is it needed?
Current_sum += anaIn(NUMBER_ANALOG-1) ;
if ( ++Current_count > 49 )
{
Current = Current_sum / 5 ;
Current_sum = 0 ;
Current_count = 0 ;
}
lcd_putsLeft(6*FH, STR_CURRENT);
lcd_outhex4(10*FW+3, 6*FH, Current ) ;
lcd_outdezAtt(18*FW, 6*FH, Current/22, 0 ) ;
#endif
#ifdef DEBUG
lcd_puts( 0*FW, 5*FH, STR_T10MSUS);
lcd_outdez8(15*FW , 5*FH, g_time_per10/2 );

View file

@ -313,4 +313,6 @@
#define TR_MINRSSI "Min Rssi"
#define TR_LATITUDE "Latitude"
#define TR_LONGITUDE "Longitude"
#define TR_GPSCOORD "Gps Coords"
#define TR_GPSCOORD "Gps Coords"
#define TR_SHUTDOWN "SHUTTING DOWN"
#define TR_CURRENT "Current"

View file

@ -313,4 +313,6 @@
#define TR_MINRSSI "Min Rssi"
#define TR_LATITUDE "Latitude"
#define TR_LONGITUDE "Longitude"
#define TR_GPSCOORD "Gps Coords"
#define TR_GPSCOORD "Gps Coords"
#define TR_SHUTDOWN "ARRET EN COURS"
#define TR_CURRENT "Courant"

View file

@ -313,4 +313,6 @@
#define TR_MINRSSI "Min Rssi"
#define TR_LATITUDE "Breddgrad"
#define TR_LONGITUDE "L\201ngdgrad"
#define TR_GPSCOORD "GPS-Koord."
#define TR_GPSCOORD "GPS-Koord."
#define TR_SHUTDOWN "SHUTTING DOWN"
#define TR_CURRENT "Current"