mirror of
https://github.com/opentx/opentx.git
synced 2025-07-23 16:25:16 +03:00
NMEA and ARDUPILOT code ported from er9x
DSM2(PPM) bug fixed Flash saving PCBV3 removed One delay_us(7) removed BEEPSPKR becomes AUDIO
This commit is contained in:
parent
5b1bad8705
commit
e6d8648074
20 changed files with 1895 additions and 380 deletions
93
src/Makefile
93
src/Makefile
|
@ -28,16 +28,15 @@
|
||||||
#----------- BUILD OPTIONS ---------------------------
|
#----------- BUILD OPTIONS ---------------------------
|
||||||
|
|
||||||
#gruvin: PCB version -- OVERRIDES the following settings if not STD
|
#gruvin: PCB version -- OVERRIDES the following settings if not STD
|
||||||
# Values: STD, V3, V4
|
# Values: STD, V4
|
||||||
PCB = STD
|
PCB = STD
|
||||||
#NOTE!: V4 adds to V3, such that both PCBV3 and PCBV4 get defined
|
|
||||||
|
|
||||||
# Following options for PCB=STD only (ignored otherwise) ...
|
# Following options for PCB=STD only (ignored otherwise) ...
|
||||||
|
|
||||||
# Enable JETI-Telemetry or FrSky Telemetry reception on UART0
|
# Enable JETI-Telemetry or FrSky Telemetry reception on UART0
|
||||||
# For this option you need to modify your hardware!
|
# For this option you need to modify your hardware!
|
||||||
# More information at [insertURLhere]
|
# More information at [insertURLhere]
|
||||||
# Values = STD, JETI, FRSKY
|
# Values = STD, FRSKY, JETI, NMEA, ARDUPILOT
|
||||||
EXT = STD
|
EXT = STD
|
||||||
|
|
||||||
# Enable heli menu
|
# Enable heli menu
|
||||||
|
@ -61,24 +60,16 @@ else
|
||||||
NAVIGATION = POTS
|
NAVIGATION = POTS
|
||||||
endif
|
endif
|
||||||
|
|
||||||
# gruvin: BEEPER. Values = BUZZER, BUZZER_MOD or SPEAKER
|
# AUDIO Mods
|
||||||
# (without a mod, BUZZER can make PPM jack output switch from output to input at random)
|
# Values = YES, NO
|
||||||
# SPEAKER mode actually works on the stock radio, using the stock beeper. Sort of sound OK(ish).
|
AUDIO = YES
|
||||||
BEEPER = BUZZER
|
|
||||||
|
|
||||||
# gruvin: Legacy support freeing of USART1 TX/RX pins [DEPRECATED]
|
|
||||||
# OPTIONS STD or FREED
|
|
||||||
USART1 = STD
|
|
||||||
|
|
||||||
# gruvin: PCM-in circuit mod for JR/Spektrum (and others) compatability
|
|
||||||
# Values = STD, MOD1
|
|
||||||
PPMIN = STD
|
|
||||||
|
|
||||||
# SPLASH on START
|
# SPLASH on START
|
||||||
SPLASH = YES
|
SPLASH = YES
|
||||||
|
|
||||||
# BATT voltage algorithm. Values = BANDGAP, UNSTABLE_BANDGAP
|
# BATT voltage algorithm.
|
||||||
BATT = BANDGAP
|
# Values = BANDGAP, UNSTABLE_BANDGAP (default for stock board)
|
||||||
|
BATT = UNSTABLE_BANDGAP
|
||||||
|
|
||||||
# Decimals display in the main view (PPM calibration,
|
# Decimals display in the main view (PPM calibration,
|
||||||
# Values = YES, NO
|
# Values = YES, NO
|
||||||
|
@ -148,6 +139,14 @@ ifeq ($(EXT), JETI)
|
||||||
CPPSRC += jeti.cpp
|
CPPSRC += jeti.cpp
|
||||||
endif
|
endif
|
||||||
|
|
||||||
|
ifeq ($(EXT), ARDUPILOT)
|
||||||
|
CPPSRC += ardupilot.cpp
|
||||||
|
endif
|
||||||
|
|
||||||
|
ifeq ($(EXT), NMEA)
|
||||||
|
CPPSRC += nmea.cpp
|
||||||
|
endif
|
||||||
|
|
||||||
# Disk IO support (PCB V2+ only)
|
# Disk IO support (PCB V2+ only)
|
||||||
ifneq ($(PCB), STD)
|
ifneq ($(PCB), STD)
|
||||||
CPPSRC += gtime.cpp
|
CPPSRC += gtime.cpp
|
||||||
|
@ -222,26 +221,25 @@ ifeq ($(NAVIGATION), POTS)
|
||||||
CPPDEFS += -DNAVIGATION_POT1 -DNAVIGATION_POT2 -DNAVIGATION_POT3
|
CPPDEFS += -DNAVIGATION_POT1 -DNAVIGATION_POT2 -DNAVIGATION_POT3
|
||||||
endif
|
endif
|
||||||
|
|
||||||
ifneq ($(SPLASH), NO)
|
ifeq ($(SPLASH), YES)
|
||||||
CPPDEFS += -DSPLASH
|
CPPDEFS += -DSPLASH
|
||||||
endif
|
endif
|
||||||
|
|
||||||
ifeq ($(BEEPER), SPEAKER)
|
ifeq ($(AUDIO), YES)
|
||||||
CPPDEFS += -DBEEPSPKR
|
CPPDEFS += -DAUDIO
|
||||||
CPPSRC += audio.cpp
|
CPPSRC += audio.cpp
|
||||||
else
|
else
|
||||||
CPPSRC += beeper.cpp
|
CPPSRC += beeper.cpp
|
||||||
endif
|
endif
|
||||||
|
|
||||||
ifeq ($(PCB), STD)
|
# If ARDUPILOT-Support is enabled
|
||||||
# STD PCB, so ...
|
ifeq ($(EXT), ARDUPILOT)
|
||||||
|
CPPDEFS += -DARDUPILOT
|
||||||
|
endif
|
||||||
|
|
||||||
CPPDEFS += -DPCBSTD
|
# If NMEA-Support is enabled
|
||||||
|
ifeq ($(EXT), NMEA)
|
||||||
# If Hardware PPM mode ( PB0<->BP7) switch the Backlight output with the original PPM to use hardware facility to generate precise PPM (hardware mods)
|
CPPDEFS += -DNMEA
|
||||||
# G: TODO This prevents HARDPPM being used with FRSKY. HARDPPM needs its own option XXX
|
|
||||||
ifeq ($(EXT), HARDPPM)
|
|
||||||
CPPDEFS += -DPPMPB7_HARDWARE
|
|
||||||
endif
|
endif
|
||||||
|
|
||||||
# If JETI-Support is enabled
|
# If JETI-Support is enabled
|
||||||
|
@ -266,47 +264,32 @@ ifeq ($(PCB), STD)
|
||||||
endif
|
endif
|
||||||
endif
|
endif
|
||||||
|
|
||||||
# If buzzer modified (no interference with PPM jack)
|
ifeq ($(PCB), V4)
|
||||||
ifeq ($(BEEPER), BUZZER_MOD)
|
# V4 PCB, so ...
|
||||||
CPPDEFS += -DBUZZER_MOD
|
CPPDEFS += -DPCBV4
|
||||||
endif
|
|
||||||
|
|
||||||
# If BandGap is not rock solid
|
|
||||||
ifeq ($(BATT), UNSTABLE_BANDGAP)
|
|
||||||
CPPDEFS += -DBATT_UNSTABLE_BANDGAP
|
|
||||||
endif
|
|
||||||
|
|
||||||
# gruvin: Legacy support for hardware mod freeing USART1 [DEPRECATED]
|
|
||||||
ifeq ($(USART1), FREED)
|
|
||||||
CPPDEFS += -DUSART1FREED
|
|
||||||
endif
|
|
||||||
|
|
||||||
# gruvin: PCM-in circuit mod for JR/Spektrum (and others) compatability
|
|
||||||
ifeq ($(PPMIN), MOD1)
|
|
||||||
CPPDEFS += -DPPMIN_MOD1
|
|
||||||
endif
|
|
||||||
|
|
||||||
else
|
|
||||||
# not PCB=STD, so ...
|
|
||||||
|
|
||||||
ifeq ($(NAVIGATION), RE1)
|
ifeq ($(NAVIGATION), RE1)
|
||||||
CPPDEFS += -DNAVIGATION_RE1
|
CPPDEFS += -DNAVIGATION_RE1
|
||||||
endif
|
endif
|
||||||
|
|
||||||
CPPSRC += frsky.cpp
|
|
||||||
CPPDEFS += -DPCBV3 -DFRSKY -DFRSKY_HUB -DWS_HOW_HIGH
|
|
||||||
ifeq ($(LOGS), YES)
|
ifeq ($(LOGS), YES)
|
||||||
CPPSRC += logs.cpp
|
CPPSRC += logs.cpp
|
||||||
CPPDEFS += -DLOGS
|
CPPDEFS += -DLOGS
|
||||||
MODS:=${MODS}L
|
MODS:=${MODS}L
|
||||||
endif
|
endif
|
||||||
ifeq ($(PCB), V4)
|
|
||||||
CPPDEFS += -DPCBV4
|
|
||||||
endif
|
|
||||||
ifeq ($(SOMO), YES)
|
ifeq ($(SOMO), YES)
|
||||||
CPPSRC += somo14d.cpp
|
CPPSRC += somo14d.cpp
|
||||||
CPPDEFS += -DSOMO
|
CPPDEFS += -DSOMO
|
||||||
endif
|
endif
|
||||||
|
else
|
||||||
|
# STD PCB, so ...
|
||||||
|
CPPDEFS += -DPCBSTD
|
||||||
|
|
||||||
|
# If BandGap is not rock solid
|
||||||
|
ifeq ($(BATT), UNSTABLE_BANDGAP)
|
||||||
|
CPPDEFS += -DBATT_UNSTABLE_BANDGAP
|
||||||
|
endif
|
||||||
endif
|
endif
|
||||||
|
|
||||||
|
|
||||||
|
|
714
src/ardupilot.cpp
Normal file
714
src/ardupilot.cpp
Normal file
|
@ -0,0 +1,714 @@
|
||||||
|
/*
|
||||||
|
*
|
||||||
|
* Author - Karl Szmutny <shadow@privy.de>
|
||||||
|
* Author - Uphiearl and Jean-Pierre PARISY
|
||||||
|
*
|
||||||
|
*
|
||||||
|
* 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"
|
||||||
|
#include "menus.h"
|
||||||
|
|
||||||
|
#define NB_BUF 2
|
||||||
|
#define LG_BUF 11
|
||||||
|
#define VALSTR(val) (rbuf[val][0] ? rbuf[val] : val_unknown)
|
||||||
|
#define APSIZE (BSS | DBLSIZE)
|
||||||
|
|
||||||
|
/* Received data
|
||||||
|
|
||||||
|
Data are received as packets, each packet is identified by a prefix of three
|
||||||
|
characters and is ended by three stars. Some packets can contain more than
|
||||||
|
one value, the values are ended by a comma.
|
||||||
|
|
||||||
|
|
||||||
|
Position packet:
|
||||||
|
!!!LAT:0123456789,LON:9876543210,SPD:123,CRT:1,ALT:123456,ALH:654321,CRS:123,BER:123,WPN:12,DST:12345,BTV:12.4567 9012,RSP:123,TOW:123456,***
|
||||||
|
...----1--------------2--------------3-------4-----5----------6----------7-------8-------9------10--------11-----------12----------13-----END
|
||||||
|
1st value 2nd value
|
||||||
|
|
||||||
|
Attitude packet:
|
||||||
|
+++ASP:123,THH:123,RLL:123,PCH:123,***
|
||||||
|
...----1-------2-------3-------4---END
|
||||||
|
|
||||||
|
Mode change packet:
|
||||||
|
###STABILIZE***
|
||||||
|
...1--------END
|
||||||
|
|
||||||
|
Waypoint packet:
|
||||||
|
%%%12 45***
|
||||||
|
...1----END
|
||||||
|
|
||||||
|
Alert packet:
|
||||||
|
XXXAlert Text alert***
|
||||||
|
...1---------------END
|
||||||
|
|
||||||
|
Performance packet:
|
||||||
|
PPPThis is performant***
|
||||||
|
...1--------------END
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Position packet prefix
|
||||||
|
#define PACK_POS 0x21
|
||||||
|
// value occurence number in this packet
|
||||||
|
#define LAT 1
|
||||||
|
#define LON 2
|
||||||
|
#define SPD 3
|
||||||
|
#define CRT 4
|
||||||
|
#define ALT 5
|
||||||
|
#define ALH 6
|
||||||
|
#define CRS 7
|
||||||
|
#define BER 8
|
||||||
|
#define WPN 9
|
||||||
|
#define DST 10
|
||||||
|
#define BTV 11
|
||||||
|
#define RSP 12
|
||||||
|
#define TOW 13
|
||||||
|
|
||||||
|
#define PACK_ATT 0x2b
|
||||||
|
// value occurence number in this packet
|
||||||
|
#define ASP 1
|
||||||
|
#define THH 2
|
||||||
|
#define RLL 3
|
||||||
|
#define PCH 4
|
||||||
|
|
||||||
|
#define PACK_MOD 0x23
|
||||||
|
// value occurence number in this packet
|
||||||
|
#define MOD 1
|
||||||
|
|
||||||
|
#define PACK_WPC 0x25
|
||||||
|
// value occurence number in this packet
|
||||||
|
#define WPC 1
|
||||||
|
|
||||||
|
#define PACK_ALR 0x58
|
||||||
|
// value occurence number in this packet
|
||||||
|
#define ALR 1
|
||||||
|
|
||||||
|
#define PACK_PRF 0x50
|
||||||
|
// value occurence number in this packet
|
||||||
|
#define PRF 1
|
||||||
|
|
||||||
|
// end of packet
|
||||||
|
#define PACK_END 0x2a
|
||||||
|
// end of value
|
||||||
|
#define VAL_END 0x2c
|
||||||
|
// end of title
|
||||||
|
#define TITLE_END 0x3a
|
||||||
|
|
||||||
|
// stateful machine
|
||||||
|
|
||||||
|
// Since the packets are sent continuously, we need to synchronize on the
|
||||||
|
// reception of the three chars prefixing a packet, whatever they are.
|
||||||
|
|
||||||
|
// states values
|
||||||
|
#define WAIT_PACKET 1
|
||||||
|
#define WAIT_PACK_POS1 2
|
||||||
|
#define WAIT_PACK_POS2 3
|
||||||
|
#define WAIT_PACK_POS3 4
|
||||||
|
#define WAIT_PACK_ATT1 5
|
||||||
|
#define WAIT_PACK_ATT2 6
|
||||||
|
#define WAIT_PACK_ATT3 7
|
||||||
|
#define WAIT_PACK_MOD1 8
|
||||||
|
#define WAIT_PACK_MOD2 9
|
||||||
|
#define WAIT_PACK_MOD3 10
|
||||||
|
#define WAIT_PACK_WPC1 11
|
||||||
|
#define WAIT_PACK_WPC2 12
|
||||||
|
#define WAIT_PACK_WPC3 13
|
||||||
|
#define WAIT_PACK_ALR1 14
|
||||||
|
#define WAIT_PACK_ALR2 15
|
||||||
|
#define WAIT_PACK_ALR3 16
|
||||||
|
#define WAIT_PACK_PRF1 17
|
||||||
|
#define WAIT_PACK_PRF2 18
|
||||||
|
#define WAIT_PACK_PRF3 19
|
||||||
|
#define FLUSH_TITLE1 20
|
||||||
|
#define FLUSH_TITLE2 21
|
||||||
|
#define FLUSH_TITLE3 22
|
||||||
|
#define FLUSH_TITLE4 23
|
||||||
|
#define READ_VALUE 24
|
||||||
|
|
||||||
|
uint8_t i; // working variable
|
||||||
|
uint8_t state; // currrent state
|
||||||
|
uint8_t rval, rpack; // received items
|
||||||
|
uint8_t xval[NB_BUF]; // expected value
|
||||||
|
uint8_t xpack[NB_BUF]; // expected packet
|
||||||
|
uint8_t ibuf[NB_BUF]; // subscripts on buffers values
|
||||||
|
char rbuf[NB_BUF][LG_BUF]; // receive buffers
|
||||||
|
const char val_unknown[] = "?";
|
||||||
|
|
||||||
|
void menuProcArduPilot1(uint8_t event);
|
||||||
|
void menuProcArduPilot2(uint8_t event);
|
||||||
|
void menuProcArduPilot3(uint8_t event);
|
||||||
|
void menuProcArduPilot4(uint8_t event);
|
||||||
|
void menuProcArduPilot5(uint8_t event);
|
||||||
|
void menuProcArduPilot6(uint8_t event);
|
||||||
|
void menuProcArduPilot7(uint8_t event);
|
||||||
|
void menuProcArduPilot8(uint8_t event);
|
||||||
|
void title(char x);
|
||||||
|
void initval(uint8_t num, uint8_t pack, uint8_t val);
|
||||||
|
|
||||||
|
#ifndef SIMU
|
||||||
|
ISR (USART0_RX_vect)
|
||||||
|
{
|
||||||
|
uint8_t rl;
|
||||||
|
uint8_t rh; //USART control and Status Register 0 B
|
||||||
|
uint8_t iostat; //USART control and Status Register 0 A
|
||||||
|
|
||||||
|
rl = UDR0;
|
||||||
|
iostat = UCSR0A; //USART control and Status Register 0 A
|
||||||
|
/*
|
||||||
|
bit 7 6 5 4 3 2 1 0
|
||||||
|
RxC0 TxC0 UDRE0 FE0 DOR0 UPE0 U2X0 MPCM0
|
||||||
|
|
||||||
|
RxC0: Receive complete
|
||||||
|
TXC0: Transmit Complete
|
||||||
|
UDRE0: USART Data Register Empty
|
||||||
|
FE0: Frame Error
|
||||||
|
DOR0: Data OverRun
|
||||||
|
UPE0: USART Parity Error
|
||||||
|
U2X0: Double Tx Speed
|
||||||
|
MPCM0: MultiProcessor Comms Mode
|
||||||
|
*/
|
||||||
|
if (iostat & ((1 << FE0) | (1 << DOR0) | (1 << UPE0)))
|
||||||
|
{
|
||||||
|
rl = xpack[0] = xpack[1] = xval[0] = xval[1] = 0;
|
||||||
|
state = WAIT_PACKET; // restart on error
|
||||||
|
}
|
||||||
|
rh = UCSR0B; //USART control and Status Register 0 B
|
||||||
|
/* bit 7 6 5 4 3 2 1 0
|
||||||
|
RxCIE0 TxCIE0 UDRIE0 RXEN0 TXEN0 UCSZ02 RXB80 TXB80
|
||||||
|
|
||||||
|
RxCIE0: Receive complete int enable
|
||||||
|
TXCIE0: Transmit Complete int enable
|
||||||
|
UDRIE0: USART Data Register Empty int enable
|
||||||
|
RXEN0: Rx enable
|
||||||
|
TXEN0: Tx Enable
|
||||||
|
UCSZ02: Character Size bit 2
|
||||||
|
RXB80: Rx data bit 8
|
||||||
|
TXB80: Tx data bit 8
|
||||||
|
*/
|
||||||
|
switch (state)
|
||||||
|
{
|
||||||
|
case WAIT_PACKET:
|
||||||
|
switch (rl)
|
||||||
|
{
|
||||||
|
case PACK_POS: // found a new POS packet
|
||||||
|
state = WAIT_PACK_POS2; // wait for the 2nd char
|
||||||
|
break;
|
||||||
|
case PACK_ATT: // found a new ATT packet
|
||||||
|
state = WAIT_PACK_ATT2; // wait for the 2nd char
|
||||||
|
break;
|
||||||
|
case PACK_MOD: // found a new MOD packet
|
||||||
|
state = WAIT_PACK_MOD2; // wait for the 2nd char
|
||||||
|
break;
|
||||||
|
case PACK_WPC: // found a new WPC packet
|
||||||
|
state = WAIT_PACK_WPC2; // wait for the 2nd char
|
||||||
|
break;
|
||||||
|
case PACK_ALR: // found a new ALR packet
|
||||||
|
state = WAIT_PACK_ALR2; // wait for the 2nd char
|
||||||
|
break;
|
||||||
|
case PACK_PRF: // found a new PRF packet
|
||||||
|
state = WAIT_PACK_PRF2; // wait for the 2nd char
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_POS2: // wait for 2nd char
|
||||||
|
if (rl == PACK_POS)
|
||||||
|
state = WAIT_PACK_POS3;
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_POS3: // wait for 3rd char
|
||||||
|
if (rl == PACK_POS) // found
|
||||||
|
{
|
||||||
|
state = FLUSH_TITLE1; // flush title "LAT:"
|
||||||
|
rpack = PACK_POS;
|
||||||
|
rval = 1;
|
||||||
|
for (i = 0; i < NB_BUF; i++)
|
||||||
|
ibuf[i] = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_ATT2: // wait for 2nd char
|
||||||
|
if (rl == PACK_ATT)
|
||||||
|
state = WAIT_PACK_ATT3;
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_ATT3: // wait for 3rd char
|
||||||
|
if (rl == PACK_ATT)
|
||||||
|
{
|
||||||
|
state = FLUSH_TITLE1; // flush title "ASP:"
|
||||||
|
rpack = PACK_ATT;
|
||||||
|
rval = 1;
|
||||||
|
for (i = 0; i < NB_BUF; i++)
|
||||||
|
ibuf[i] = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_MOD2: // wait for 2nd char
|
||||||
|
if (rl == PACK_MOD)
|
||||||
|
state = WAIT_PACK_MOD3;
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_MOD3: // wait for 3rd char
|
||||||
|
if (rl == PACK_MOD)
|
||||||
|
{
|
||||||
|
state = READ_VALUE; // ready to read values from PACK_MOD packet
|
||||||
|
rpack = PACK_MOD;
|
||||||
|
rval = 1;
|
||||||
|
for (i = 0; i < NB_BUF; i++)
|
||||||
|
ibuf[i] = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_WPC2: // wait for 2nd char
|
||||||
|
if (rl == PACK_WPC)
|
||||||
|
state = WAIT_PACK_WPC3;
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_WPC3: // wait for 3rd char
|
||||||
|
if (rl == PACK_WPC)
|
||||||
|
{
|
||||||
|
state = READ_VALUE; // ready to read values from PACK_WPC packet
|
||||||
|
rpack = PACK_WPC;
|
||||||
|
rval = 1;
|
||||||
|
for (i = 0; i < NB_BUF; i++)
|
||||||
|
ibuf[i] = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_ALR2: // wait for 2nd char
|
||||||
|
if (rl == PACK_ALR)
|
||||||
|
state = WAIT_PACK_ALR3;
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_ALR3: // wait for 3rd char
|
||||||
|
if (rl == PACK_ALR)
|
||||||
|
{
|
||||||
|
state = READ_VALUE; // ready to read values from PACK_ALR packet
|
||||||
|
rpack = PACK_ALR;
|
||||||
|
rval = 1;
|
||||||
|
for (i = 0; i < NB_BUF; i++)
|
||||||
|
ibuf[i] = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_PRF2: // wait for 2nd char
|
||||||
|
if (rl == PACK_PRF)
|
||||||
|
state = WAIT_PACK_PRF3;
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_PRF3: // wait for 3rd char
|
||||||
|
if (rl == PACK_PRF)
|
||||||
|
{
|
||||||
|
state = READ_VALUE; // ready to read values from PACK_PRF packet
|
||||||
|
rpack = PACK_PRF;
|
||||||
|
rval = 1;
|
||||||
|
for (i = 0; i < NB_BUF; i++)
|
||||||
|
ibuf[i] = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
case FLUSH_TITLE1: // wait for 1st char of title
|
||||||
|
state = FLUSH_TITLE2;
|
||||||
|
break;
|
||||||
|
case FLUSH_TITLE2: // wait for 2nd char
|
||||||
|
state = FLUSH_TITLE3;
|
||||||
|
break;
|
||||||
|
case FLUSH_TITLE3: // wait for 3rd char
|
||||||
|
state = FLUSH_TITLE4;
|
||||||
|
break;
|
||||||
|
case FLUSH_TITLE4: // wait for 4th char
|
||||||
|
if (rl == TITLE_END)
|
||||||
|
state = READ_VALUE;
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // was not a title, wait for the next packet
|
||||||
|
break;
|
||||||
|
case READ_VALUE:
|
||||||
|
switch (rl)
|
||||||
|
{
|
||||||
|
case PACK_END:
|
||||||
|
state = WAIT_PACKET; // packet completed, wait for the next packet
|
||||||
|
break;
|
||||||
|
case VAL_END: // comma found, value completed
|
||||||
|
state = FLUSH_TITLE1; // flush next title
|
||||||
|
rval++; // and get next value
|
||||||
|
break;
|
||||||
|
default: // store the char in the corresponding buffer
|
||||||
|
for (i = 0; i < NB_BUF; i++)
|
||||||
|
{ // is it the expected value in the expected packet ?
|
||||||
|
if (rpack == xpack[i] && rval == xval[i] && ibuf[i] < LG_BUF - 1)
|
||||||
|
{ // yes, store the char
|
||||||
|
rbuf[i] [ibuf[i]] = rl;
|
||||||
|
ibuf[i]++;
|
||||||
|
rbuf[i] [ibuf[i]] = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void ARDUPILOT_Init (void)
|
||||||
|
{
|
||||||
|
DDRE &= ~(1 << DDE0); // set RXD0 pin as input
|
||||||
|
PORTE &= ~(1 << PORTE0); // disable pullup on RXD0 pin
|
||||||
|
|
||||||
|
#ifndef SIMU
|
||||||
|
// switch (Telem_baud)
|
||||||
|
// {
|
||||||
|
// case 1:
|
||||||
|
#undef BAUD
|
||||||
|
#define BAUD 38400
|
||||||
|
#include <util/setbaud.h>
|
||||||
|
UBRR0H = UBRRH_VALUE;
|
||||||
|
UBRR0L = UBRRL_VALUE;
|
||||||
|
// break;
|
||||||
|
// }
|
||||||
|
|
||||||
|
UCSR0A &= ~(1 << U2X0); // disable double speed operation
|
||||||
|
// set 8N1
|
||||||
|
UCSR0B = 0|(0<< RXCIE0)|(0<<TXCIE0)|(0<<UDRIE0)|(0<<RXEN0)|(0<<TXEN0)|(0<<UCSZ02);
|
||||||
|
UCSR0C = 0|(1 << UCSZ01) | (1 << UCSZ00);
|
||||||
|
while ( UCSR0A & (1 << RXC0) )
|
||||||
|
UDR0; // flush receive buffer
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void ARDUPILOT_DisableTXD (void)
|
||||||
|
{
|
||||||
|
UCSR0B &= ~(1 << TXEN0); // disable TX
|
||||||
|
}
|
||||||
|
|
||||||
|
void ARDUPILOT_EnableTXD (void)
|
||||||
|
{
|
||||||
|
UCSR0B |= (1 << TXEN0); // enable TX
|
||||||
|
}
|
||||||
|
|
||||||
|
void ARDUPILOT_DisableRXD (void)
|
||||||
|
{
|
||||||
|
UCSR0B &= ~(1 << RXEN0); // disable RX
|
||||||
|
UCSR0B &= ~(1 << RXCIE0); // disable Interrupt
|
||||||
|
}
|
||||||
|
|
||||||
|
void ARDUPILOT_EnableRXD (void)
|
||||||
|
{
|
||||||
|
for (i = 0; i < NB_BUF; i++)
|
||||||
|
{
|
||||||
|
ibuf[i] = 0;
|
||||||
|
rbuf[i][0] = 0;
|
||||||
|
xpack[i] = 0;
|
||||||
|
xval[i] = 0;
|
||||||
|
}
|
||||||
|
state = WAIT_PACKET; // wait for the next packet
|
||||||
|
UCSR0B |= (1 << RXEN0); // enable RX
|
||||||
|
UCSR0B |= (1 << RXCIE0); // enable Interrupt
|
||||||
|
}
|
||||||
|
|
||||||
|
void menuProcArduPilot(uint8_t event)
|
||||||
|
{
|
||||||
|
menuProcArduPilot1(event);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Start of ArduPilot menus 1-8 <<<<<<<<<<<<<<<<<<<<<<<<<<<
|
||||||
|
|
||||||
|
void menuProcArduPilot1(uint8_t event)
|
||||||
|
{
|
||||||
|
switch(event) // new event received, branch accordingly
|
||||||
|
{
|
||||||
|
case EVT_KEY_FIRST(KEY_UP):
|
||||||
|
chainMenu(menuProcArduPilot8);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_DOWN):
|
||||||
|
chainMenu(menuProcArduPilot2);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_MENU):
|
||||||
|
ARDUPILOT_DisableRXD();
|
||||||
|
chainMenu(menuProcStatistic);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_EXIT):
|
||||||
|
ARDUPILOT_DisableRXD();
|
||||||
|
chainMenu(menuMainView);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
/*
|
||||||
|
How to use:
|
||||||
|
|
||||||
|
You choose the values to be displayed using the function:
|
||||||
|
|
||||||
|
initval(<number>, <packet>, <value>);
|
||||||
|
-------------------------------------
|
||||||
|
|
||||||
|
That means that "<value>" of "<packet>" is stored in the <number> buffer.
|
||||||
|
The first <number> is 0.
|
||||||
|
|
||||||
|
Here are the packet names and the associated value names:
|
||||||
|
|
||||||
|
Position packet (beginning with "!!!"): "PACK_POS"
|
||||||
|
value names: "LAT", "LON", "SPD", "CRT", "ALT", "ALH", "CRS", "BER",
|
||||||
|
"WPN", "DST", "BTV", "RSP", "TOW"
|
||||||
|
|
||||||
|
Attitude packet (beginning with "+++"): "PACK_ATT"
|
||||||
|
value names: "ASP", "THH", "RLL", "PCH"
|
||||||
|
|
||||||
|
Mode change packet (beginning with "###"): "PACK_MOD"
|
||||||
|
value name: "MOD"
|
||||||
|
|
||||||
|
Waypoint packet (beginning with "%%%"): "PACK_WPC"
|
||||||
|
value name: "WPC"
|
||||||
|
|
||||||
|
Alert packet (beginning with "XXX"): "PACK_ALR"
|
||||||
|
value name: "ALR"
|
||||||
|
|
||||||
|
Performance packet (beginning with "PPP"): "PACK_PRF"
|
||||||
|
value name: "PRF"
|
||||||
|
|
||||||
|
The buffers are accessed using the macro "VALSTR(<n>)", where "<n>" is "0"
|
||||||
|
for the first buffer, and "1" for the second buffer.
|
||||||
|
|
||||||
|
When a value is missing, it is replaced by the contents of val_unknown ("?").
|
||||||
|
*/
|
||||||
|
// expecting LAT value in POS packet to be stored in the first buffer
|
||||||
|
initval (0, PACK_POS, LAT);
|
||||||
|
// and LON value in POS packet stored in the second buffer
|
||||||
|
initval (1, PACK_POS, LON);
|
||||||
|
// title of the screen
|
||||||
|
title ('1');
|
||||||
|
lcd_puts_P (5*FW, 1*FH, PSTR(" Latitude")); // line 1 column 5
|
||||||
|
// first buffer into line 2 column 2
|
||||||
|
lcd_putsAtt (2*FW, 2*FH, VALSTR(0), APSIZE);
|
||||||
|
lcd_puts_P (5*FW, 4*FH, PSTR(" Longitude")); // line 4 column 5
|
||||||
|
// second buffer into line 5 column 2
|
||||||
|
lcd_putsAtt (1*FW, 5*FH, VALSTR(1), APSIZE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void menuProcArduPilot2(uint8_t event)
|
||||||
|
{
|
||||||
|
switch(event)
|
||||||
|
{
|
||||||
|
case EVT_KEY_FIRST(KEY_UP):
|
||||||
|
chainMenu(menuProcArduPilot1);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_DOWN):
|
||||||
|
chainMenu(menuProcArduPilot3);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_EXIT):
|
||||||
|
ARDUPILOT_DisableRXD();
|
||||||
|
chainMenu(menuMainView);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
initval (0, PACK_POS, SPD);
|
||||||
|
initval (1, PACK_POS, CRT);
|
||||||
|
title ('2');
|
||||||
|
lcd_puts_P (1*FW, 1*FH, PSTR(" Ground speed"));
|
||||||
|
lcd_putsAtt (2*FW, 2*FH, VALSTR(0), APSIZE);
|
||||||
|
lcd_puts_P (1*FW, 4*FH, PSTR(" Climb rate") );
|
||||||
|
lcd_putsAtt (2*FW, 5*FH, VALSTR(1), APSIZE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void menuProcArduPilot3(uint8_t event)
|
||||||
|
{
|
||||||
|
switch(event)
|
||||||
|
{
|
||||||
|
case EVT_KEY_FIRST(KEY_UP):
|
||||||
|
chainMenu(menuProcArduPilot2);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_DOWN):
|
||||||
|
chainMenu(menuProcArduPilot4);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_EXIT):
|
||||||
|
ARDUPILOT_DisableRXD();
|
||||||
|
chainMenu(menuMainView);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
initval (0, PACK_POS, ALT);
|
||||||
|
initval (1, PACK_POS, ALH);
|
||||||
|
title ('3');
|
||||||
|
lcd_puts_P (1*FW, 1*FH, PSTR(" Altitude"));
|
||||||
|
lcd_putsAtt (2*FW, 2*FH, VALSTR(0), APSIZE);
|
||||||
|
lcd_puts_P (1*FW, 4*FH, PSTR(" Altitude Hold") );
|
||||||
|
lcd_putsAtt (2*FW, 5*FH, VALSTR(1), APSIZE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void menuProcArduPilot4(uint8_t event)
|
||||||
|
{
|
||||||
|
switch(event)
|
||||||
|
{
|
||||||
|
case EVT_KEY_FIRST(KEY_UP):
|
||||||
|
chainMenu(menuProcArduPilot3);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_DOWN):
|
||||||
|
chainMenu(menuProcArduPilot5);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_EXIT):
|
||||||
|
ARDUPILOT_DisableRXD();
|
||||||
|
chainMenu(menuMainView);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
initval (0, PACK_POS, CRS);
|
||||||
|
initval (1, PACK_POS, BER);
|
||||||
|
title ('4');
|
||||||
|
lcd_puts_P (1*FW, 1*FH, PSTR(" Course"));
|
||||||
|
lcd_putsAtt (2*FW, 2*FH, VALSTR(0), APSIZE);
|
||||||
|
lcd_puts_P (1*FW, 4*FH, PSTR(" Bearing"));
|
||||||
|
lcd_putsAtt (2*FW, 5*FH, VALSTR(1), APSIZE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void menuProcArduPilot5(uint8_t event)
|
||||||
|
{
|
||||||
|
switch(event)
|
||||||
|
{
|
||||||
|
case EVT_KEY_FIRST(KEY_UP):
|
||||||
|
chainMenu(menuProcArduPilot4);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_DOWN):
|
||||||
|
chainMenu(menuProcArduPilot6);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_MENU):
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_EXIT):
|
||||||
|
ARDUPILOT_DisableRXD();
|
||||||
|
chainMenu(menuMainView);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
initval (0, PACK_POS, WPN);
|
||||||
|
initval (1, PACK_POS, DST);
|
||||||
|
title ('5');
|
||||||
|
lcd_puts_P (1*FW, 1*FH, PSTR(" Way Point # "));
|
||||||
|
lcd_putsAtt (2*FW, 2*FH, VALSTR(0), APSIZE);
|
||||||
|
lcd_puts_P (1*FW, 4*FH, PSTR(" Distance "));
|
||||||
|
lcd_putsAtt (2*FW, 5*FH, VALSTR(1), APSIZE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void menuProcArduPilot6(uint8_t event)
|
||||||
|
{
|
||||||
|
switch(event)
|
||||||
|
{
|
||||||
|
case EVT_KEY_FIRST(KEY_UP):
|
||||||
|
chainMenu(menuProcArduPilot5);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_DOWN):
|
||||||
|
chainMenu(menuProcArduPilot7);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_MENU):
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_EXIT):
|
||||||
|
ARDUPILOT_DisableRXD();
|
||||||
|
chainMenu(menuMainView);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
initval (0, PACK_ATT, ASP);
|
||||||
|
initval (1, PACK_ATT, THH);
|
||||||
|
title ('6');
|
||||||
|
lcd_puts_P (1*FW, 1*FH, PSTR(" Air Speed "));
|
||||||
|
lcd_putsAtt (2*FW, 2*FH, VALSTR(0), APSIZE);
|
||||||
|
lcd_puts_P (1*FW, 4*FH, PSTR(" Climb Rate "));
|
||||||
|
lcd_putsAtt (2*FW, 5*FH, VALSTR(1), APSIZE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void menuProcArduPilot7(uint8_t event)
|
||||||
|
{
|
||||||
|
switch(event)
|
||||||
|
{
|
||||||
|
case EVT_KEY_FIRST(KEY_UP):
|
||||||
|
chainMenu(menuProcArduPilot6);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_DOWN):
|
||||||
|
chainMenu(menuProcArduPilot8);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_MENU):
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_EXIT):
|
||||||
|
ARDUPILOT_DisableRXD();
|
||||||
|
chainMenu(menuMainView);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
initval (0, PACK_ATT, RLL);
|
||||||
|
initval (1, PACK_ATT, PCH);
|
||||||
|
title ('7');
|
||||||
|
lcd_puts_P (1*FW, 1*FH, PSTR(" Roll Angle"));
|
||||||
|
lcd_putsAtt (2*FW, 2*FH, VALSTR(0), APSIZE);
|
||||||
|
lcd_puts_P (1*FW, 4*FH, PSTR(" Pitch Angle"));
|
||||||
|
lcd_putsAtt (2*FW, 5*FH, VALSTR(1), APSIZE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void menuProcArduPilot8(uint8_t event)
|
||||||
|
{
|
||||||
|
switch(event)
|
||||||
|
{
|
||||||
|
case EVT_KEY_FIRST(KEY_UP):
|
||||||
|
chainMenu(menuProcArduPilot7);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_DOWN):
|
||||||
|
chainMenu(menuProcArduPilot1);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_MENU):
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_EXIT):
|
||||||
|
ARDUPILOT_DisableRXD();
|
||||||
|
chainMenu(menuMainView);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
initval (0, PACK_MOD, MOD);
|
||||||
|
initval (1, PACK_WPC, WPC);
|
||||||
|
title ('8');
|
||||||
|
lcd_puts_P (1*FW, 1*FH, PSTR(" ArduPilot Mode"));
|
||||||
|
lcd_putsAtt (2*FW, 2*FH, VALSTR(0), APSIZE);
|
||||||
|
lcd_puts_P (1*FW, 4*FH, PSTR(" RTL Distance"));
|
||||||
|
lcd_putsAtt (2*FW, 5*FH, VALSTR(1), APSIZE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void title(char x)
|
||||||
|
{
|
||||||
|
lcd_putsAtt (0, 0, PSTR(" ARDU PILOT Mega ?/8 "), INVERS);
|
||||||
|
lcd_putcAtt(17*FW, 0*FH, x, INVERS);
|
||||||
|
}
|
||||||
|
|
||||||
|
void initval(uint8_t num, uint8_t pack, uint8_t val)
|
||||||
|
{
|
||||||
|
if (xpack[num] != pack || xval[num] != val)
|
||||||
|
{
|
||||||
|
ibuf[num] = rbuf[num][0] = 0;
|
||||||
|
xpack[num] = pack;
|
||||||
|
xval[num] = val;
|
||||||
|
state = WAIT_PACKET; // synchronize to the next packet
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
Without ArduPilot:
|
||||||
|
Size after:
|
||||||
|
er9x.elf :
|
||||||
|
section size addr
|
||||||
|
.data 164 8388864
|
||||||
|
.text 50634 0
|
||||||
|
.bss 3485 8389028
|
||||||
|
----------------------------------
|
||||||
|
With ArduPilot:
|
||||||
|
Size after:
|
||||||
|
er9x.elf :
|
||||||
|
section size addr
|
||||||
|
.data 166 8388864
|
||||||
|
.text 53026 0
|
||||||
|
.bss 3517 8389030
|
||||||
|
*/
|
23
src/ardupilot.h
Normal file
23
src/ardupilot.h
Normal file
|
@ -0,0 +1,23 @@
|
||||||
|
/*
|
||||||
|
* Author - Philip Moss
|
||||||
|
* Adapted from frsky.h code by Jean-Pierre PARISY
|
||||||
|
*
|
||||||
|
*
|
||||||
|
* 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 ardupilot_h
|
||||||
|
#define ardupilot_h
|
||||||
|
void ARDUPILOT_Init(void);
|
||||||
|
void ARDUPILOT_EnableRXD (void);
|
||||||
|
void menuProcArduPilot(uint8_t event);
|
||||||
|
#endif
|
||||||
|
|
|
@ -164,14 +164,14 @@ void audioQueue::heartbeat()
|
||||||
case 0:
|
case 0:
|
||||||
//stock beeper. simply turn port on for x time!
|
//stock beeper. simply turn port on for x time!
|
||||||
if (toneTimeLeft > 0) {
|
if (toneTimeLeft > 0) {
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
TCCR0A &= ~(0b01<<COM0A0);
|
TCCR0A &= ~(0b01<<COM0A0);
|
||||||
#else
|
#else
|
||||||
PORTE |= (1 << OUT_E_BUZZER); // speaker output 'high'
|
PORTE |= (1 << OUT_E_BUZZER); // speaker output 'high'
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
#if defined (PCVV3)
|
#if defined (PCVV4)
|
||||||
TCCR0A &= ~(0b01<<COM0A0);
|
TCCR0A &= ~(0b01<<COM0A0);
|
||||||
#else
|
#else
|
||||||
PORTE &= ~(1 << OUT_E_BUZZER); // speaker output 'low'
|
PORTE &= ~(1 << OUT_E_BUZZER); // speaker output 'low'
|
||||||
|
@ -188,7 +188,7 @@ void audioQueue::heartbeat()
|
||||||
if (toneTimeLeft > 0) {
|
if (toneTimeLeft > 0) {
|
||||||
toneCounter += toneFreq;
|
toneCounter += toneFreq;
|
||||||
if ((toneCounter & 0x80) == 0x80) {
|
if ((toneCounter & 0x80) == 0x80) {
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
TCCR0A &= ~(0b01<<COM0A0);
|
TCCR0A &= ~(0b01<<COM0A0);
|
||||||
#else
|
#else
|
||||||
PORTE |= (1 << OUT_E_BUZZER); // speaker output 'high'
|
PORTE |= (1 << OUT_E_BUZZER); // speaker output 'high'
|
||||||
|
|
|
@ -25,6 +25,7 @@ uint8_t g_beepCnt;
|
||||||
uint8_t beepAgain = 0;
|
uint8_t beepAgain = 0;
|
||||||
uint8_t beepAgainOrig = 0;
|
uint8_t beepAgainOrig = 0;
|
||||||
uint8_t beepOn = false;
|
uint8_t beepOn = false;
|
||||||
|
bool warble = false;
|
||||||
|
|
||||||
// The various "beep" tone lengths
|
// The various "beep" tone lengths
|
||||||
static prog_uint8_t APM beepTab[]= {
|
static prog_uint8_t APM beepTab[]= {
|
||||||
|
|
|
@ -23,10 +23,10 @@
|
||||||
#define BEEPER_H
|
#define BEEPER_H
|
||||||
|
|
||||||
extern uint8_t g_beepCnt;
|
extern uint8_t g_beepCnt;
|
||||||
extern uint8_t g_beepVal[5];
|
|
||||||
extern uint8_t beepAgain;
|
extern uint8_t beepAgain;
|
||||||
extern uint8_t beepAgainOrig;
|
extern uint8_t beepAgainOrig;
|
||||||
extern uint8_t beepOn;
|
extern uint8_t beepOn;
|
||||||
|
extern bool warble;
|
||||||
|
|
||||||
extern void beep(uint8_t val);
|
extern void beep(uint8_t val);
|
||||||
|
|
||||||
|
|
163
src/drivers.cpp
163
src/drivers.cpp
|
@ -35,7 +35,7 @@ inline void eeprom_write_byte()
|
||||||
{
|
{
|
||||||
EEAR = eeprom_pointer;
|
EEAR = eeprom_pointer;
|
||||||
EEDR = *eeprom_buffer_data;
|
EEDR = *eeprom_buffer_data;
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
EECR |= 1<<EEMPE;
|
EECR |= 1<<EEMPE;
|
||||||
EECR |= 1<<EEPE;
|
EECR |= 1<<EEPE;
|
||||||
#else
|
#else
|
||||||
|
@ -52,7 +52,7 @@ ISR(EE_READY_vect)
|
||||||
eeprom_write_byte();
|
eeprom_write_byte();
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
EECR &= ~(1<<EERIE);
|
EECR &= ~(1<<EERIE);
|
||||||
#else
|
#else
|
||||||
EECR &= ~(1<<EERIE);
|
EECR &= ~(1<<EERIE);
|
||||||
|
@ -72,7 +72,7 @@ void eeWriteBlockCmp(const void *i_pointer_ram, uint16_t i_pointer_eeprom, size_
|
||||||
|
|
||||||
#ifdef SIMU
|
#ifdef SIMU
|
||||||
sem_post(&eeprom_write_sem);
|
sem_post(&eeprom_write_sem);
|
||||||
#elif defined (PCBV3)
|
#elif defined (PCBV4)
|
||||||
EECR |= (1<<EERIE);
|
EECR |= (1<<EERIE);
|
||||||
#else
|
#else
|
||||||
EECR |= (1<<EERIE);
|
EECR |= (1<<EERIE);
|
||||||
|
@ -190,63 +190,117 @@ void Key::input(bool val, EnumKeys enuk)
|
||||||
|
|
||||||
bool keyState(EnumKeys enuk)
|
bool keyState(EnumKeys enuk)
|
||||||
{
|
{
|
||||||
if(enuk < (int)DIM(keys)) return keys[enuk].state() ? 1 : 0;
|
uint8_t result = 0 ;
|
||||||
|
|
||||||
|
if (enuk < (int)DIM(keys))
|
||||||
|
return keys[enuk].state() ? 1 : 0;
|
||||||
|
|
||||||
#if defined (PCBV4)
|
#if defined (PCBV4)
|
||||||
switch(enuk){
|
switch(enuk){
|
||||||
case SW_ElevDR : return PINC & (1<<INP_C_ElevDR);
|
case SW_ElevDR:
|
||||||
|
result = PINC & (1<<INP_C_ElevDR);
|
||||||
|
break;
|
||||||
|
|
||||||
case SW_AileDR : return PINC & (1<<INP_C_AileDR);
|
case SW_AileDR:
|
||||||
|
result = PINC & (1<<INP_C_AileDR);
|
||||||
|
break;
|
||||||
|
|
||||||
case SW_RuddDR : return PING & (1<<INP_G_RuddDR);
|
case SW_RuddDR:
|
||||||
|
result = PING & (1<<INP_G_RuddDR);
|
||||||
|
break;
|
||||||
// INP_G_ID1 INP_B_ID2
|
// INP_G_ID1 INP_B_ID2
|
||||||
// id0 0 1
|
// id0 0 1
|
||||||
// id1 1 1
|
// id1 1 1
|
||||||
// id2 1 0
|
// id2 1 0
|
||||||
case SW_ID0 : return !(PING & (1<<INP_G_ID1));
|
case SW_ID0:
|
||||||
case SW_ID1 : return (PING & (1<<INP_G_ID1))&& (PINB & (1<<INP_B_ID2));
|
result = !(PING & (1<<INP_G_ID1));
|
||||||
case SW_ID2 : return !(PINB & (1<<INP_B_ID2));
|
break;
|
||||||
|
|
||||||
case SW_Gear : return PING & (1<<INP_G_Gear);
|
case SW_ID1:
|
||||||
|
result = (PING & (1<<INP_G_ID1))&& (PINB & (1<<INP_B_ID2));
|
||||||
|
break;
|
||||||
|
|
||||||
case SW_ThrCt : return PING & (1<<INP_G_ThrCt);
|
case SW_ID2:
|
||||||
|
result = !(PINB & (1<<INP_B_ID2));
|
||||||
|
break;
|
||||||
|
|
||||||
case SW_Trainer: return PINB & (1<<INP_B_Trainer);
|
case SW_Gear:
|
||||||
|
result = PING & (1<<INP_G_Gear);
|
||||||
|
break;
|
||||||
|
|
||||||
default:;
|
case SW_ThrCt:
|
||||||
|
result = PING & (1<<INP_G_ThrCt);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case SW_Trainer:
|
||||||
|
result = PINB & (1<<INP_B_Trainer);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
switch(enuk){
|
switch(enuk){
|
||||||
case SW_ElevDR : return PINE & (1<<INP_E_ElevDR);
|
case SW_ElevDR:
|
||||||
|
result = PINE & (1<<INP_E_ElevDR);
|
||||||
|
break;
|
||||||
|
|
||||||
#if defined(JETI) || defined(FRSKY)
|
#if defined(JETI) || defined(FRSKY) || defined(ARDUPILOT) || defined(NMEA)
|
||||||
case SW_AileDR : return PINC & (1<<INP_C_AileDR); //shad974: rerouted inputs to free up UART0
|
case SW_AileDR:
|
||||||
|
result = PINC & (1<<INP_C_AileDR); //shad974: rerouted inputs to free up UART0
|
||||||
|
break;
|
||||||
#else
|
#else
|
||||||
case SW_AileDR : return PINE & (1<<INP_E_AileDR);
|
case SW_AileDR:
|
||||||
|
result = PINE & (1<<INP_E_AileDR);
|
||||||
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
case SW_RuddDR : return PING & (1<<INP_G_RuddDR);
|
case SW_RuddDR:
|
||||||
|
result = PING & (1<<INP_G_RuddDR);
|
||||||
|
break;
|
||||||
// INP_G_ID1 INP_E_ID2
|
// INP_G_ID1 INP_E_ID2
|
||||||
// id0 0 1
|
// id0 0 1
|
||||||
// id1 1 1
|
// id1 1 1
|
||||||
// id2 1 0
|
// id2 1 0
|
||||||
case SW_ID0 : return !(PING & (1<<INP_G_ID1));
|
case SW_ID0:
|
||||||
case SW_ID1 : return (PING & (1<<INP_G_ID1))&& (PINE & (1<<INP_E_ID2));
|
result = !(PING & (1<<INP_G_ID1));
|
||||||
case SW_ID2 : return !(PINE & (1<<INP_E_ID2));
|
break;
|
||||||
case SW_Gear : return PINE & (1<<INP_E_Gear);
|
|
||||||
|
case SW_ID1:
|
||||||
|
result = (PING & (1<<INP_G_ID1))&& (PINE & (1<<INP_E_ID2));
|
||||||
|
break;
|
||||||
|
|
||||||
|
case SW_ID2:
|
||||||
|
result = !(PINE & (1<<INP_E_ID2));
|
||||||
|
break;
|
||||||
|
|
||||||
|
case SW_Gear:
|
||||||
|
result = PINE & (1<<INP_E_Gear);
|
||||||
|
break;
|
||||||
|
|
||||||
//case SW_ThrCt : return PINE & (1<<INP_E_ThrCt);
|
//case SW_ThrCt : return PINE & (1<<INP_E_ThrCt);
|
||||||
|
|
||||||
#if defined(JETI) || defined(FRSKY)
|
#if defined(JETI) || defined(FRSKY) || defined(ARDUPILOT) || defined(NMEA)
|
||||||
case SW_ThrCt : return PINC & (1<<INP_C_ThrCt); //shad974: rerouted inputs to free up UART0
|
case SW_ThrCt:
|
||||||
|
result = PINC & (1<<INP_C_ThrCt); //shad974: rerouted inputs to free up UART0
|
||||||
|
break;
|
||||||
|
|
||||||
#else
|
#else
|
||||||
case SW_ThrCt : return PINE & (1<<INP_E_ThrCt);
|
case SW_ThrCt:
|
||||||
|
result = PINE & (1<<INP_E_ThrCt);
|
||||||
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
case SW_Trainer: return PINE & (1<<INP_E_Trainer);
|
case SW_Trainer:
|
||||||
default:;
|
result = PINE & (1<<INP_E_Trainer);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
#endif // defined (PCBV4)
|
#endif // defined (PCBV4)
|
||||||
return 0;
|
|
||||||
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
void pauseEvents(uint8_t event)
|
void pauseEvents(uint8_t event)
|
||||||
|
@ -265,7 +319,7 @@ volatile uint16_t g_tmr10ms;
|
||||||
volatile uint8_t g_blinkTmr10ms;
|
volatile uint8_t g_blinkTmr10ms;
|
||||||
|
|
||||||
|
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
uint8_t g_ms100 = 0; // global to allow time set function to reset to zero
|
uint8_t g_ms100 = 0; // global to allow time set function to reset to zero
|
||||||
#endif
|
#endif
|
||||||
void per10ms()
|
void per10ms()
|
||||||
|
@ -273,7 +327,7 @@ void per10ms()
|
||||||
g_tmr10ms++;
|
g_tmr10ms++;
|
||||||
g_blinkTmr10ms++;
|
g_blinkTmr10ms++;
|
||||||
|
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
/* Update gloabal Date/Time every 100 per10ms cycles */
|
/* Update gloabal Date/Time every 100 per10ms cycles */
|
||||||
if (++g_ms100 == 100)
|
if (++g_ms100 == 100)
|
||||||
{
|
{
|
||||||
|
@ -286,7 +340,7 @@ void per10ms()
|
||||||
uint8_t enuk = KEY_MENU;
|
uint8_t enuk = KEY_MENU;
|
||||||
|
|
||||||
// User buttons ...
|
// User buttons ...
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
/* Original keys were connected to PORTB as follows:
|
/* Original keys were connected to PORTB as follows:
|
||||||
|
|
||||||
Bit Key
|
Bit Key
|
||||||
|
@ -346,7 +400,6 @@ void per10ms()
|
||||||
// End User buttons
|
// End User buttons
|
||||||
|
|
||||||
// Trim switches ...
|
// Trim switches ...
|
||||||
#if defined (PCBV3)
|
|
||||||
#if defined (PCBV4)
|
#if defined (PCBV4)
|
||||||
static prog_uchar APM crossTrim[]={
|
static prog_uchar APM crossTrim[]={
|
||||||
1<<INP_J_TRM_LH_DWN,
|
1<<INP_J_TRM_LH_DWN,
|
||||||
|
@ -358,21 +411,7 @@ void per10ms()
|
||||||
1<<INP_J_TRM_RH_DWN,
|
1<<INP_J_TRM_RH_DWN,
|
||||||
1<<INP_J_TRM_RH_UP
|
1<<INP_J_TRM_RH_UP
|
||||||
};
|
};
|
||||||
# else
|
|
||||||
static prog_uchar APM crossTrim[]={
|
|
||||||
1<<TRIM_M_RV_DWN,
|
|
||||||
1<<TRIM_M_RV_UP,
|
|
||||||
1<<TRIM_M_RH_DWN,
|
|
||||||
1<<TRIM_M_RH_UP,
|
|
||||||
1<<TRIM_M_LH_DWN,
|
|
||||||
1<<TRIM_M_LH_UP,
|
|
||||||
1<<TRIM_M_LV_DWN,
|
|
||||||
1<<TRIM_M_LV_UP
|
|
||||||
};
|
|
||||||
# endif
|
|
||||||
|
|
||||||
#else // stock original board ...
|
#else // stock original board ...
|
||||||
|
|
||||||
static prog_uchar APM crossTrim[]={
|
static prog_uchar APM crossTrim[]={
|
||||||
1<<INP_D_TRM_LH_DWN, // bit 7
|
1<<INP_D_TRM_LH_DWN, // bit 7
|
||||||
1<<INP_D_TRM_LH_UP,
|
1<<INP_D_TRM_LH_UP,
|
||||||
|
@ -385,39 +424,13 @@ void per10ms()
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined (PCBV3)
|
|
||||||
|
|
||||||
#if defined (PCBV4)
|
#if defined (PCBV4)
|
||||||
in = ~PINJ;
|
in = ~PINJ;
|
||||||
#else
|
#else
|
||||||
PORTD = ~KEY_Y2; // select Y2 row. (Bits 3:0 LVD / LVU / LHU / LHD)
|
|
||||||
_delay_us(1);
|
|
||||||
in = ~PIND & 0xf0; // mask out outputs
|
|
||||||
|
|
||||||
PORTD = ~KEY_Y3; // select Y3 row. (Bits 3:0 RHU / RHD / RVD / RVU)
|
|
||||||
_delay_us(1);
|
|
||||||
in |= ((~PIND & 0xf0) >> 4);
|
|
||||||
|
|
||||||
PORTD = 0xFF;
|
|
||||||
# endif
|
|
||||||
|
|
||||||
#else
|
|
||||||
|
|
||||||
in = ~PIND;
|
in = ~PIND;
|
||||||
|
|
||||||
// Legacy support for USART1 free hardware mod [DEPRECATED]
|
|
||||||
# if defined(USART1FREED)
|
|
||||||
// mask out original INP_D_TRM_LV_UP and INP_D_TRM_LV_DWN bits
|
|
||||||
in &= ~((1<<INP_D_TRM_LV_UP) | (1<<INP_D_TRM_LV_DWN));
|
|
||||||
|
|
||||||
// merge in the two new switch port values
|
|
||||||
in |= (~PINC & (1<<INP_C_TRM_LV_UP)) ? (1<<INP_D_TRM_LV_UP) : 0;
|
|
||||||
in |= (~PING & (1<<INP_G_TRM_LV_DWN)) ? (1<<INP_D_TRM_LV_DWN) : 0;
|
|
||||||
# endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
for(int i=0; i<8; i++)
|
for (int i=0; i<8; i++) {
|
||||||
{
|
|
||||||
// INP_D_TRM_RH_UP 0 .. INP_D_TRM_LH_UP 7
|
// INP_D_TRM_RH_UP 0 .. INP_D_TRM_LH_UP 7
|
||||||
keys[enuk].input(in & pgm_read_byte(crossTrim+i),(EnumKeys)enuk);
|
keys[enuk].input(in & pgm_read_byte(crossTrim+i),(EnumKeys)enuk);
|
||||||
++enuk;
|
++enuk;
|
||||||
|
@ -443,7 +456,7 @@ void per10ms()
|
||||||
frskyStreaming--;
|
frskyStreaming--;
|
||||||
}
|
}
|
||||||
else if (g_eeGeneral.enableTelemetryAlarm && (g_model.frsky.channels[0].ratio || g_model.frsky.channels[1].ratio)) {
|
else if (g_eeGeneral.enableTelemetryAlarm && (g_model.frsky.channels[0].ratio || g_model.frsky.channels[1].ratio)) {
|
||||||
#if defined (BEEPSPKR)
|
#if defined (AUDIO)
|
||||||
if (!(g_tmr10ms % 30)) {
|
if (!(g_tmr10ms % 30)) {
|
||||||
audioDefevent(AU_WARNING1);
|
audioDefevent(AU_WARNING1);
|
||||||
}
|
}
|
||||||
|
|
|
@ -28,7 +28,7 @@
|
||||||
// bs=16 128 blocks verlust link:128 16files:16*8 128 sum 256
|
// 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
|
// bs=32 64 blocks verlust link: 64 16files:16*16 256 sum 320
|
||||||
//
|
//
|
||||||
#if defined(PCBV3)
|
#if defined(PCBV4)
|
||||||
// 4096 - 16 bytes to give 255 blocks, since we can't address 256 block in an 8-bit register
|
// 4096 - 16 bytes to give 255 blocks, since we can't address 256 block in an 8-bit register
|
||||||
#define EESIZE 4080
|
#define EESIZE 4080
|
||||||
#else
|
#else
|
||||||
|
|
|
@ -24,7 +24,7 @@
|
||||||
|
|
||||||
enum EnumTabDiag {
|
enum EnumTabDiag {
|
||||||
e_Setup,
|
e_Setup,
|
||||||
#if defined(PCBV3)
|
#if defined(PCBV4)
|
||||||
e_FrskyTime,
|
e_FrskyTime,
|
||||||
#endif
|
#endif
|
||||||
e_Trainer,
|
e_Trainer,
|
||||||
|
@ -35,7 +35,7 @@ enum EnumTabDiag {
|
||||||
};
|
};
|
||||||
|
|
||||||
void menuProcSetup(uint8_t event);
|
void menuProcSetup(uint8_t event);
|
||||||
#if defined(PCBV3)
|
#if defined(PCBV4)
|
||||||
void menuProcTime(uint8_t event);
|
void menuProcTime(uint8_t event);
|
||||||
#endif
|
#endif
|
||||||
void menuProcTrainer(uint8_t event);
|
void menuProcTrainer(uint8_t event);
|
||||||
|
@ -46,7 +46,7 @@ void menuProcDiagCalib(uint8_t event);
|
||||||
|
|
||||||
MenuFuncP_PROGMEM APM menuTabDiag[] = {
|
MenuFuncP_PROGMEM APM menuTabDiag[] = {
|
||||||
menuProcSetup,
|
menuProcSetup,
|
||||||
#if defined(PCBV3)
|
#if defined(PCBV4)
|
||||||
menuProcTime,
|
menuProcTime,
|
||||||
#endif
|
#endif
|
||||||
menuProcTrainer,
|
menuProcTrainer,
|
||||||
|
@ -61,7 +61,7 @@ enum menuProcSetupItems {
|
||||||
#ifdef SPLASH
|
#ifdef SPLASH
|
||||||
ITEM_SETUP_SPLASH,
|
ITEM_SETUP_SPLASH,
|
||||||
#endif
|
#endif
|
||||||
#ifdef BEEPSPKR
|
#ifdef AUDIO
|
||||||
ITEM_SETUP_SPEAKER,
|
ITEM_SETUP_SPEAKER,
|
||||||
#endif
|
#endif
|
||||||
#ifdef HAPTIC
|
#ifdef HAPTIC
|
||||||
|
@ -93,7 +93,7 @@ void menuProcSetup(uint8_t event)
|
||||||
if((y+=FH)>7*FH) return;
|
if((y+=FH)>7*FH) return;
|
||||||
}subN++;
|
}subN++;
|
||||||
|
|
||||||
#ifdef BEEPSPKR
|
#ifdef AUDIO
|
||||||
if(s_pgOfs<subN) {
|
if(s_pgOfs<subN) {
|
||||||
lcd_puts_P(0, y, PSTR("Speaker Pitch"));
|
lcd_puts_P(0, y, PSTR("Speaker Pitch"));
|
||||||
lcd_outdezAtt(PARAM_OFS,y,g_eeGeneral.speakerPitch,(sub==subN ? INVERS : 0)|LEFT);
|
lcd_outdezAtt(PARAM_OFS,y,g_eeGeneral.speakerPitch,(sub==subN ? INVERS : 0)|LEFT);
|
||||||
|
@ -287,7 +287,7 @@ void menuProcSetup(uint8_t event)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
#if defined(PCBV3)
|
#if defined(PCBV4)
|
||||||
// SD card interface contains Real-Time-Clock chip
|
// SD card interface contains Real-Time-Clock chip
|
||||||
void menuProcTime(uint8_t event)
|
void menuProcTime(uint8_t event)
|
||||||
{
|
{
|
||||||
|
|
|
@ -158,6 +158,12 @@ void menuMainView(uint8_t event)
|
||||||
#if defined(JETI)
|
#if defined(JETI)
|
||||||
JETI_EnableRXD(); // enable JETI-Telemetry reception
|
JETI_EnableRXD(); // enable JETI-Telemetry reception
|
||||||
chainMenu(menuProcJeti);
|
chainMenu(menuProcJeti);
|
||||||
|
#elif defined(ARDUPILOT)
|
||||||
|
ARDUPILOT_EnableRXD(); // enable ArduPilot-Telemetry reception
|
||||||
|
chainMenu(menuProcArduPilot);
|
||||||
|
#elif defined(NMEA)
|
||||||
|
NMEA_EnableRXD(); // enable NMEA-Telemetry reception
|
||||||
|
chainMenu(menuProcNMEA);
|
||||||
#else
|
#else
|
||||||
chainMenu(menuProcDebug);
|
chainMenu(menuProcDebug);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -102,7 +102,7 @@ int16_t checkIncDec(uint8_t event, int16_t val, int16_t i_min, int16_t i_max, ui
|
||||||
if(newval != val){
|
if(newval != val){
|
||||||
if(newval==0) {
|
if(newval==0) {
|
||||||
pauseEvents(event); // delay before auto-repeat continues
|
pauseEvents(event); // delay before auto-repeat continues
|
||||||
if (newval>val) // TODO check if without BEEPSPKR it's optimized!
|
if (newval>val) // TODO check if without AUDIO it's optimized!
|
||||||
AUDIO_KEYPAD_UP();
|
AUDIO_KEYPAD_UP();
|
||||||
else
|
else
|
||||||
AUDIO_KEYPAD_DOWN();
|
AUDIO_KEYPAD_DOWN();
|
||||||
|
|
824
src/nmea.cpp
Normal file
824
src/nmea.cpp
Normal file
|
@ -0,0 +1,824 @@
|
||||||
|
/*
|
||||||
|
*
|
||||||
|
* Author - Karl Szmutny <shadow@privy.de>
|
||||||
|
* Author - Uphiearl and Jean-Pierre PARISY
|
||||||
|
* Modified to accept NMEA records GGA and RMC - ReSt and Jean-Pierre PARISY
|
||||||
|
*
|
||||||
|
* 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"
|
||||||
|
#include "menus.h"
|
||||||
|
|
||||||
|
#define LG_BUF 14
|
||||||
|
#define NB_LONG_BUF 3
|
||||||
|
#define NB_SHORT_BUF 3
|
||||||
|
#define LONG_BUF(val) (val)
|
||||||
|
#define SHORT_BUF(val) (val+NB_LONG_BUF)
|
||||||
|
#define VALSTR(val) (rbuf[val][0] ? rbuf[val] : val_unknown)
|
||||||
|
#define APSIZE (BSS | DBLSIZE)
|
||||||
|
|
||||||
|
uint8_t i; // working variable
|
||||||
|
uint8_t state; // currrent state
|
||||||
|
uint8_t rval, rpack; // received items
|
||||||
|
uint8_t xval[NB_LONG_BUF+NB_SHORT_BUF]; // expected value
|
||||||
|
uint8_t xpack[NB_LONG_BUF+NB_SHORT_BUF]; // expected packet
|
||||||
|
uint8_t ibuf[NB_LONG_BUF]; // subscripts on long buffers values
|
||||||
|
char rbuf[NB_LONG_BUF][LG_BUF]; // long receive buffers
|
||||||
|
char sbuf[NB_SHORT_BUF]; // short receive buffers
|
||||||
|
const char val_unknown[] = "?";
|
||||||
|
int32_t home_alt, save_alt, rel_alt, prev_alt, lift_alt, max_alt, abs_alt; // integer values for altitude computations
|
||||||
|
int32_t gpstimer=0;
|
||||||
|
int32_t gpstime;
|
||||||
|
uint8_t ggareceived;
|
||||||
|
uint8_t beep_on;
|
||||||
|
uint8_t show_timer;
|
||||||
|
|
||||||
|
/* Received data
|
||||||
|
Data are received as packets, each packet is identified by a prefix of seven
|
||||||
|
characters ('$GPGGA,' or '$GPRMC,')and is ended by one star plus two bytes checksum.
|
||||||
|
The values are terminated by a comma.
|
||||||
|
|
||||||
|
$GPGGA - Global Positioning System Fix Data, Time, Position and fix related data fora GPS receiver.
|
||||||
|
|
||||||
|
11
|
||||||
|
1 2 3 4 5 6 7 8 9 10 | 12 13 14 15
|
||||||
|
| | | | | | | | | | | | | | |
|
||||||
|
GGA,hhmmss.ss,llll.ll,a,yyyyy.yy,a,x,xx,x.x,x.x,M,x.x,M,x.x,xxxx*hh<CR><LF>
|
||||||
|
|
||||||
|
Field Number:
|
||||||
|
1) Universal Time Coordinated (UTC)
|
||||||
|
2) Latitude
|
||||||
|
3) N or S (North or South)
|
||||||
|
4) Longitude
|
||||||
|
5) E or W (East or West)
|
||||||
|
6) GPS Quality Indicator,
|
||||||
|
0 - fix not available,
|
||||||
|
1 - GPS fix,
|
||||||
|
2 - Differential GPS fix
|
||||||
|
7) Number of satellites in view, 00 - 12
|
||||||
|
8) Horizontal Dilution of precision
|
||||||
|
9) Antenna Altitude above/below mean-sea-level (geoid)
|
||||||
|
10) Units of antenna altitude, meters
|
||||||
|
11) Geoidal separation, the difference between the WGS-84 earth
|
||||||
|
ellipsoid and mean-sea-level (geoid), "-" means mean-sea-level
|
||||||
|
below ellipsoid
|
||||||
|
12) Units of geoidal separation, meters
|
||||||
|
13) Age of differential GPS data, time in seconds since last SC104
|
||||||
|
type 1 or 9 update, null field when DGPS is not used
|
||||||
|
14) Differential reference station ID, 0000-1023
|
||||||
|
*
|
||||||
|
15) Checksum
|
||||||
|
CrLf
|
||||||
|
|
||||||
|
|
||||||
|
$GPRMC - Recommended Minimum Navigation Information
|
||||||
|
12
|
||||||
|
1 2 3 4 5 6 7 8 9 10 11|
|
||||||
|
| | | | | | | | | | | |
|
||||||
|
RMC,hhmmss.ss,A,llll.ll,a,yyyyy.yy,a,x.x,x.x,xxxx,x.x,a*hh<CR><LF>
|
||||||
|
|
||||||
|
Field Number:
|
||||||
|
1) UTC Time
|
||||||
|
2) Status, V = Navigation receiver warning
|
||||||
|
3) Latitude
|
||||||
|
4) N or S
|
||||||
|
5) Longitude
|
||||||
|
6) E or W
|
||||||
|
7) Speed over ground, knots
|
||||||
|
8) Track made good, degrees true. = = Course over ground (COG)
|
||||||
|
9) Date, ddmmyy
|
||||||
|
10) Magnetic Variation, degrees
|
||||||
|
11) E or W
|
||||||
|
12) Checksum
|
||||||
|
*/
|
||||||
|
|
||||||
|
// GGA record prefix
|
||||||
|
#define PACK_GGA 0x47 // "G"
|
||||||
|
#define PACK_GGA3 0x41 // "A"
|
||||||
|
// value occurence number in the GGA packet
|
||||||
|
#define TIM 1
|
||||||
|
#define LAT 2
|
||||||
|
#define NOS 3
|
||||||
|
#define LON 4
|
||||||
|
#define EOW 5
|
||||||
|
#define FIX 6
|
||||||
|
#define SAT 7
|
||||||
|
#define DIL 8
|
||||||
|
#define ALT 9
|
||||||
|
#define MTR 10
|
||||||
|
#define GEO 11
|
||||||
|
#define MET 12
|
||||||
|
#define AGE 13
|
||||||
|
#define DIF 14
|
||||||
|
|
||||||
|
// RMC record prefix
|
||||||
|
#define PACK_RMC 0x52 // "R"
|
||||||
|
#define PACK_RMC2 0x4D // "M"
|
||||||
|
#define PACK_RMC3 0x43 // "C"
|
||||||
|
// value occurence number in the RMC packet
|
||||||
|
#define TIM 1
|
||||||
|
#define NRW 2
|
||||||
|
#define LT1 3
|
||||||
|
#define NSO 4
|
||||||
|
#define LN1 5
|
||||||
|
#define EWE 6
|
||||||
|
#define SOG 7
|
||||||
|
#define COG 8
|
||||||
|
#define DAT 9
|
||||||
|
#define MAG 10
|
||||||
|
#define EAW 11
|
||||||
|
|
||||||
|
// end of packet
|
||||||
|
#define PACK_END 0x2a // *
|
||||||
|
// end of value
|
||||||
|
#define VAL_END 0x2c // ,
|
||||||
|
|
||||||
|
// stateful machine
|
||||||
|
|
||||||
|
// Since the packets are sent continuously, we need to synchronize on the
|
||||||
|
// reception of the three chars prefixing a packet, whatever they are.
|
||||||
|
|
||||||
|
// states values
|
||||||
|
#define WAIT_PACKET 1
|
||||||
|
#define WAIT_PACK_GGA1 2
|
||||||
|
#define WAIT_PACK_GGA2 3
|
||||||
|
#define WAIT_PACK_GGA3 4
|
||||||
|
#define WAIT_PACK_RMC2 5
|
||||||
|
#define WAIT_PACK_RMC3 6
|
||||||
|
#define WAIT_VAL_END 7
|
||||||
|
#define READ_VALUE 8
|
||||||
|
|
||||||
|
void menuProcNMEA1(uint8_t event);
|
||||||
|
void menuProcNMEA2(uint8_t event);
|
||||||
|
void menuProcNMEA3(uint8_t event);
|
||||||
|
void menuProcNMEA4(uint8_t event);
|
||||||
|
void title(char x);
|
||||||
|
void initval(uint8_t num, uint8_t pack, uint8_t val);
|
||||||
|
int32_t binary (char *str);
|
||||||
|
int32_t bintime (char *str);
|
||||||
|
|
||||||
|
#ifndef SIMU
|
||||||
|
ISR (USART0_RX_vect)
|
||||||
|
{
|
||||||
|
uint8_t rl;
|
||||||
|
uint8_t rh; //USART control and Status Register 0 B
|
||||||
|
uint8_t iostat; //USART control and Status Register 0 A
|
||||||
|
|
||||||
|
rl = UDR0;
|
||||||
|
iostat = UCSR0A; //USART control and Status Register 0 A
|
||||||
|
/*
|
||||||
|
bit 7 6 5 4 3 2 1 0
|
||||||
|
RxC0 TxC0 UDRE0 FE0 DOR0 UPE0 U2X0 MPCM0
|
||||||
|
|
||||||
|
RxC0: Receive complete
|
||||||
|
TXC0: Transmit Complete
|
||||||
|
UDRE0: USART Data Register Empty
|
||||||
|
FE0: Frame Error
|
||||||
|
DOR0: Data OverRun
|
||||||
|
UPE0: USART Parity Error
|
||||||
|
U2X0: Double Tx Speed
|
||||||
|
MPCM0: MultiProcessor Comms Mode
|
||||||
|
*/
|
||||||
|
if (iostat & ((1 << FE0) | (1 << DOR0) | (1 << UPE0)))
|
||||||
|
{
|
||||||
|
rl = xpack[0] = xpack[1] = xval[0] = xval[1] = 0;
|
||||||
|
initval (LONG_BUF(2), PACK_GGA, TIM); // always get UTC time for timer
|
||||||
|
state = WAIT_PACKET; // restart on error
|
||||||
|
}
|
||||||
|
rh = UCSR0B; //USART control and Status Register 0 B
|
||||||
|
/* bit 7 6 5 4 3 2 1 0
|
||||||
|
RxCIE0 TxCIE0 UDRIE0 RXEN0 TXEN0 UCSZ02 RXB80 TXB80
|
||||||
|
|
||||||
|
RxCIE0: Receive complete int enable
|
||||||
|
TXCIE0: Transmit Complete int enable
|
||||||
|
UDRIE0: USART Data Register Empty int enable
|
||||||
|
RXEN0: Rx enable
|
||||||
|
TXEN0: Tx Enable
|
||||||
|
UCSZ02: Character Size bit 2
|
||||||
|
RXB80: Rx data bit 8
|
||||||
|
TXB80: Tx data bit 8
|
||||||
|
*/
|
||||||
|
switch (state)
|
||||||
|
{
|
||||||
|
case WAIT_PACKET:
|
||||||
|
switch (rl)
|
||||||
|
{
|
||||||
|
case PACK_GGA: // found a new GGA packet "G"
|
||||||
|
state = WAIT_PACK_GGA2; // wait for the 2nd char
|
||||||
|
break;
|
||||||
|
case PACK_RMC: // found a new RMS packet "R"
|
||||||
|
state = WAIT_PACK_RMC2; // wait for the 2nd char
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case WAIT_PACK_GGA2: // received 2nd char "G"
|
||||||
|
if (rl == PACK_GGA)
|
||||||
|
state = WAIT_PACK_GGA3; // wait for 3rd character "A"
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not "G"
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_GGA3: // received 3rd char "A"
|
||||||
|
if (rl == PACK_GGA3) // found
|
||||||
|
{
|
||||||
|
state = WAIT_VAL_END; // wait for ","
|
||||||
|
rpack = PACK_GGA;
|
||||||
|
rval = 1; //clear the buffer
|
||||||
|
for (i = 0; i < NB_LONG_BUF; i++)
|
||||||
|
ibuf[i] = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
|
||||||
|
case WAIT_PACK_RMC2: // wait for 2nd char "M"
|
||||||
|
if (rl == PACK_RMC2)
|
||||||
|
state = WAIT_PACK_RMC3;
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
case WAIT_PACK_RMC3: // wait for 3rd char "C"
|
||||||
|
if (rl == PACK_RMC3)
|
||||||
|
{
|
||||||
|
state = WAIT_VAL_END; // wait for ","
|
||||||
|
rpack = PACK_RMC;
|
||||||
|
rval = 1;
|
||||||
|
for (i = 0; i < NB_LONG_BUF; i++) // clear buffer
|
||||||
|
ibuf[i] = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
|
||||||
|
case WAIT_VAL_END:
|
||||||
|
if (rl == VAL_END) // "," nach "GGA" oder "RMC"
|
||||||
|
{
|
||||||
|
state = READ_VALUE;
|
||||||
|
rval = 1;
|
||||||
|
for (i = 0; i < NB_LONG_BUF; i++) // clear buffer
|
||||||
|
ibuf[i] = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
state = WAIT_PACKET; // restart if not found
|
||||||
|
break;
|
||||||
|
|
||||||
|
|
||||||
|
case READ_VALUE:
|
||||||
|
switch (rl)
|
||||||
|
{
|
||||||
|
case PACK_END:
|
||||||
|
if (rpack == PACK_GGA)
|
||||||
|
ggareceived = 1;
|
||||||
|
state = WAIT_PACKET; // packet completed, wait for the next packet
|
||||||
|
break;
|
||||||
|
case VAL_END: // comma found, value completed
|
||||||
|
rval++; // and get next value
|
||||||
|
break;
|
||||||
|
default: // store the char in the corresponding buffer
|
||||||
|
for (i = 0; i < NB_LONG_BUF; i++)
|
||||||
|
{ // is it the expected value in the expected packet ?
|
||||||
|
if (rpack == xpack[i] && rval == xval[i] && ibuf[i] < LG_BUF - 1)
|
||||||
|
{ // yes, store the char
|
||||||
|
rbuf[i] [ibuf[i]] = rl;
|
||||||
|
ibuf[i]++;
|
||||||
|
rbuf[i] [ibuf[i]] = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
for (i = NB_LONG_BUF; i < NB_LONG_BUF+NB_SHORT_BUF; i++) {
|
||||||
|
if (rpack == xpack[i] // is this the expected short value in the expected packet ?
|
||||||
|
&& rval == xval[i])
|
||||||
|
sbuf[i-NB_LONG_BUF] = rl; // yes, store the char
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void NMEA_Init (void)
|
||||||
|
{
|
||||||
|
#ifndef SIMU
|
||||||
|
DDRE &= ~(1 << DDE0); // set RXD0 pin as input
|
||||||
|
PORTE &= ~(1 << PORTE0); // disable pullup on RXD0 pin
|
||||||
|
|
||||||
|
// switch (Telem_baud)
|
||||||
|
// {
|
||||||
|
// case 1:
|
||||||
|
#undef BAUD
|
||||||
|
#define BAUD 4800
|
||||||
|
#include <util/setbaud.h>
|
||||||
|
UBRR0H = UBRRH_VALUE;
|
||||||
|
UBRR0L = UBRRL_VALUE;
|
||||||
|
// break;
|
||||||
|
// }
|
||||||
|
|
||||||
|
UCSR0A &= ~(1 << U2X0); // disable double speed operation
|
||||||
|
// set 8N1
|
||||||
|
UCSR0B = 0|(0<< RXCIE0)|(0<<TXCIE0)|(0<<UDRIE0)|(0<<RXEN0)|(0<<TXEN0)|(0<<UCSZ02);
|
||||||
|
UCSR0C = 0|(1 << UCSZ01) | (1 << UCSZ00);
|
||||||
|
while ( UCSR0A & (1 << RXC0) )
|
||||||
|
UDR0; // flush receive buffer
|
||||||
|
#endif
|
||||||
|
home_alt = rel_alt = ggareceived =0;
|
||||||
|
gpstimer = -1;
|
||||||
|
beep_on=1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// TX Capabilities are not required for NMEA
|
||||||
|
// void NMEA_DisableTXD (void)
|
||||||
|
// {
|
||||||
|
// UCSR0B &= ~(1 << TXEN0); // disable TX
|
||||||
|
// }
|
||||||
|
|
||||||
|
// void NMEA_EnableTXD (void)
|
||||||
|
// {
|
||||||
|
// UCSR0B |= (1 << TXEN0); // enable TX
|
||||||
|
// }
|
||||||
|
|
||||||
|
void NMEA_DisableRXD (void)
|
||||||
|
{
|
||||||
|
UCSR0B &= ~(1 << RXEN0); // disable RX
|
||||||
|
UCSR0B &= ~(1 << RXCIE0); // disable Interrupt
|
||||||
|
}
|
||||||
|
|
||||||
|
void NMEA_EnableRXD (void)
|
||||||
|
{
|
||||||
|
for (i = 0; i < NB_LONG_BUF; i++)
|
||||||
|
{
|
||||||
|
ibuf[i] = 0;
|
||||||
|
rbuf[i][0] = 0;
|
||||||
|
xpack[i] = 0;
|
||||||
|
xval[i] = 0;
|
||||||
|
}
|
||||||
|
initval (LONG_BUF(2), PACK_GGA, TIM); // always get UTC time for timer
|
||||||
|
state = WAIT_PACKET; // wait for the next packet
|
||||||
|
UCSR0B |= (1 << RXEN0); // enable RX
|
||||||
|
UCSR0B |= (1 << RXCIE0); // enable Interrupt
|
||||||
|
}
|
||||||
|
|
||||||
|
void menuProcNMEA(uint8_t event)
|
||||||
|
{
|
||||||
|
menuProcNMEA1(event);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Start of NMEA menus 1-4 <<<<<<<<<<<<<<<<<<<<<<<<<<<
|
||||||
|
|
||||||
|
void menuProcNMEA1(uint8_t event)
|
||||||
|
{
|
||||||
|
switch(event) // new event received, branch accordingly
|
||||||
|
{
|
||||||
|
case EVT_KEY_BREAK(KEY_LEFT):
|
||||||
|
chainMenu(menuProcNMEA4);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_BREAK(KEY_RIGHT):
|
||||||
|
chainMenu(menuProcNMEA2);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_LONG(KEY_UP):
|
||||||
|
NMEA_DisableRXD();
|
||||||
|
chainMenu(menuProcStatistic);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_LONG(KEY_DOWN):
|
||||||
|
NMEA_DisableRXD();
|
||||||
|
chainMenu(menuMainView);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_MENU):
|
||||||
|
if (show_timer == 0) {
|
||||||
|
show_timer = 1;
|
||||||
|
if (gpstimer <= 0)
|
||||||
|
gpstimer = bintime(rbuf[2]);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
show_timer = 0;
|
||||||
|
break;
|
||||||
|
case EVT_KEY_FIRST(KEY_EXIT):
|
||||||
|
if ((show_timer == 1) &&(rbuf[2][0]))
|
||||||
|
gpstimer = bintime(rbuf[2]); // get actual GPS time ->resets timer to 00:00
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
/*
|
||||||
|
How to use:
|
||||||
|
|
||||||
|
You choose the values to be displayed using the function:
|
||||||
|
|
||||||
|
initval(<number>, <packet>, <value>);
|
||||||
|
-------------------------------------
|
||||||
|
|
||||||
|
That means that "<value>" of "<packet>" is stored in the <number> buffer.
|
||||||
|
The first <number> is 0.
|
||||||
|
|
||||||
|
Here are the packet names and the associated value names:
|
||||||
|
|
||||||
|
Position packet (beginning with "GGA"): "PACK_GGA"
|
||||||
|
value names: "TIM", "LAT", "NOS", "LON", "EOW", "FIX", "SAT", "DIL", "ALT", "MTR", "GEO", "MET", "AGE", "DIF",
|
||||||
|
|
||||||
|
Required minimum packet (beginning with "RMC"): "PACK_RMC"
|
||||||
|
value names: "TIM", "NRW", "LT1", "NSO", "LN1", "EWE", "SOG", "COG", "DAT", "MAG", "EAW"
|
||||||
|
|
||||||
|
The buffers are accessed using the macro "VALSTR(<n>)", where "<n>" is "0"
|
||||||
|
for the first buffer, and "1" for the second buffer.
|
||||||
|
|
||||||
|
When a value is missing, it is replaced by the contents of val_unknown ("?").
|
||||||
|
*/
|
||||||
|
|
||||||
|
if (ggareceived)
|
||||||
|
{
|
||||||
|
gpstime=bintime(rbuf[2]);
|
||||||
|
ggareceived=0;
|
||||||
|
}
|
||||||
|
|
||||||
|
initval (LONG_BUF(0), PACK_RMC, TIM); // sets rbuf[0][.]
|
||||||
|
initval (LONG_BUF(1), PACK_RMC, DAT); // sets rbuf[1][.]
|
||||||
|
initval (SHORT_BUF(0), PACK_RMC, NRW); // sets sbuf[0]
|
||||||
|
initval (SHORT_BUF(2), PACK_GGA, SAT); // -> sbuf[2]
|
||||||
|
|
||||||
|
|
||||||
|
title ('1');
|
||||||
|
lcd_puts_P ( 2*FW, 1*FH, PSTR("UTC-Time Sat"));
|
||||||
|
|
||||||
|
if (rbuf[0][0]) { // show always if data have been received
|
||||||
|
lcd_putcAtt ( 19*FW, 1*FH, sbuf[2], 0); // satellites in view
|
||||||
|
lcd_putsnAtt ( 2*FW, 2*FH, &rbuf[0][0], 2, APSIZE); // hours
|
||||||
|
lcd_putcAtt ( 6*FW, 2*FH, ':', DBLSIZE); // ":"
|
||||||
|
lcd_putsnAtt ( 8*FW, 2*FH, &rbuf[0][2], 2, APSIZE); // minutes
|
||||||
|
lcd_putcAtt ( 12*FW, 2*FH, ':', DBLSIZE); // ":"
|
||||||
|
lcd_putsnAtt ( 14*FW, 2*FH, &rbuf[0][4], 2, APSIZE); // seconds
|
||||||
|
}
|
||||||
|
else
|
||||||
|
lcd_putsAtt ( 2*FW, 2*FH, val_unknown, APSIZE); // "?"
|
||||||
|
|
||||||
|
if ((show_timer == 1) && rbuf[0][0]) { // show the Timer when data have been received
|
||||||
|
|
||||||
|
lcd_puts_P ( 2*FW, 4*FH, PSTR("Timer")); // display "Timer"
|
||||||
|
putsTime ( 5*FW, 5*FH, (gpstime-gpstimer), DBLSIZE, DBLSIZE); // display difference as mm:ss
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
lcd_puts_P ( 2*FW, 4*FH, PSTR("Date")); // show the UTC Date
|
||||||
|
|
||||||
|
if (rbuf[1][0]) {
|
||||||
|
lcd_putsnAtt( 2*FW, 5*FH, &rbuf[1][0], 2, APSIZE); // year
|
||||||
|
lcd_putcAtt ( 6*FW, 5*FH, '/', DBLSIZE); // "/"
|
||||||
|
lcd_putsnAtt( 8*FW, 5*FH, &rbuf[1][2], 2, APSIZE); // month
|
||||||
|
lcd_putcAtt (12*FW, 5*FH, '/', DBLSIZE); // "/"
|
||||||
|
lcd_putsnAtt(14*FW, 5*FH, &rbuf[1][4], 2, APSIZE); // day
|
||||||
|
}
|
||||||
|
else
|
||||||
|
lcd_putsAtt ( 2*FW, 5*FH, val_unknown, APSIZE); // "?"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void menuProcNMEA2(uint8_t event)
|
||||||
|
{
|
||||||
|
static uint8_t ignore_break;
|
||||||
|
|
||||||
|
|
||||||
|
switch(event)
|
||||||
|
{
|
||||||
|
// Menu navigation
|
||||||
|
case EVT_KEY_BREAK(KEY_LEFT):
|
||||||
|
if (ignore_break==1) {
|
||||||
|
ignore_break=0;
|
||||||
|
break;}
|
||||||
|
chainMenu(menuProcNMEA1);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_BREAK(KEY_RIGHT):
|
||||||
|
if (ignore_break==1) {
|
||||||
|
ignore_break=0;
|
||||||
|
break;}
|
||||||
|
chainMenu(menuProcNMEA3);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_LONG(KEY_UP):
|
||||||
|
NMEA_DisableRXD();
|
||||||
|
chainMenu(menuProcStatistic);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_LONG(KEY_DOWN):
|
||||||
|
NMEA_DisableRXD();
|
||||||
|
chainMenu(menuMainView);
|
||||||
|
break;
|
||||||
|
|
||||||
|
//Beep setting
|
||||||
|
case EVT_KEY_LONG(KEY_LEFT):
|
||||||
|
ignore_break = 1;
|
||||||
|
beep_on=0;
|
||||||
|
AUDIO_MENUS(); // short blip
|
||||||
|
break;
|
||||||
|
case EVT_KEY_LONG(KEY_RIGHT):
|
||||||
|
ignore_break = 1;
|
||||||
|
beep_on=1;
|
||||||
|
AUDIO_MENUS(); // short blip
|
||||||
|
break;
|
||||||
|
|
||||||
|
//Altitude setting
|
||||||
|
/* Set a home position for altitude. Normally used before starting
|
||||||
|
the model when GPS has got a fix.
|
||||||
|
MENU[short] --> alternating relative and absolute altitudes
|
||||||
|
MENU[long] --> set home altitude to current
|
||||||
|
EXIT[long] --> reset max altitude to 0
|
||||||
|
|
||||||
|
Switch ON / OFF short beep with positive lift
|
||||||
|
LEFT[long] --> Positive lift Beep off
|
||||||
|
RIGHT[long] --> Positive lift Beep on */
|
||||||
|
|
||||||
|
|
||||||
|
case EVT_KEY_BREAK(KEY_MENU):
|
||||||
|
if (ignore_break==1) {
|
||||||
|
ignore_break=0;
|
||||||
|
break;}
|
||||||
|
|
||||||
|
if (!home_alt) // umschalten zwischen absoluter und relativer Höhe
|
||||||
|
home_alt = save_alt;
|
||||||
|
else
|
||||||
|
home_alt=0;
|
||||||
|
|
||||||
|
if (save_alt==0) // wenn noch keine Home Höhe gesetzt war, wird sie es jetzt, weil sonst
|
||||||
|
// das Umschalten keine Wirkung zeigt
|
||||||
|
save_alt = home_alt = abs_alt; // absolute altitude
|
||||||
|
AUDIO_MENUS(); // short blip for non negative lift
|
||||||
|
break;
|
||||||
|
|
||||||
|
case EVT_KEY_LONG(KEY_MENU):
|
||||||
|
ignore_break = 1;
|
||||||
|
save_alt = home_alt = abs_alt; // Home altitude auf aktuelle absolute Höhe setzen
|
||||||
|
AUDIO_MENUS(); // short blip for non negative lift
|
||||||
|
break;
|
||||||
|
|
||||||
|
case EVT_KEY_LONG(KEY_EXIT): // Max Altitude auf 0 zurücksetzen
|
||||||
|
max_alt=0;
|
||||||
|
AUDIO_MENUS(); // short blip for non negative lift
|
||||||
|
break;
|
||||||
|
|
||||||
|
}
|
||||||
|
title ('2');
|
||||||
|
|
||||||
|
lcd_puts_P ( 1*FW, 1*FH, PSTR("Altitude Sat Max"));
|
||||||
|
|
||||||
|
|
||||||
|
lcd_puts_P ( 16*FW, 3*FH, PSTR("Home"));
|
||||||
|
lcd_puts_P ( 2*FW, 4*FH, PSTR("Lift") );
|
||||||
|
|
||||||
|
lcd_puts_P ( 16*FW, 5*FH, PSTR("Beep") );
|
||||||
|
if (beep_on==1)
|
||||||
|
lcd_puts_P ( 18*FW, 6*FH, PSTR("ON") );
|
||||||
|
|
||||||
|
else
|
||||||
|
lcd_puts_P ( 17*FW, 6*FH, PSTR("OFF") );
|
||||||
|
|
||||||
|
|
||||||
|
lcd_outdezNAtt( 20*FW, 4*FH, home_alt, PREC1, 6); // display home_alt, small characters
|
||||||
|
|
||||||
|
if (xpack[0] != PACK_GGA)
|
||||||
|
ggareceived = 0;
|
||||||
|
|
||||||
|
initval (LONG_BUF(0), PACK_GGA, ALT); // -> rbuf[0]
|
||||||
|
initval (LONG_BUF(1), PACK_GGA, GEO); // -> rbuf[1]
|
||||||
|
initval (SHORT_BUF(0), PACK_GGA, MTR); // -> sbuf[0]
|
||||||
|
initval (SHORT_BUF(1), PACK_GGA, FIX); // -> sbuf[1]
|
||||||
|
initval (SHORT_BUF(2), PACK_GGA, SAT); // -> sbuf[2]
|
||||||
|
|
||||||
|
if (ggareceived) // at least one second has elapsed
|
||||||
|
{
|
||||||
|
ggareceived = 0;
|
||||||
|
|
||||||
|
/* ALT and GEO have one single digit following the decimal point
|
||||||
|
e.g. ALT=359.7 GEO=47.7
|
||||||
|
The altitude over mean sea level is to be calculated as:
|
||||||
|
altitude minus geoidal separation
|
||||||
|
*/
|
||||||
|
|
||||||
|
abs_alt = binary(rbuf[0]) - binary(rbuf[1]); // alt - geo that is absolute altitude
|
||||||
|
|
||||||
|
if (abs_alt> max_alt) max_alt=abs_alt; // hold max altitude relative to 0 m
|
||||||
|
|
||||||
|
rel_alt=abs_alt - home_alt; // alt - geo - home altitude relative to home
|
||||||
|
|
||||||
|
|
||||||
|
lift_alt = rel_alt - prev_alt;
|
||||||
|
prev_alt = rel_alt;
|
||||||
|
|
||||||
|
if ((lift_alt >= 0) && (sbuf[1]>0x30) && beep_on) // GGA record must have Fix> 0
|
||||||
|
AUDIO_MENUS(); // short blip for non negative lift
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (rbuf[0][0]) {
|
||||||
|
lcd_putcAtt ( 13*FW, 1*FH, sbuf[2], 0); // satellites in view
|
||||||
|
|
||||||
|
if (sbuf[1]>0x30) { // & GGA has FIX > 0
|
||||||
|
|
||||||
|
|
||||||
|
lcd_outdezNAtt( 10*FW, 2*FH, rel_alt, DBLSIZE|PREC1, 7); // altitude
|
||||||
|
|
||||||
|
if (home_alt >= 0)
|
||||||
|
lcd_outdezNAtt( 20*FW, 2*FH, (max_alt-home_alt), PREC1, 6); // display small characters
|
||||||
|
else
|
||||||
|
lcd_outdezNAtt( 20*FW, 2*FH, max_alt, PREC1, 6); // display small characters
|
||||||
|
|
||||||
|
|
||||||
|
lcd_putcAtt ( 11*FW, 3*FH, sbuf[0], 0); // dimension [m]
|
||||||
|
|
||||||
|
lcd_outdezNAtt( 10*FW, 5*FH, lift_alt, DBLSIZE|PREC1, 6); // lift
|
||||||
|
lcd_putcAtt ( 11*FW, 6*FH, sbuf[0], 0); // dimension [m/S]
|
||||||
|
lcd_puts_P ( 12*FW, 6*FH, PSTR("/S") );
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
lcd_putsAtt ( 2*FW, 2*FH, val_unknown, APSIZE);
|
||||||
|
lcd_putsAtt ( 2*FW, 5*FH, val_unknown, APSIZE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void menuProcNMEA3(uint8_t event)
|
||||||
|
{
|
||||||
|
switch(event)
|
||||||
|
{
|
||||||
|
case EVT_KEY_BREAK(KEY_LEFT):
|
||||||
|
chainMenu(menuProcNMEA2);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_BREAK(KEY_RIGHT):
|
||||||
|
chainMenu(menuProcNMEA4);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_LONG(KEY_UP):
|
||||||
|
NMEA_DisableRXD();
|
||||||
|
chainMenu(menuProcStatistic);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_LONG(KEY_DOWN):
|
||||||
|
NMEA_DisableRXD();
|
||||||
|
chainMenu(menuMainView);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
initval (LONG_BUF(0), PACK_RMC, SOG);
|
||||||
|
initval (LONG_BUF(1), PACK_RMC, COG);
|
||||||
|
initval (SHORT_BUF(2), PACK_GGA, SAT); // -> sbuf[2]
|
||||||
|
title ('3');
|
||||||
|
lcd_puts_P ( 0*FW, 1*FH, PSTR("GrndSpeed[knt] Sat"));
|
||||||
|
if (rbuf[0][0]) // if first position is 00, buffer is empty, taken as false
|
||||||
|
{ // any other value is true
|
||||||
|
uint8_t i = 0;
|
||||||
|
while (rbuf[0][i])
|
||||||
|
{
|
||||||
|
if (rbuf[0][i] == '.') // find decimal point and insert End of String 3 positions higher
|
||||||
|
{
|
||||||
|
rbuf[0][i+3] = 0;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
lcd_putsAtt ( 2*FW, 2*FH, VALSTR(0), APSIZE); // speed over ground
|
||||||
|
}
|
||||||
|
else
|
||||||
|
lcd_putsAtt ( 2*FW, 2*FH, val_unknown, APSIZE);
|
||||||
|
|
||||||
|
lcd_putcAtt ( 19*FW, 1*FH, sbuf[2], 0); // satellites in view
|
||||||
|
|
||||||
|
lcd_puts_P ( 1*FW, 4*FH, PSTR("Course over ground") );
|
||||||
|
lcd_putsAtt ( 2*FW, 5*FH, VALSTR(1), APSIZE); // course over ground
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void menuProcNMEA4(uint8_t event)
|
||||||
|
{
|
||||||
|
switch(event) // new event received, branch accordingly
|
||||||
|
{
|
||||||
|
case EVT_KEY_BREAK(KEY_LEFT):
|
||||||
|
chainMenu(menuProcNMEA3);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_BREAK(KEY_RIGHT):
|
||||||
|
chainMenu(menuProcNMEA1);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_LONG(KEY_UP):
|
||||||
|
NMEA_DisableRXD();
|
||||||
|
chainMenu(menuProcStatistic);
|
||||||
|
break;
|
||||||
|
case EVT_KEY_LONG(KEY_DOWN):
|
||||||
|
NMEA_DisableRXD();
|
||||||
|
chainMenu(menuMainView);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
// expecting LAT value in POS packet to be stored in the first buffer
|
||||||
|
initval (LONG_BUF(0), PACK_GGA, LAT);
|
||||||
|
initval (SHORT_BUF(0), PACK_GGA, NOS);
|
||||||
|
// and LON value in POS packet stored in the second buffer
|
||||||
|
initval (LONG_BUF(1), PACK_GGA, LON);
|
||||||
|
initval (SHORT_BUF(1), PACK_GGA, EOW);
|
||||||
|
initval (SHORT_BUF(2), PACK_GGA, SAT); // -> sbuf[2]
|
||||||
|
// title of the screen
|
||||||
|
title ('4');
|
||||||
|
lcd_puts_P ( 3*FW, 1*FH, PSTR("Latitude Sat")); // line 1 column 3
|
||||||
|
// first buffer into line 2 column 2
|
||||||
|
if (rbuf[0][0])
|
||||||
|
{
|
||||||
|
lcd_putcAtt ( 13*FW, 1*FH, sbuf[0], 0); // N or S
|
||||||
|
lcd_putcAtt ( 19*FW, 1*FH, sbuf[2], 0); // satellites in view
|
||||||
|
lcd_putsnAtt ( 1*FW, 2*FH, rbuf[0], 2, APSIZE);
|
||||||
|
lcd_putcAtt ( 5*FW, 2*FH, '@',0);
|
||||||
|
lcd_putsAtt ( 6*FW, 2*FH, &rbuf[0][2], APSIZE); // minutes with small decimal point
|
||||||
|
}
|
||||||
|
else
|
||||||
|
lcd_putsAtt ( 2*FW, 2*FH, val_unknown, APSIZE);
|
||||||
|
lcd_puts_P ( 3*FW, 4*FH, PSTR("Longitude")); // line 4 column 5
|
||||||
|
// second buffer into line 5 column 2
|
||||||
|
if (rbuf[0][0])
|
||||||
|
{
|
||||||
|
lcd_putcAtt ( 13*FW, 4*FH, sbuf[1], 0); // E or W
|
||||||
|
lcd_putsnAtt ( 0*FW, 5*FH, rbuf[1], 3, APSIZE);
|
||||||
|
lcd_putcAtt ( 6*FW, 5*FH, '@',0);
|
||||||
|
lcd_putsAtt ( 7*FW, 5*FH, &rbuf[1][3], APSIZE); // minutes with small decimal point
|
||||||
|
|
||||||
|
}
|
||||||
|
else
|
||||||
|
lcd_putsAtt ( 2*FW, 5*FH, val_unknown, APSIZE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void title(char x)
|
||||||
|
{
|
||||||
|
lcd_putsAtt (0*FW, 0*FH, PSTR(" GPS NMEA data ?/4 "), INVERS);
|
||||||
|
lcd_putcAtt(16*FW, 0*FH, x, INVERS);
|
||||||
|
}
|
||||||
|
|
||||||
|
void initval(uint8_t num, uint8_t pack, uint8_t val)
|
||||||
|
{
|
||||||
|
if (xpack[num] != pack || xval[num] != val)
|
||||||
|
{
|
||||||
|
if (num < NB_LONG_BUF) {
|
||||||
|
ibuf[num] = rbuf[num][0] = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
sbuf[num-NB_LONG_BUF] = '?';
|
||||||
|
xpack[num] = pack;
|
||||||
|
xval[num] = val;
|
||||||
|
state = WAIT_PACKET; // synchronize to the next packet
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int32_t binary (char *str)
|
||||||
|
{
|
||||||
|
int32_t numval = 0;
|
||||||
|
uint8_t sign = 0;
|
||||||
|
|
||||||
|
while (*str) {
|
||||||
|
if (*str == '-')
|
||||||
|
sign = 1;
|
||||||
|
else if (*str >= '0' && *str <= '9')
|
||||||
|
numval = numval * 10 + (*str - '0');
|
||||||
|
str++;
|
||||||
|
}
|
||||||
|
if (sign)
|
||||||
|
numval = -numval;
|
||||||
|
return numval;
|
||||||
|
}
|
||||||
|
|
||||||
|
int32_t bintime (char *str)
|
||||||
|
{
|
||||||
|
int32_t numval=0;
|
||||||
|
|
||||||
|
if (*str) {
|
||||||
|
numval = ((str[0] - '0') * 10l) + (str[1] - '0'); // hours
|
||||||
|
numval = numval * 3600l;
|
||||||
|
numval = numval + ((( (str[2] - '0') * 10l) + (str[3] - '0')) * 60l); // minutes
|
||||||
|
numval = numval + ((str[4] - '0') * 10l) + (str[5] - '0'); // seconds
|
||||||
|
}
|
||||||
|
return numval;
|
||||||
|
}
|
||||||
|
/*
|
||||||
|
Without NMEA:
|
||||||
|
|
||||||
|
Size after:
|
||||||
|
AVR Memory Usage
|
||||||
|
----------------
|
||||||
|
Device: atmega64
|
||||||
|
|
||||||
|
Program: 54226 bytes (82.7% Full)
|
||||||
|
(.text + .data + .bootloader)
|
||||||
|
|
||||||
|
Data: 3440 bytes (84.0% Full)
|
||||||
|
(.data + .bss + .noinit)
|
||||||
|
|
||||||
|
----------------------------------
|
||||||
|
|
||||||
|
With NMEA:
|
||||||
|
|
||||||
|
Size after:
|
||||||
|
AVR Memory Usage
|
||||||
|
----------------
|
||||||
|
Device: atmega64
|
||||||
|
|
||||||
|
Program: 57098 bytes (87.1% Full)
|
||||||
|
(.text + .data + .bootloader)
|
||||||
|
|
||||||
|
Data: 3524 bytes (86.0% Full)
|
||||||
|
(.data + .bss + .noinit)
|
||||||
|
*/
|
25
src/nmea.h
Normal file
25
src/nmea.h
Normal file
|
@ -0,0 +1,25 @@
|
||||||
|
/*
|
||||||
|
* Author - Philip Moss
|
||||||
|
* Adapted from frsky.h code by Jean-Pierre PARISY
|
||||||
|
*
|
||||||
|
*
|
||||||
|
* 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 nmea_h
|
||||||
|
#define nmea_h
|
||||||
|
|
||||||
|
void NMEA_Init(void);
|
||||||
|
void NMEA_EnableRXD (void);
|
||||||
|
void menuProcNMEA(uint8_t event);
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -41,7 +41,7 @@ const prog_char APM STR_OPEN9X[] =
|
||||||
#if defined(DSM2)
|
#if defined(DSM2)
|
||||||
TR_DSM2MODE
|
TR_DSM2MODE
|
||||||
#endif
|
#endif
|
||||||
#if defined(PCBV3)
|
#if defined(PCBV4)
|
||||||
TR_RE1RE2
|
TR_RE1RE2
|
||||||
TR_DATETIME
|
TR_DATETIME
|
||||||
#endif
|
#endif
|
||||||
|
@ -190,7 +190,7 @@ const prog_char APM STR_MENUSERROR[] = TR_MENUSERROR;
|
||||||
|
|
||||||
const prog_char APM STR_MENURADIOSETUP[] = TR_MENURADIOSETUP;
|
const prog_char APM STR_MENURADIOSETUP[] = TR_MENURADIOSETUP;
|
||||||
|
|
||||||
#ifdef PCBV3
|
#ifdef PCBV4
|
||||||
const prog_char APM STR_MENUDATEANDTIME[] = TR_MENUDATEANDTIME;
|
const prog_char APM STR_MENUDATEANDTIME[] = TR_MENUDATEANDTIME;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -66,7 +66,7 @@ extern const PROGMEM char STR_OPEN9X[];
|
||||||
#else
|
#else
|
||||||
#define OFS_ENDDSM2 (OFS_VTMRMODES + PSIZE(TR_VTMRMODES))
|
#define OFS_ENDDSM2 (OFS_VTMRMODES + PSIZE(TR_VTMRMODES))
|
||||||
#endif
|
#endif
|
||||||
#if defined(PCBV3)
|
#if defined(PCBV4)
|
||||||
#define OFS_RE1RE2 (OFS_ENDDSM2)
|
#define OFS_RE1RE2 (OFS_ENDDSM2)
|
||||||
#define OFS_DATETIME (OFS_RE1RE2 + PSIZE(TR_RE1RE2))
|
#define OFS_DATETIME (OFS_RE1RE2 + PSIZE(TR_RE1RE2))
|
||||||
#endif
|
#endif
|
||||||
|
@ -119,7 +119,7 @@ extern const PROGMEM char STR_OPEN9X[];
|
||||||
#define STR_DSM2MODE (STR_OPEN9X + OFS_DSM2MODE)
|
#define STR_DSM2MODE (STR_OPEN9X + OFS_DSM2MODE)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(PCBV3)
|
#if defined(PCBV4)
|
||||||
#define STR_RE1RE2 (STR_OPEN9X + OFS_RE1RE2)
|
#define STR_RE1RE2 (STR_OPEN9X + OFS_RE1RE2)
|
||||||
#define STR_DATETIME (STR_OPEN9X + OFS_DATETIME)
|
#define STR_DATETIME (STR_OPEN9X + OFS_DATETIME)
|
||||||
#endif
|
#endif
|
||||||
|
|
157
src/open9x.cpp
157
src/open9x.cpp
|
@ -30,7 +30,7 @@ prog_uchar APM speMarker[] = { "SPE" };
|
||||||
#include "menus.h"
|
#include "menus.h"
|
||||||
|
|
||||||
// MM/SD card Disk IO Support
|
// MM/SD card Disk IO Support
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
gtime_t g_unixTime; // Global date/time register, incremented each second in per10ms()
|
gtime_t g_unixTime; // Global date/time register, incremented each second in per10ms()
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -51,21 +51,18 @@ uint16_t g_timeMain;
|
||||||
uint16_t g_time_per10;
|
uint16_t g_time_per10;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined (PCBSTD) && defined (BEEPSPKR)
|
#if defined (PCBSTD) && defined (AUDIO)
|
||||||
uint8_t toneFreq = BEEP_DEFAULT_FREQ;
|
uint8_t toneFreq = BEEP_DEFAULT_FREQ;
|
||||||
uint8_t toneOn = false;
|
uint8_t toneOn = false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
bool warble = false; // TODO is it needed with BEEPSPKR?
|
#ifdef AUDIO
|
||||||
|
|
||||||
#ifdef BEEPSPKR
|
|
||||||
//new audio object
|
//new audio object
|
||||||
audioQueue audio;
|
audioQueue audio;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
uint8_t heartbeat;
|
uint8_t heartbeat;
|
||||||
|
|
||||||
// TODO reduce these tabs
|
|
||||||
const prog_char APM s_charTab[] = "_-.,";
|
const prog_char APM s_charTab[] = "_-.,";
|
||||||
|
|
||||||
//R=1
|
//R=1
|
||||||
|
@ -471,21 +468,6 @@ uint8_t getTrimFlightPhase(uint8_t idx, uint8_t phase)
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined (PCBV3) && !defined (PCBV4)
|
|
||||||
// The ugly scanned keys thing should be gone for PCBV4+. In the meantime ...
|
|
||||||
uint8_t keyDown()
|
|
||||||
{
|
|
||||||
uint8_t in;
|
|
||||||
PORTD = ~1; // select KEY_Y0 row (Bits 3:2 EXIT:MENU)
|
|
||||||
_delay_us(1);
|
|
||||||
in = (~PIND & 0b11000000) >> 5;
|
|
||||||
PORTD = ~2; // select Y1 row. (Bits 3:0 Left/Right/Up/Down)
|
|
||||||
_delay_us(1);
|
|
||||||
in |= (~PIND & 0xf0) >> 1;
|
|
||||||
PORTD = 0xff;
|
|
||||||
return (in);
|
|
||||||
}
|
|
||||||
#else
|
|
||||||
FORCEINLINE uint8_t keyDown()
|
FORCEINLINE uint8_t keyDown()
|
||||||
{
|
{
|
||||||
#if defined (PCBV4)
|
#if defined (PCBV4)
|
||||||
|
@ -494,7 +476,6 @@ FORCEINLINE uint8_t keyDown()
|
||||||
return (~PINB) & 0x7E;
|
return (~PINB) & 0x7E;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
void clearKeyEvents()
|
void clearKeyEvents()
|
||||||
{
|
{
|
||||||
|
@ -729,7 +710,7 @@ uint8_t checkTrim(uint8_t event)
|
||||||
|
|
||||||
setTrimValue(phase, idx, after);
|
setTrimValue(phase, idx, after);
|
||||||
|
|
||||||
#if defined (BEEPSPKR)
|
#if defined (AUDIO)
|
||||||
// toneFreq higher/lower according to trim position
|
// toneFreq higher/lower according to trim position
|
||||||
// limit the frequency, range -125 to 125 = toneFreq: 19 to 101
|
// limit the frequency, range -125 to 125 = toneFreq: 19 to 101
|
||||||
if (after > TRIM_MAX)
|
if (after > TRIM_MAX)
|
||||||
|
@ -742,18 +723,18 @@ uint8_t checkTrim(uint8_t event)
|
||||||
|
|
||||||
if (beepTrim) {
|
if (beepTrim) {
|
||||||
killEvents(event);
|
killEvents(event);
|
||||||
warble = false;
|
#if defined (AUDIO)
|
||||||
#if defined (BEEPSPKR)
|
|
||||||
audio.event(AU_TRIM_MOVE, after);
|
audio.event(AU_TRIM_MOVE, after);
|
||||||
#else
|
#else
|
||||||
|
warble = false;
|
||||||
AUDIO_WARNING2();
|
AUDIO_WARNING2();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
if (event & _MSK_KEY_REPT) warble = true;
|
#if defined (AUDIO)
|
||||||
#if defined (BEEPSPKR)
|
|
||||||
audio.event(AU_TRIM_MOVE, after);
|
audio.event(AU_TRIM_MOVE, after);
|
||||||
#else
|
#else
|
||||||
|
if (event & _MSK_KEY_REPT) warble = true;
|
||||||
AUDIO_TRIM();
|
AUDIO_TRIM();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -762,7 +743,11 @@ uint8_t checkTrim(uint8_t event)
|
||||||
return event;
|
return event;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifndef SIMU
|
#ifdef SIMU
|
||||||
|
|
||||||
|
uint16_t BandGap = 225;
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
// #define STARTADCONV (ADCSRA = (1<<ADEN) | (1<<ADPS0) | (1<<ADPS1) | (1<<ADPS2) | (1<<ADSC) | (1 << ADIE))
|
// #define STARTADCONV (ADCSRA = (1<<ADEN) | (1<<ADPS0) | (1<<ADPS1) | (1<<ADPS2) | (1<<ADSC) | (1 << ADIE))
|
||||||
// G: Note that the above would have set the ADC prescaler to 128, equating to
|
// G: Note that the above would have set the ADC prescaler to 128, equating to
|
||||||
|
@ -841,19 +826,7 @@ getADCp getADC[3] = {
|
||||||
|
|
||||||
void getADC_bandgap()
|
void getADC_bandgap()
|
||||||
{
|
{
|
||||||
#if defined(PCBSTD)
|
#if defined (PCBV4)
|
||||||
ADMUX=0x1E|ADC_VREF_TYPE; // Switch MUX to internal 1.22V reference
|
|
||||||
_delay_us(7); // short delay to stabilise reference voltage
|
|
||||||
ADCSRA|=0x40;
|
|
||||||
while ((ADCSRA & 0x10)==0);
|
|
||||||
ADCSRA|=0x10; // grab a sample
|
|
||||||
BandGap=ADCW;
|
|
||||||
#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 1.1V reference
|
|
||||||
_delay_us(10); // tiny bit of stablisation time needed to allow capture-hold capacitor to charge
|
|
||||||
// For times over-sample with no divide, x2 to end at a half averaged, x8. DON'T ASK mmmkay? :P This is how I want it.
|
// For times over-sample with no divide, x2 to end at a half averaged, x8. DON'T ASK mmmkay? :P This is how I want it.
|
||||||
ADCSRA|=0x40; while ((ADCSRA & 0x10)==0); ADCSRA|=0x10;
|
ADCSRA|=0x40; while ((ADCSRA & 0x10)==0); ADCSRA|=0x10;
|
||||||
BandGap=ADCW;
|
BandGap=ADCW;
|
||||||
|
@ -864,19 +837,19 @@ void getADC_bandgap()
|
||||||
ADCSRA|=0x40; while ((ADCSRA & 0x10)==0); ADCSRA|=0x10;
|
ADCSRA|=0x40; while ((ADCSRA & 0x10)==0); ADCSRA|=0x10;
|
||||||
BandGap+=ADCW;
|
BandGap+=ADCW;
|
||||||
BandGap *= 2;
|
BandGap *= 2;
|
||||||
|
|
||||||
ADCSRB |= (1<<MUX5);
|
ADCSRB |= (1<<MUX5);
|
||||||
#else
|
#else
|
||||||
ADMUX=0x1E|ADC_VREF_TYPE; // Switch MUX to internal 1.1V reference
|
// TODO is the next line needed (because it has been called before perMain)?
|
||||||
_delay_us(400); // this somewhat costly delay is the only remedy for stable results on the Atmega2560/1 chips
|
ADMUX=0x1E|ADC_VREF_TYPE; // Switch MUX to internal 1.22V reference
|
||||||
ADCSRA|=0x40; while ((ADCSRA & 0x10)==0); ADCSRA|=0x10; // take sample
|
ADCSRA|=0x40;
|
||||||
|
while ((ADCSRA & 0x10)==0);
|
||||||
|
ADCSRA|=0x10; // take sample
|
||||||
BandGap=ADCW;
|
BandGap=ADCW;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#else
|
#endif // SIMU
|
||||||
uint16_t BandGap = 225;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef BATT_UNSTABLE_BANDGAP
|
#ifndef BATT_UNSTABLE_BANDGAP
|
||||||
uint16_t abRunningAvg = 0;
|
uint16_t abRunningAvg = 0;
|
||||||
|
@ -892,7 +865,7 @@ FORCEINLINE bool checkSlaveMode()
|
||||||
{
|
{
|
||||||
// no power -> only phone jack = slave mode
|
// no power -> only phone jack = slave mode
|
||||||
|
|
||||||
#if defined(BUZZER_MOD) || defined(BEEPSPKR)
|
#if defined(PCBV4)
|
||||||
return SLAVE_MODE;
|
return SLAVE_MODE;
|
||||||
#else
|
#else
|
||||||
static bool lastSlaveMode = false;
|
static bool lastSlaveMode = false;
|
||||||
|
@ -1753,10 +1726,10 @@ uint8_t ppmInState = 0; //0=unsync 1..8= wait for value i-1
|
||||||
#ifndef SIMU
|
#ifndef SIMU
|
||||||
|
|
||||||
volatile uint8_t g_tmr16KHz; //continuous timer 16ms (16MHz/1024/256) -- 8-bit counter overflow
|
volatile uint8_t g_tmr16KHz; //continuous timer 16ms (16MHz/1024/256) -- 8-bit counter overflow
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
ISR(TIMER2_OVF_vect)
|
ISR(TIMER2_OVF_vect)
|
||||||
#else
|
#else
|
||||||
ISR(TIMER0_OVF_vect)
|
ISR(TIMER0_OVF_vect) // TODO now NOBLOCK in er9x
|
||||||
#endif
|
#endif
|
||||||
{
|
{
|
||||||
g_tmr16KHz++; // gruvin: Not 16KHz. Overflows occur at 61.035Hz (1/256th of 15.625KHz)
|
g_tmr16KHz++; // gruvin: Not 16KHz. Overflows occur at 61.035Hz (1/256th of 15.625KHz)
|
||||||
|
@ -1769,7 +1742,7 @@ uint16_t getTmr16KHz()
|
||||||
{
|
{
|
||||||
while(1){
|
while(1){
|
||||||
uint8_t hb = g_tmr16KHz;
|
uint8_t hb = g_tmr16KHz;
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
uint8_t lb = TCNT2;
|
uint8_t lb = TCNT2;
|
||||||
#else
|
#else
|
||||||
uint8_t lb = TCNT0;
|
uint8_t lb = TCNT0;
|
||||||
|
@ -1782,7 +1755,7 @@ uint16_t getTmr16KHz()
|
||||||
extern uint16_t g_time_per10; // instantiated in menus.cpp
|
extern uint16_t g_time_per10; // instantiated in menus.cpp
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
ISR(TIMER2_COMPA_vect, ISR_NOBLOCK) //10ms timer
|
ISR(TIMER2_COMPA_vect, ISR_NOBLOCK) //10ms timer
|
||||||
#else
|
#else
|
||||||
ISR(TIMER0_COMP_vect, ISR_NOBLOCK) //10ms timer
|
ISR(TIMER0_COMP_vect, ISR_NOBLOCK) //10ms timer
|
||||||
|
@ -1790,14 +1763,14 @@ ISR(TIMER0_COMP_vect, ISR_NOBLOCK) //10ms timer
|
||||||
{
|
{
|
||||||
cli();
|
cli();
|
||||||
|
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
static uint8_t accuracyWarble = 4; // becasue 16M / 1024 / 100 = 156.25. So bump every 4.
|
static uint8_t accuracyWarble = 4; // becasue 16M / 1024 / 100 = 156.25. So bump every 4.
|
||||||
uint8_t bump = (!(accuracyWarble++ & 0x03)) ? 157 : 156;
|
uint8_t bump = (!(accuracyWarble++ & 0x03)) ? 157 : 156;
|
||||||
TIMSK2 &= ~(1<<OCIE2A); //stop reentrance
|
TIMSK2 &= ~(1<<OCIE2A); //stop reentrance
|
||||||
OCR2A += bump;
|
OCR2A += bump;
|
||||||
#else
|
#else
|
||||||
TIMSK &= ~(1<<OCIE0); //stop reentrance
|
TIMSK &= ~(1<<OCIE0); //stop reentrance
|
||||||
#if defined (BEEPSPKR)
|
#if defined (AUDIO)
|
||||||
OCR0 += 2; // run much faster, to generate speaker tones
|
OCR0 += 2; // run much faster, to generate speaker tones
|
||||||
#else
|
#else
|
||||||
static uint8_t accuracyWarble = 4; // becasue 16M / 1024 / 100 = 156.25. So bump every 4.
|
static uint8_t accuracyWarble = 4; // becasue 16M / 1024 / 100 = 156.25. So bump every 4.
|
||||||
|
@ -1810,7 +1783,7 @@ ISR(TIMER0_COMP_vect, ISR_NOBLOCK) //10ms timer
|
||||||
|
|
||||||
AUDIO_HEARTBEAT();
|
AUDIO_HEARTBEAT();
|
||||||
|
|
||||||
#if defined (PCBSTD) && defined (BEEPSPKR)
|
#if defined (PCBSTD) && defined (AUDIO)
|
||||||
static uint8_t cnt10ms = 77; // execute 10ms code once every 78 ISRs
|
static uint8_t cnt10ms = 77; // execute 10ms code once every 78 ISRs
|
||||||
if (cnt10ms-- == 0) // BEGIN { ... every 10ms ... }
|
if (cnt10ms-- == 0) // BEGIN { ... every 10ms ... }
|
||||||
{
|
{
|
||||||
|
@ -1827,7 +1800,7 @@ ISR(TIMER0_COMP_vect, ISR_NOBLOCK) //10ms timer
|
||||||
|
|
||||||
per10ms();
|
per10ms();
|
||||||
|
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
disk_timerproc();
|
disk_timerproc();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -1841,12 +1814,12 @@ ISR(TIMER0_COMP_vect, ISR_NOBLOCK) //10ms timer
|
||||||
g_time_per10 = dt2 - dt; // NOTE: These spike to nearly 65535 just now and then. Why? :/
|
g_time_per10 = dt2 - dt; // NOTE: These spike to nearly 65535 just now and then. Why? :/
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined (PCBSTD) && defined (BEEPSPKR)
|
#if defined (PCBSTD) && defined (AUDIO)
|
||||||
} // end 10ms event
|
} // end 10ms event
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
cli();
|
cli();
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
TIMSK2 |= (1<<OCIE2A);
|
TIMSK2 |= (1<<OCIE2A);
|
||||||
#else
|
#else
|
||||||
TIMSK |= (1<<OCIE0);
|
TIMSK |= (1<<OCIE0);
|
||||||
|
@ -1866,7 +1839,7 @@ ISR(TIMER3_CAPT_vect) // G: High frequency noise can cause stack overflo with IS
|
||||||
uint16_t capture=ICR3;
|
uint16_t capture=ICR3;
|
||||||
|
|
||||||
// Prevent rentrance for this IRQ only
|
// Prevent rentrance for this IRQ only
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
TIMSK3 &= ~(1<<ICIE3);
|
TIMSK3 &= ~(1<<ICIE3);
|
||||||
#else
|
#else
|
||||||
ETIMSK &= ~(1<<TICIE3);
|
ETIMSK &= ~(1<<TICIE3);
|
||||||
|
@ -1896,7 +1869,7 @@ ISR(TIMER3_CAPT_vect) // G: High frequency noise can cause stack overflo with IS
|
||||||
lastCapt = capture;
|
lastCapt = capture;
|
||||||
|
|
||||||
cli(); // disable other interrupts for stack pops before this function's RETI
|
cli(); // disable other interrupts for stack pops before this function's RETI
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
TIMSK3 |= (1<<ICIE3);
|
TIMSK3 |= (1<<ICIE3);
|
||||||
#else
|
#else
|
||||||
ETIMSK |= (1<<TICIE3);
|
ETIMSK |= (1<<TICIE3);
|
||||||
|
@ -1911,7 +1884,7 @@ extern uint16_t g_timeMain;
|
||||||
// (reading from the .hex file), since a bug relating to Intel HEX file record
|
// (reading from the .hex file), since a bug relating to Intel HEX file record
|
||||||
// interpretation was fixed. However, I leave these commented out, just in case
|
// interpretation was fixed. However, I leave these commented out, just in case
|
||||||
// it causes trouble for others.
|
// it causes trouble for others.
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
// See fuses_2561.txt
|
// See fuses_2561.txt
|
||||||
FUSES =
|
FUSES =
|
||||||
{
|
{
|
||||||
|
@ -1989,7 +1962,7 @@ ISR(USART0_UDRE_vect)
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
/*---------------------------------------------------------*/
|
/*---------------------------------------------------------*/
|
||||||
/* User Provided Date/Time Function for FatFs module */
|
/* User Provided Date/Time Function for FatFs module */
|
||||||
/*---------------------------------------------------------*/
|
/*---------------------------------------------------------*/
|
||||||
|
@ -2126,19 +2099,13 @@ int main(void)
|
||||||
DDRJ = 0x00; PORTJ = 0xff; // 7-0:Trim switch inputs
|
DDRJ = 0x00; PORTJ = 0xff; // 7-0:Trim switch inputs
|
||||||
DDRK = 0x00; PORTK = 0x00; // anain. No pull-ups!
|
DDRK = 0x00; PORTK = 0x00; // anain. No pull-ups!
|
||||||
DDRL = 0x80; PORTL = 0x7f; // 7: Hold_PWR_On (1=On, default Off), 6:Jack_Presence_TTL, 5-0: User Button inputs
|
DDRL = 0x80; PORTL = 0x7f; // 7: Hold_PWR_On (1=On, default Off), 6:Jack_Presence_TTL, 5-0: User Button inputs
|
||||||
#else
|
|
||||||
# if defined (PCBV3)
|
|
||||||
DDRB = 0x97; PORTB = 0x1e; // 7:AUDIO, SD_CARD[6:SDA 5:SCL 4:CS 3:MISO 2:MOSI 1:SCK], 0:PPM_OUT
|
|
||||||
DDRC = 0x3f; PORTC = 0xc0; // PC0 used for LCD back light control
|
|
||||||
DDRD = 0x0F; PORTD = 0xff; // 7:4=inputs (keys/trims, pull-ups on), 3:0=outputs (keyscan row select)
|
|
||||||
#else
|
#else
|
||||||
DDRB = 0x81; PORTB = 0x7e; //pullups keys+nc
|
DDRB = 0x81; PORTB = 0x7e; //pullups keys+nc
|
||||||
DDRC = 0x3e; PORTC = 0xc1; //pullups nc
|
DDRC = 0x3e; PORTC = 0xc1; //pullups nc
|
||||||
DDRD = 0x00; PORTD = 0xff; //pullups keys
|
DDRD = 0x00; PORTD = 0xff; //pullups keys
|
||||||
# endif
|
|
||||||
DDRE = (1<<OUT_E_BUZZER); PORTE = 0xff-(1<<OUT_E_BUZZER); //pullups + buzzer 0
|
DDRE = (1<<OUT_E_BUZZER); PORTE = 0xff-(1<<OUT_E_BUZZER); //pullups + buzzer 0
|
||||||
DDRF = 0x00; PORTF = 0x00; //anain
|
DDRF = 0x00; PORTF = 0x00; //anain
|
||||||
DDRG = 0x10; PORTG = 0xfB; //pullups + SIM_CTL=1 = phonejack = ppm_in
|
DDRG = 0x10; PORTG = 0xfb; //pullups + SIM_CTL=1 = phonejack = ppm_in
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
lcd_init();
|
lcd_init();
|
||||||
|
@ -2150,7 +2117,7 @@ int main(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**** Set up timer/counter 0 ****/
|
/**** Set up timer/counter 0 ****/
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
/** Move old 64A Timer0 functions to Timer2 and use WGM on OC0(A) (PB7) for spkear tone output **/
|
/** Move old 64A Timer0 functions to Timer2 and use WGM on OC0(A) (PB7) for spkear tone output **/
|
||||||
|
|
||||||
// TCNT0 10ms = 16MHz/1024/156(.25) periodic timer (100ms interval)
|
// TCNT0 10ms = 16MHz/1024/156(.25) periodic timer (100ms interval)
|
||||||
|
@ -2167,7 +2134,7 @@ int main(void)
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
|
||||||
# if defined (BEEPSPKR)
|
# if defined (AUDIO)
|
||||||
// TCNT0 10ms = 16MHz/1024/2(/78) periodic timer (for speaker tone generation)
|
// TCNT0 10ms = 16MHz/1024/2(/78) periodic timer (for speaker tone generation)
|
||||||
// Capture ISR 7812.5/second -- runs per-10ms code segment once every 78
|
// Capture ISR 7812.5/second -- runs per-10ms code segment once every 78
|
||||||
// cycles (9.984ms). Timer overflows at about 61Hz or once every 16ms.
|
// cycles (9.984ms). Timer overflows at about 61Hz or once every 16ms.
|
||||||
|
@ -2184,26 +2151,6 @@ int main(void)
|
||||||
TIMSK |= (1<<OCIE0) | (1<<TOIE0); // Enable Output-Compare and Overflow interrrupts
|
TIMSK |= (1<<OCIE0) | (1<<TOIE0); // Enable Output-Compare and Overflow interrrupts
|
||||||
/********************************/
|
/********************************/
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// TCNT1 2MHz counter (auto-cleared) plus Capture Compare int.
|
|
||||||
// Used for PPM pulse generator
|
|
||||||
TCCR1B = (1 << WGM12) | (2<<CS10); // CTC OCR1A, 16MHz / 8
|
|
||||||
// not here ... TIMSK1 |= (1<<OCIE1A); ... enable immediately before mainloop
|
|
||||||
|
|
||||||
// TCNT3 (2MHz) used for PPM_IN pulse width capture
|
|
||||||
#if defined (PPMIN_MOD1) || (defined (PCBV3) && !defined (PCBV4))
|
|
||||||
// Noise Canceller enabled, pos. edge, clock at 16MHz / 8 (2MHz)
|
|
||||||
TCCR3B = (1<<ICNC3) | (1<<ICES3) | (0b010 << CS30);
|
|
||||||
#else
|
|
||||||
// Noise Canceller enabled, neg. edge, clock at 16MHz / 8 (2MHz) (Correct for PCB V4.x+ also)
|
|
||||||
TCCR3B = (1<<ICNC3) | (0b010 << CS30);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined (PCBV3)
|
|
||||||
TIMSK3 |= (1<<ICIE3); // Enable Timer 3 (PPM_IN) capture event interrupt
|
|
||||||
#else
|
|
||||||
ETIMSK |= (1<<TICIE3);
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Init Stack while interrupts are disabled
|
// Init Stack while interrupts are disabled
|
||||||
|
@ -2240,11 +2187,19 @@ int main(void)
|
||||||
JETI_Init();
|
JETI_Init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef ARDUPILOT
|
||||||
|
ARDUPILOT_Init();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef NMEA
|
||||||
|
NMEA_Init();
|
||||||
|
#endif
|
||||||
|
|
||||||
eeReadAll();
|
eeReadAll();
|
||||||
|
|
||||||
uint8_t cModel = g_eeGeneral.currModel;
|
uint8_t cModel = g_eeGeneral.currModel;
|
||||||
|
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
if (MCUSR != (1 << PORF)) {
|
if (MCUSR != (1 << PORF)) {
|
||||||
#else
|
#else
|
||||||
if (MCUCSR != (1 << PORF)) {
|
if (MCUCSR != (1 << PORF)) {
|
||||||
|
@ -2272,7 +2227,7 @@ int main(void)
|
||||||
|
|
||||||
if(cModel!=g_eeGeneral.currModel) eeDirty(EE_GENERAL); // if model was quick-selected, make sure it sticks
|
if(cModel!=g_eeGeneral.currModel) eeDirty(EE_GENERAL); // if model was quick-selected, make sure it sticks
|
||||||
|
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
// Initialise global unix timestamp with current time from RTC chip on SD card interface
|
// Initialise global unix timestamp with current time from RTC chip on SD card interface
|
||||||
RTC rtc;
|
RTC rtc;
|
||||||
struct gtm utm;
|
struct gtm utm;
|
||||||
|
@ -2315,10 +2270,22 @@ int main(void)
|
||||||
|
|
||||||
while(1){
|
while(1){
|
||||||
uint16_t t0 = getTmr16KHz();
|
uint16_t t0 = getTmr16KHz();
|
||||||
|
|
||||||
getADC[g_eeGeneral.filterInput]();
|
getADC[g_eeGeneral.filterInput]();
|
||||||
getADC_bandgap() ;
|
|
||||||
|
#if 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
|
||||||
|
#else
|
||||||
|
ADMUX = 0x1E|ADC_VREF_TYPE; // Switch MUX to internal reference
|
||||||
|
#endif
|
||||||
|
|
||||||
perMain();
|
perMain();
|
||||||
|
|
||||||
|
// Bandgap has had plenty of time to settle...
|
||||||
|
getADC_bandgap();
|
||||||
|
|
||||||
if(heartbeat == 0x3)
|
if(heartbeat == 0x3)
|
||||||
{
|
{
|
||||||
wdt_reset();
|
wdt_reset();
|
||||||
|
|
60
src/open9x.h
60
src/open9x.h
|
@ -28,7 +28,7 @@
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
#if defined(PCBV3)
|
#if defined(PCBV4)
|
||||||
#include "ff.h"
|
#include "ff.h"
|
||||||
#include "gtime.h"
|
#include "gtime.h"
|
||||||
#endif
|
#endif
|
||||||
|
@ -83,6 +83,16 @@ extern uint16_t jeti_keys;
|
||||||
#include "frsky.h"
|
#include "frsky.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef ARDUPILOT
|
||||||
|
// ArduPilot Telemetry
|
||||||
|
#include "ardupilot.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef NMEA
|
||||||
|
// NMEA Telemetry
|
||||||
|
#include "nmea.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
extern RlcFile theFile; //used for any file operation
|
extern RlcFile theFile; //used for any file operation
|
||||||
|
|
||||||
// G: The following comments relate to the original stock PCB only
|
// G: The following comments relate to the original stock PCB only
|
||||||
|
@ -198,20 +208,14 @@ extern uint16_t DEBUG2;
|
||||||
|
|
||||||
#else // boards prior to v4 ...
|
#else // boards prior to v4 ...
|
||||||
|
|
||||||
|
#define OUT_B_LIGHT 7
|
||||||
#define INP_B_KEY_LFT 6
|
#define INP_B_KEY_LFT 6
|
||||||
#define INP_B_KEY_RGT 5
|
#define INP_B_KEY_RGT 5
|
||||||
#define INP_B_KEY_UP 4
|
#define INP_B_KEY_UP 4
|
||||||
#define INP_B_KEY_DWN 3
|
#define INP_B_KEY_DWN 3
|
||||||
#define INP_B_KEY_EXT 2
|
#define INP_B_KEY_EXT 2
|
||||||
#define INP_B_KEY_MEN 1
|
#define INP_B_KEY_MEN 1
|
||||||
//vinceofdrink@gmail harwared ppm
|
|
||||||
//Orginal bitbang port for PPM
|
|
||||||
# ifndef DPPMPB7_HARDWARE
|
|
||||||
#define OUT_B_PPM 0
|
#define OUT_B_PPM 0
|
||||||
# else
|
|
||||||
# define OUT_B_PPM 7 // will not be used
|
|
||||||
# endif
|
|
||||||
|
|
||||||
#define INP_D_TRM_LH_UP 7
|
#define INP_D_TRM_LH_UP 7
|
||||||
#define INP_D_TRM_LH_DWN 6
|
#define INP_D_TRM_LH_DWN 6
|
||||||
|
@ -222,16 +226,6 @@ extern uint16_t DEBUG2;
|
||||||
#define INP_D_TRM_RH_DWN 1
|
#define INP_D_TRM_RH_DWN 1
|
||||||
#define INP_D_TRM_RH_UP 0
|
#define INP_D_TRM_RH_UP 0
|
||||||
|
|
||||||
# if defined (PCBV3)
|
|
||||||
# define OUT_C_LIGHT 0
|
|
||||||
# else
|
|
||||||
# ifndef DPPMPB7_HARDWARE
|
|
||||||
# define OUT_B_LIGHT 7
|
|
||||||
# else
|
|
||||||
# define OUT_B_LIGHT 0
|
|
||||||
# endif
|
|
||||||
# endif
|
|
||||||
|
|
||||||
#define INP_E_PPM_IN 7
|
#define INP_E_PPM_IN 7
|
||||||
#define INP_E_ID2 6
|
#define INP_E_ID2 6
|
||||||
#define INP_E_Trainer 5
|
#define INP_E_Trainer 5
|
||||||
|
@ -241,7 +235,7 @@ extern uint16_t DEBUG2;
|
||||||
#define INP_E_AileDR 1
|
#define INP_E_AileDR 1
|
||||||
#define INP_E_ThrCt 0
|
#define INP_E_ThrCt 0
|
||||||
|
|
||||||
# if defined(JETI) || defined(FRSKY)
|
#if (defined(JETI) || defined(FRSKY) || defined(ARDUPILOT) || defined(NMEA))
|
||||||
#undef INP_E_ThrCt
|
#undef INP_E_ThrCt
|
||||||
#undef INP_E_AileDR
|
#undef INP_E_AileDR
|
||||||
#define INP_C_ThrCt 6
|
#define INP_C_ThrCt 6
|
||||||
|
@ -253,14 +247,6 @@ extern uint16_t DEBUG2;
|
||||||
#define INP_G_RF_POW 1
|
#define INP_G_RF_POW 1
|
||||||
#define INP_G_RuddDR 0
|
#define INP_G_RuddDR 0
|
||||||
|
|
||||||
// Legacy support for USART1 hardware mod [DEPRECATED]
|
|
||||||
// G: This board will be retired before much longer. But I still need it for now.
|
|
||||||
#if defined(USART1FREED)
|
|
||||||
// do not undef the original INP_D_TRM_LV_DWN/UP as we need them later
|
|
||||||
#define INP_C_TRM_LV_UP 0
|
|
||||||
#define INP_G_TRM_LV_DWN 2
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // defined (PCBV4)
|
#endif // defined (PCBV4)
|
||||||
|
|
||||||
#define SLAVE_MODE (PING & (1<<INP_G_RF_POW))
|
#define SLAVE_MODE (PING & (1<<INP_G_RF_POW))
|
||||||
|
@ -439,7 +425,7 @@ bool keyState(EnumKeys enuk);
|
||||||
/// EVT_KEY_BREAK(key), EVT_KEY_FIRST(key), EVT_KEY_REPT(key) oder EVT_KEY_LONG(key)
|
/// EVT_KEY_BREAK(key), EVT_KEY_FIRST(key), EVT_KEY_REPT(key) oder EVT_KEY_LONG(key)
|
||||||
uint8_t getEvent();
|
uint8_t getEvent();
|
||||||
void putEvent(uint8_t evt);
|
void putEvent(uint8_t evt);
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
extern uint8_t keyDown();
|
extern uint8_t keyDown();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -529,14 +515,12 @@ void getADC_filt();
|
||||||
#define EE_GENERAL 0x01
|
#define EE_GENERAL 0x01
|
||||||
#define EE_MODEL 0x02
|
#define EE_MODEL 0x02
|
||||||
|
|
||||||
extern bool warble;
|
|
||||||
|
|
||||||
extern uint8_t s_eeDirtyMsk;
|
extern uint8_t s_eeDirtyMsk;
|
||||||
|
|
||||||
#define STORE_MODELVARS eeDirty(EE_MODEL)
|
#define STORE_MODELVARS eeDirty(EE_MODEL)
|
||||||
#define STORE_GENERALVARS eeDirty(EE_GENERAL)
|
#define STORE_GENERALVARS eeDirty(EE_GENERAL)
|
||||||
|
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
#define BACKLIGHT_ON PORTC |= (1<<OUT_C_LIGHT)
|
#define BACKLIGHT_ON PORTC |= (1<<OUT_C_LIGHT)
|
||||||
#define BACKLIGHT_OFF PORTC &= ~(1<<OUT_C_LIGHT)
|
#define BACKLIGHT_OFF PORTC &= ~(1<<OUT_C_LIGHT)
|
||||||
#else
|
#else
|
||||||
|
@ -670,14 +654,14 @@ inline void _beep(uint8_t b) {
|
||||||
}
|
}
|
||||||
|
|
||||||
extern uint8_t toneFreq;
|
extern uint8_t toneFreq;
|
||||||
#if defined (PCBV3) && defined(BEEPSPKR)
|
#if defined (PCBV4)
|
||||||
inline void _beepSpkr(uint8_t d, uint8_t f)
|
inline void _beepSpkr(uint8_t d, uint8_t f)
|
||||||
{
|
{
|
||||||
g_beepCnt=d;
|
g_beepCnt=d;
|
||||||
OCR0A = (5000 / f); // sticking with old values approx 20(abs. min) to 90, 60 being the default tone(?).
|
OCR0A = (5000 / f); // sticking with old values approx 20(abs. min) to 90, 60 being the default tone(?).
|
||||||
}
|
}
|
||||||
#elif defined (BEEPSPKR)
|
#elif defined (AUDIO)
|
||||||
inline void _beepSpkr(uint8_t d, uint8_t f)
|
inline void _beepSpkr(uint8_t d, uint8_t f) // TODO needed?
|
||||||
{
|
{
|
||||||
g_beepCnt=d;
|
g_beepCnt=d;
|
||||||
toneFreq=f;
|
toneFreq=f;
|
||||||
|
@ -685,7 +669,7 @@ inline void _beepSpkr(uint8_t d, uint8_t f)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// MM/SD card Disk IO Support
|
// MM/SD card Disk IO Support
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
#include "rtc.h"
|
#include "rtc.h"
|
||||||
extern void disk_timerproc(void);
|
extern void disk_timerproc(void);
|
||||||
extern gtime_t g_unixTime; // global unix timestamp -- hold current time in seconds since 1970-01-01 00:00:00
|
extern gtime_t g_unixTime; // global unix timestamp -- hold current time in seconds since 1970-01-01 00:00:00
|
||||||
|
@ -712,7 +696,7 @@ inline bool isFunctionActive(uint8_t func)
|
||||||
extern char userDataDisplayBuf[TELEM_SCREEN_BUFFER_SIZE]; // text buffer for frsky telem. user data experiments
|
extern char userDataDisplayBuf[TELEM_SCREEN_BUFFER_SIZE]; // text buffer for frsky telem. user data experiments
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
extern char g_logFilename[22]; // pers.cpp::resetTelemetry()
|
extern char g_logFilename[22]; // pers.cpp::resetTelemetry()
|
||||||
extern FATFS FATFS_Obj; // pers.cpp::resetTelemetry()
|
extern FATFS FATFS_Obj; // pers.cpp::resetTelemetry()
|
||||||
extern FIL g_oLogFile; // pers.cpp::resetTelemetry()
|
extern FIL g_oLogFile; // pers.cpp::resetTelemetry()
|
||||||
|
@ -723,9 +707,9 @@ extern FIL g_oLogFile; // pers.cpp::resetTelemetry()
|
||||||
extern volatile uint8_t g_rotenc[2];
|
extern volatile uint8_t g_rotenc[2];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef BEEPSPKR
|
#if defined(AUDIO)
|
||||||
//audio settungs are external to keep out clutter!
|
//audio settungs are external to keep out clutter!
|
||||||
// TODO what does mean "keep out clutter"?
|
// TODO english learning for me... what does mean "keep out clutter"?
|
||||||
#include "audio.h"
|
#include "audio.h"
|
||||||
#else
|
#else
|
||||||
#include "beeper.h"
|
#include "beeper.h"
|
||||||
|
|
|
@ -63,13 +63,10 @@ void startPulses()
|
||||||
fires for the first time and sets up the pulse period. */
|
fires for the first time and sets up the pulse period. */
|
||||||
// TCCR1A |= (1<<COM1B0); // (COM1B1=0 and COM1B0=1 in TCCR1A) toogle the state of PB6(OC1B) on each TCNT1==OCR1B
|
// TCCR1A |= (1<<COM1B0); // (COM1B1=0 and COM1B0=1 in TCCR1A) toogle the state of PB6(OC1B) on each TCNT1==OCR1B
|
||||||
TCCR1A = (3<<COM1B0); // Connect OC1B to PPM_OUT pin (SET the state of PB6(OC1B) on next TCNT1==OCR1B)
|
TCCR1A = (3<<COM1B0); // Connect OC1B to PPM_OUT pin (SET the state of PB6(OC1B) on next TCNT1==OCR1B)
|
||||||
#elif defined(DPPMPB7_HARDWARE) // addon Vinceofdrink@gmail (hardware ppm)
|
|
||||||
OCR1C = 0xffff; // See comment for PCBV4, above
|
|
||||||
TCCR1A |= (1<<COM1C0); // (COM1C1=0 and COM1C0=1 in TCCR1A) toogle the state of PB7(OC1C) on each TCNT1==OCR1C
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(PCBV3)
|
#if defined(PCBV4)
|
||||||
TIMSK1 |= (1<<OCIE1A); // Pulse generator enable immediately before mainloop
|
TIMSK1 |= (1<<OCIE1A); // Pulse generator enable immediately before mainloop
|
||||||
#else
|
#else
|
||||||
TIMSK |= (1<<OCIE1A); // Pulse generator enable immediately before mainloop
|
TIMSK |= (1<<OCIE1A); // Pulse generator enable immediately before mainloop
|
||||||
|
@ -112,9 +109,8 @@ ISR(TIMER1_COMPA_vect) //2MHz pulse generation
|
||||||
else
|
else
|
||||||
#endif
|
#endif
|
||||||
{
|
{
|
||||||
// vinceofdrink@gmail harwared ppm
|
|
||||||
// Orginal bitbang for PPM
|
// Orginal bitbang for PPM
|
||||||
#if !defined(DPPMPB7_HARDWARE) && !defined(PCBV4)
|
#if !defined(PCBV4)
|
||||||
if (pulsePol) {
|
if (pulsePol) {
|
||||||
PORTB |= (1<<OUT_B_PPM); // GCC optimisation should result in a single SBI instruction
|
PORTB |= (1<<OUT_B_PPM); // GCC optimisation should result in a single SBI instruction
|
||||||
pulsePol = 0;
|
pulsePol = 0;
|
||||||
|
@ -141,11 +137,6 @@ ISR(TIMER1_COMPA_vect) //2MHz pulse generation
|
||||||
TCCR1A = (2<<COM1B0); // CLEAR the state of PB6(OC1B) on next TCNT1==OCR1B
|
TCCR1A = (2<<COM1B0); // CLEAR the state of PB6(OC1B) on next TCNT1==OCR1B
|
||||||
pulsePol = 1;
|
pulsePol = 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
//vinceofdrink@gmail harwared ppm
|
|
||||||
#elif defined(DPPMPB7_HARDWARE)
|
|
||||||
OCR1C = *((uint16_t*)pulses2MHzRPtr); // just copy the value of the OCR1A to OCR1C to test PPM out without too
|
|
||||||
// much change in the code not optimum but will not alter ppm precision
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
pulses2MHzRPtr += sizeof(uint16_t);
|
pulses2MHzRPtr += sizeof(uint16_t);
|
||||||
|
@ -153,8 +144,7 @@ ISR(TIMER1_COMPA_vect) //2MHz pulse generation
|
||||||
|
|
||||||
pulsePol = !g_model.pulsePol;
|
pulsePol = !g_model.pulsePol;
|
||||||
|
|
||||||
// TODO does it exist PCBV3? If no, replace PCBV3 by PCBV4 everywhere
|
#if defined(PCBV4)
|
||||||
#if defined(PCBV3)
|
|
||||||
TIMSK1 &= ~(1<<OCIE1A); //stop reentrance
|
TIMSK1 &= ~(1<<OCIE1A); //stop reentrance
|
||||||
#else
|
#else
|
||||||
TIMSK &= ~(1<<OCIE1A); //stop reentrance
|
TIMSK &= ~(1<<OCIE1A); //stop reentrance
|
||||||
|
@ -164,14 +154,6 @@ ISR(TIMER1_COMPA_vect) //2MHz pulse generation
|
||||||
|
|
||||||
setupPulses();
|
setupPulses();
|
||||||
|
|
||||||
#if defined(DPPMPB7_HARDWARE)
|
|
||||||
// G: NOTE: This strategy does not work on the '2560 becasue you can't
|
|
||||||
// read the PPM out pin when connected to OC1B. Vincent says
|
|
||||||
// it works on the '64A. I haven't personally tested it.
|
|
||||||
if (PINB & (1<<OUT_B_PPM) && g_model.pulsePol)
|
|
||||||
TCCR1C=(1<<FOC1C);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// TODO test that it's optimized
|
// TODO test that it's optimized
|
||||||
if (1
|
if (1
|
||||||
#if defined(PXX)
|
#if defined(PXX)
|
||||||
|
@ -184,7 +166,7 @@ ISR(TIMER1_COMPA_vect) //2MHz pulse generation
|
||||||
|
|
||||||
// cli is not needed because for these 2 protocols interrupts are not enabled when entering here
|
// cli is not needed because for these 2 protocols interrupts are not enabled when entering here
|
||||||
|
|
||||||
#if defined(PCBV3)
|
#if defined(PCBV4)
|
||||||
TIMSK1 |= (1<<OCIE1A);
|
TIMSK1 |= (1<<OCIE1A);
|
||||||
#else
|
#else
|
||||||
TIMSK |= (1<<OCIE1A);
|
TIMSK |= (1<<OCIE1A);
|
||||||
|
@ -516,7 +498,7 @@ void setupPulsesDsm2()
|
||||||
}
|
}
|
||||||
if ((dsmDat[0] & BIND_BIT) && (!keyState(SW_Trainer))) dsmDat[0] &= ~BIND_BIT; // clear bind bit if trainer not pulled
|
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
|
// 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;
|
// else dsmDat[0] &= ~RANGECHECK_BIT;
|
||||||
dsmDat[1] = g_model.modelId; // DSM2 Header second byte for model match
|
dsmDat[1] = g_model.modelId; // DSM2 Header second byte for model match
|
||||||
for (uint8_t i=0; i<DSM2_CHANS; i++)
|
for (uint8_t i=0; i<DSM2_CHANS; i++)
|
||||||
{
|
{
|
||||||
|
@ -551,7 +533,7 @@ void setupPulses()
|
||||||
OCR1C = 200; // 100 uS
|
OCR1C = 200; // 100 uS
|
||||||
TCNT1 = 300; // Past the OCR1C value
|
TCNT1 = 300; // Past the OCR1C value
|
||||||
ICR1 = 44000; // Next frame starts in 22 mS
|
ICR1 = 44000; // Next frame starts in 22 mS
|
||||||
#if defined(PCBV3)
|
#if defined(PCBV4)
|
||||||
TIMSK1 &= ~0x3C; // All interrupts off
|
TIMSK1 &= ~0x3C; // All interrupts off
|
||||||
TIFR1 = 0x2F;
|
TIFR1 = 0x2F;
|
||||||
TIMSK1 |= 0x28; // Enable CAPT and COMPB
|
TIMSK1 |= 0x28; // Enable CAPT and COMPB
|
||||||
|
@ -608,7 +590,7 @@ void setupPulses()
|
||||||
TCCR1B = 0; // Stop counter
|
TCCR1B = 0; // Stop counter
|
||||||
OCR1A = 40000; // Next frame starts in 20 mS
|
OCR1A = 40000; // Next frame starts in 20 mS
|
||||||
TCNT1 = 0;
|
TCNT1 = 0;
|
||||||
#if defined(PCBV3)
|
#if defined(PCBV4)
|
||||||
TIMSK1 &= ~0x3C; // All interrupts off
|
TIMSK1 &= ~0x3C; // All interrupts off
|
||||||
TIFR1 = 0x2F;
|
TIFR1 = 0x2F;
|
||||||
TIMSK1 |= 0x10; // Enable COMPA
|
TIMSK1 |= 0x10; // Enable COMPA
|
||||||
|
@ -618,6 +600,8 @@ void setupPulses()
|
||||||
ETIFR = 0x3F ; // Clear all pending interrupts
|
ETIFR = 0x3F ; // Clear all pending interrupts
|
||||||
TIMSK |= 0x10; // Enable COMPA
|
TIMSK |= 0x10; // Enable COMPA
|
||||||
#endif
|
#endif
|
||||||
|
// TCNT1 2MHz counter (auto-cleared) plus Capture Compare int.
|
||||||
|
// Used for PPM pulse generator
|
||||||
TCCR1A = (0 << WGM10);
|
TCCR1A = (0 << WGM10);
|
||||||
TCCR1B = (1 << WGM12) | (2 << CS10); // CTC OCRA, 16MHz / 8
|
TCCR1B = (1 << WGM12) | (2 << CS10); // CTC OCRA, 16MHz / 8
|
||||||
break;
|
break;
|
||||||
|
@ -699,11 +683,11 @@ ISR(TIMER1_COMPC_vect) // DSM2 or PXX end of frame
|
||||||
|
|
||||||
#if defined(DSM2_PPM)
|
#if defined(DSM2_PPM)
|
||||||
ICR1 = 41536 ; // next frame starts in 22ms 41536 = 2*(22000 - 14*11*8)
|
ICR1 = 41536 ; // next frame starts in 22ms 41536 = 2*(22000 - 14*11*8)
|
||||||
if (OCR1B < 255) {
|
if (OCR1C < 255) {
|
||||||
OCR1B = 39000; // delay setup pulses by 19.5ms to reduce system latency
|
OCR1C = 39000; // delay setup pulses by 19.5ms to reduce system latency
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
OCR1B = 200;
|
OCR1C = 200;
|
||||||
// sei will be called inside setupPulses()
|
// sei will be called inside setupPulses()
|
||||||
setupPulses();
|
setupPulses();
|
||||||
}
|
}
|
||||||
|
@ -727,10 +711,11 @@ ISR(TIMER1_COMPC_vect) // DSM2 or PXX end of frame
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
void set_timer3_capture()
|
void set_timer3_capture()
|
||||||
{
|
{
|
||||||
#ifndef SIMU
|
#ifndef SIMU
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
TIMSK3 &= ~( (1<<OCIE3A) | (1<<OCIE3B) | (1<<OCIE3C) ) ; // Stop compare interrupts // TODO Cam please could you check this line please? Thanks a lot!
|
TIMSK3 &= ~( (1<<OCIE3A) | (1<<OCIE3B) | (1<<OCIE3C) ) ; // Stop compare interrupts // TODO Cam please could you check this line please? Thanks a lot!
|
||||||
#else
|
#else
|
||||||
ETIMSK &= ~( (1<<OCIE3A) | (1<<OCIE3B) | (1<<OCIE3C) ) ; // Stop compare interrupts
|
ETIMSK &= ~( (1<<OCIE3A) | (1<<OCIE3B) | (1<<OCIE3C) ) ; // Stop compare interrupts
|
||||||
|
@ -739,8 +724,9 @@ void set_timer3_capture()
|
||||||
|
|
||||||
TCCR3B = 0 ; // Stop counter
|
TCCR3B = 0 ; // Stop counter
|
||||||
TCCR3A = 0;
|
TCCR3A = 0;
|
||||||
TCCR3B = (1<<ICNC3) | (2<<CS30); //ICNC3 16MHz / 8
|
// Noise Canceller enabled, neg. edge, clock at 16MHz / 8 (2MHz) (Correct for PCB V4.x+ also)
|
||||||
#if defined (PCBV3)
|
TCCR3B = (1<<ICNC3) | (0b010 << CS30);
|
||||||
|
#if defined (PCBV4)
|
||||||
TIMSK3 |= (1<<ICIE3);
|
TIMSK3 |= (1<<ICIE3);
|
||||||
#else
|
#else
|
||||||
ETIMSK |= (1<<TICIE3);
|
ETIMSK |= (1<<TICIE3);
|
||||||
|
@ -752,7 +738,7 @@ void set_timer3_capture()
|
||||||
void set_timer3_ppm()
|
void set_timer3_ppm()
|
||||||
{
|
{
|
||||||
#ifndef SIMU
|
#ifndef SIMU
|
||||||
#if defined (PCBV3)
|
#if defined (PCBV4)
|
||||||
TIMSK3 &= ~(1<<ICIE3);
|
TIMSK3 &= ~(1<<ICIE3);
|
||||||
#else
|
#else
|
||||||
ETIMSK &= ~(1<<TICIE3) ; // Stop capture interrupt
|
ETIMSK &= ~(1<<TICIE3) ; // Stop capture interrupt
|
||||||
|
|
11
src/rtc.cpp
11
src/rtc.cpp
|
@ -24,27 +24,16 @@
|
||||||
|
|
||||||
#include "open9x.h"
|
#include "open9x.h"
|
||||||
|
|
||||||
#if defined (PCBV4)
|
|
||||||
#define SCL_LOW() DDRD |= 0x01 /* SCL = LOW */
|
#define SCL_LOW() DDRD |= 0x01 /* SCL = LOW */
|
||||||
#define SCL_HIGH() DDRD &= ~0x01 /* SCL = High-Z */
|
#define SCL_HIGH() DDRD &= ~0x01 /* SCL = High-Z */
|
||||||
#define SCL_VAL ((PIND & 0x01) ? 1 : 0) /* SCL input level */
|
#define SCL_VAL ((PIND & 0x01) ? 1 : 0) /* SCL input level */
|
||||||
#define SDA_LOW() DDRD |= 0x02 /* SDA = LOW */
|
#define SDA_LOW() DDRD |= 0x02 /* SDA = LOW */
|
||||||
#define SDA_HIGH() DDRD &= ~0x02 /* SDA = High-Z */
|
#define SDA_HIGH() DDRD &= ~0x02 /* SDA = High-Z */
|
||||||
#define SDA_VAL ((PIND & 0x02) ? 1 : 0) /* SDA input level */
|
#define SDA_VAL ((PIND & 0x02) ? 1 : 0) /* SDA input level */
|
||||||
#else // PCBV3
|
|
||||||
#define SCL_LOW() DDRB |= 0x20 /* SCL = LOW */
|
|
||||||
#define SCL_HIGH() DDRB &= ~0x20 /* SCL = High-Z */
|
|
||||||
#define SCL_VAL ((PINB & 0x20) ? 1 : 0) /* SCL input level */
|
|
||||||
#define SDA_LOW() DDRB |= 0x40 /* SDA = LOW */
|
|
||||||
#define SDA_HIGH() DDRB &= ~0x40 /* SDA = High-Z */
|
|
||||||
#define SDA_VAL ((PINB & 0x40) ? 1 : 0) /* SDA input level */
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
/*-------------------------------------------------*/
|
/*-------------------------------------------------*/
|
||||||
/* I2C bus protocol */
|
/* I2C bus protocol */
|
||||||
|
|
||||||
|
|
||||||
static
|
static
|
||||||
void iic_delay (void)
|
void iic_delay (void)
|
||||||
{
|
{
|
||||||
|
|
|
@ -319,7 +319,7 @@ void Gruvin9xSim::refreshDiplay()
|
||||||
};
|
};
|
||||||
|
|
||||||
static SwitchKey keys3[] = {
|
static SwitchKey keys3[] = {
|
||||||
#if defined(JETI) || defined(FRSKY)
|
#if defined(JETI) || defined(FRSKY) || defined(NMEA) || defined(ARDUPILOT)
|
||||||
{ KEY_1, pinc, INP_C_ThrCt, 0 },
|
{ KEY_1, pinc, INP_C_ThrCt, 0 },
|
||||||
{ KEY_6, pinc, INP_C_AileDR, 0 },
|
{ KEY_6, pinc, INP_C_AileDR, 0 },
|
||||||
#else
|
#else
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue