Subversion Repositories FlightCtrl

Compare Revisions

Ignore whitespace Rev 2002 → Rev 2003

/branches/V0.86d_MartinW_Jeti+V0.20/FlightCtrl.aps
0,0 → 1,0
<AVRStudio><MANAGEMENT><ProjectName>FlightCtrl</ProjectName><Created>15-May-2007 11:20:41</Created><LastEdit>11-Oct-2007 22:58:54</LastEdit><ICON>241</ICON><ProjectType>0</ProjectType><Created>15-May-2007 11:20:41</Created><Version>4</Version><Build>4, 13, 0, 528</Build><ProjectTypeName>AVR GCC</ProjectTypeName></MANAGEMENT><CODE_CREATION><ObjectFile>default\Flight-Ctrl.elf</ObjectFile><EntryFile></EntryFile><SaveFolder>F:\SVN\MikroKopter\FlightCtrl\branches\V0.64_ZeroWarnings\</SaveFolder></CODE_CREATION><DEBUG_TARGET><CURRENT_TARGET>AVR Simulator</CURRENT_TARGET><CURRENT_PART>ATmega644.xml</CURRENT_PART><BREAKPOINTS></BREAKPOINTS><IO_EXPAND><HIDE>false</HIDE></IO_EXPAND><REGISTERNAMES><Register>R00</Register><Register>R01</Register><Register>R02</Register><Register>R03</Register><Register>R04</Register><Register>R05</Register><Register>R06</Register><Register>R07</Register><Register>R08</Register><Register>R09</Register><Register>R10</Register><Register>R11</Register><Register>R12</Register><Register>R13</Register><Register>R14</Register><Register>R15</Register><Register>R16</Register><Register>R17</Register><Register>R18</Register><Register>R19</Register><Register>R20</Register><Register>R21</Register><Register>R22</Register><Register>R23</Register><Register>R24</Register><Register>R25</Register><Register>R26</Register><Register>R27</Register><Register>R28</Register><Register>R29</Register><Register>R30</Register><Register>R31</Register></REGISTERNAMES><COM>Auto</COM><COMType>0</COMType><WATCHNUM>0</WATCHNUM><WATCHNAMES><Pane0></Pane0><Pane1></Pane1><Pane2></Pane2><Pane3></Pane3></WATCHNAMES><BreakOnTrcaeFull>0</BreakOnTrcaeFull></DEBUG_TARGET><Debugger><Triggers></Triggers></Debugger><AVRGCCPLUGIN><FILES><SOURCEFILE>uart.c</SOURCEFILE><SOURCEFILE>analog.c</SOURCEFILE><SOURCEFILE>eeprom.c</SOURCEFILE><SOURCEFILE>fc.c</SOURCEFILE><SOURCEFILE>GPS.c</SOURCEFILE><SOURCEFILE>main.c</SOURCEFILE><SOURCEFILE>menu.c</SOURCEFILE><SOURCEFILE>printf_P.c</SOURCEFILE><SOURCEFILE>rc.c</SOURCEFILE><SOURCEFILE>timer0.c</SOURCEFILE><SOURCEFILE>twimaster.c</SOURCEFILE><HEADERFILE>uart.h</HEADERFILE><HEADERFILE>_Settings.h</HEADERFILE><HEADERFILE>analog.h</HEADERFILE><HEADERFILE>fc.h</HEADERFILE><HEADERFILE>gps.h</HEADERFILE><HEADERFILE>main.h</HEADERFILE><HEADERFILE>menu.h</HEADERFILE><HEADERFILE>old_macros.h</HEADERFILE><HEADERFILE>printf_P.h</HEADERFILE><HEADERFILE>rc.h</HEADERFILE><HEADERFILE>Settings.h</HEADERFILE><HEADERFILE>timer0.h</HEADERFILE><HEADERFILE>twimaster.h</HEADERFILE></FILES><CONFIGS><CONFIG><NAME>default</NAME><USESEXTERNALMAKEFILE>NO</USESEXTERNALMAKEFILE><EXTERNALMAKEFILE></EXTERNALMAKEFILE><PART>atmega644</PART><HEX>1</HEX><LIST>1</LIST><MAP>1</MAP><OUTPUTFILENAME>Flight-Ctrl.elf</OUTPUTFILENAME><OUTPUTDIR>default\</OUTPUTDIR><ISDIRTY>1</ISDIRTY><OPTIONS><OPTION><FILE>GPS.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>analog.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>eeprom.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>fc.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>main.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>menu.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>printf_P.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>rc.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>timer0.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>twimaster.c</FILE><OPTIONLIST></OPTIONLIST></OPTION><OPTION><FILE>uart.c</FILE><OPTIONLIST></OPTIONLIST></OPTION></OPTIONS><INCDIRS/><LIBDIRS/><LIBS><LIB>libc.a</LIB><LIB>libm.a</LIB></LIBS><LINKOBJECTS/><OPTIONSFORALL>-Wall -gdwarf-2 -Wstrict-prototypes -std=gnu99 -Os -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums -DVERSION_HAUPTVERSION=0 -DVERSION_NEBENVERSION=64 -DVERSION_KOMPATIBEL=5</OPTIONSFORALL><LINKEROPTIONS></LINKEROPTIONS><SEGMENTS/></CONFIG></CONFIGS><LASTCONFIG>default</LASTCONFIG><USES_WINAVR>1</USES_WINAVR><GCC_LOC>C:\Program Files\WinAVR\bin\avr-gcc.exe</GCC_LOC><MAKE_LOC>C:\Program Files\WinAVR\utils\bin\make.exe</MAKE_LOC></AVRGCCPLUGIN><IOView><usergroups/></IOView><Files><File00000><FileId>00000</FileId><FileName>main.c</FileName><Status>1</Status></File00000><File00001><FileId>00001</FileId><FileName>uart.c</FileName><Status>1</Status></File00001><File00002><FileId>00002</FileId><FileName>menu.c</FileName><Status>1</Status></File00002><File00003><FileId>00003</FileId><FileName>timer0.c</FileName><Status>1</Status></File00003><File00004><FileId>00004</FileId><FileName>fc.c</FileName><Status>1</Status></File00004><File00005><FileId>00005</FileId><FileName>fc.h</FileName><Status>1</Status></File00005><File00006><FileId>00006</FileId><FileName>menu.h</FileName><Status>1</Status></File00006><File00007><FileId>00007</FileId><FileName>TWIMASTER.C</FileName><Status>1</Status></File00007><File00008><FileId>00008</FileId><FileName>twimaster.h</FileName><Status>1</Status></File00008><File00009><FileId>00009</FileId><FileName>uart.h</FileName><Status>1</Status></File00009><File00010><FileId>00010</FileId><FileName>_Settings.h</FileName><Status>1</Status></File00010><File00011><FileId>00011</FileId><FileName>analog.h</FileName><Status>1</Status></File00011><File00012><FileId>00012</FileId><FileName>gps.h</FileName><Status>1</Status></File00012><File00013><FileId>00013</FileId><FileName>main.h</FileName><Status>1</Status></File00013><File00014><FileId>00014</FileId><FileName>old_macros.h</FileName><Status>1</Status></File00014><File00015><FileId>00015</FileId><FileName>printf_P.h</FileName><Status>1</Status></File00015><File00016><FileId>00016</FileId><FileName>rc.h</FileName><Status>1</Status></File00016><File00017><FileId>00017</FileId><FileName>Settings.h</FileName><Status>1</Status></File00017><File00018><FileId>00018</FileId><FileName>timer0.h</FileName><Status>1</Status></File00018></Files><Events><Bookmarks></Bookmarks></Events><Trace><Filters></Filters></Trace></AVRStudio>
/branches/V0.86d_MartinW_Jeti+V0.20/GPS.c
0,0 → 1,16
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) Holger Buss, Ingo Busker
// + only for non-profit use
// + www.MikroKopter.com
// + see the File "License.txt" for further Informations
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
#include "main.h"
 
signed int GPS_Nick = 0;
signed int GPS_Roll = 0;
unsigned char GPS_Aid_StickMultiplikator = 0; // 64 = 100%
 
 
 
 
/branches/V0.86d_MartinW_Jeti+V0.20/Spektrum.c
0,0 → 1,463
/*#######################################################################################
Decodieren eines RC Summen Signals oder Spektrum Empfänger-Satellit
#######################################################################################*/
 
#include "Spektrum.h"
#include "main.h"
// Achtung: RECEIVER_SPEKTRUM_DX7EXP oder RECEIVER_SPEKTRUM_DX8EXP wird in der Main.h gesetzt
 
#ifndef WITHSPECTRUM /// MartinW
#warning : "### without SPECTRUM Code ###"
#endif
 
unsigned char SpektrumTimer = 0;
 
#if defined (RECEIVER_SPEKTRUM_DX7EXP) || defined (RECEIVER_SPEKTRUM_DX8EXP)
unsigned char s_excnt = 0; // Counter for Spektrum-Expander
unsigned char s_exparity = 0; // Parity Bit for Spektrum-Expander
signed char s_exdata[11]; // Data for Spektrum-Expander
#endif
//--------------------------------------------------------------//
//--------------------------------------------------------------//
/*
void SpektrumBinding(void)
{
unsigned int timerTimeout = SetDelay(10000); // Timeout 10 sec.
unsigned char connected = 0;
unsigned int delaycounter;
 
UCSR1B &= ~(1 << RXCIE1); // disable rx-interrupt
UCSR1B &= ~(1<<RXEN1); // disable Uart-Rx
PORTD &= ~(1 << PORTD2); // disable pull-up
 
printf("\n\rPlease connect Spektrum receiver for binding NOW...");
 
while(!CheckDelay(timerTimeout))
{
if (PIND & (1 << PORTD2)) { timerTimeout = SetDelay(90); connected = 1; break; }
}
 
if (connected)
{
 
printf("ok.\n\r");
DDRD |= (1 << DDD2); // Rx as output
 
while(!CheckDelay(timerTimeout)); // delay after startup of RX
for (delaycounter = 0; delaycounter < 100; delaycounter++) PORTD |= (1 << PORTD2);
for (delaycounter = 0; delaycounter < 400; delaycounter++) PORTD &= ~(1 << PORTD2);
 
for (delaycounter = 0; delaycounter < 10; delaycounter++) PORTD |= (1 << PORTD2);
for (delaycounter = 0; delaycounter < 10; delaycounter++) PORTD &= ~(1 << PORTD2);
for (delaycounter = 0; delaycounter < 400; delaycounter++) PORTD |= (1 << PORTD2);
for (delaycounter = 0; delaycounter < 400; delaycounter++) PORTD &= ~(1 << PORTD2);
 
for (delaycounter = 0; delaycounter < 10; delaycounter++) PORTD |= (1 << PORTD2);
for (delaycounter = 0; delaycounter < 10; delaycounter++) PORTD &= ~(1 << PORTD2);
for (delaycounter = 0; delaycounter < 400; delaycounter++) PORTD |= (1 << PORTD2);
for (delaycounter = 0; delaycounter < 400; delaycounter++) PORTD &= ~(1 << PORTD2);
 
for (delaycounter = 0; delaycounter < 10; delaycounter++) PORTD |= (1 << PORTD2);
for (delaycounter = 0; delaycounter < 10; delaycounter++) PORTD &= ~(1 << PORTD2);
for (delaycounter = 0; delaycounter < 400; delaycounter++) PORTD |= (1 << PORTD2);
 
}
else
{ printf("Timeout.\n\r");
 
 
}
 
DDRD &= ~(1 << DDD2); // RX as input
PORTD &= ~(1 << PORTD2);
 
SpektrumUartInit(); // init Uart again
}
*/
//############################################################################
// USART1 initialisation from killagreg
void SpektrumUartInit(void)
//############################################################################
{
#ifdef WITHSPECTRUM /// MartinW main.h means no memsave
#warning : "### with left over Spectrum code ###"
// -- Start of USART1 initialisation for Spekturm seriell-mode
// USART1 Control and Status Register A, B, C and baud rate register
uint8_t sreg = SREG;
uint16_t ubrr = (uint16_t) ((uint32_t) SYSCLK/(8 * 115200) - 1);
// disable all interrupts before reconfiguration
cli();
// disable RX-Interrupt
UCSR1B &= ~(1 << RXCIE1);
// disable TX-Interrupt
UCSR1B &= ~(1 << TXCIE1);
// disable DRE-Interrupt
UCSR1B &= ~(1 << UDRIE1);
// set direction of RXD1 and TXD1 pins
// set RXD1 (PD2) as an input pin
PORTD |= (1 << PORTD2);
DDRD &= ~(1 << DDD2);
 
// set TXD1 (PD3) as an output pin
PORTD |= (1 << PORTD3);
DDRD |= (1 << DDD3);
// USART0 Baud Rate Register
// set clock divider
UBRR1H = (uint8_t)(ubrr>>8);
UBRR1L = (uint8_t)ubrr;
// enable double speed operation
UCSR1A |= (1 << U2X1);
// enable receiver and transmitter
//UCSR1B = (1<<RXEN1)|(1<<TXEN1);
 
UCSR1B = (1<<RXEN1);
// set asynchronous mode
UCSR1C &= ~(1 << UMSEL11);
UCSR1C &= ~(1 << UMSEL10);
// no parity
UCSR1C &= ~(1 << UPM11);
UCSR1C &= ~(1 << UPM10);
// 1 stop bit
UCSR1C &= ~(1 << USBS1);
// 8-bit
UCSR1B &= ~(1 << UCSZ12);
UCSR1C |= (1 << UCSZ11);
UCSR1C |= (1 << UCSZ10);
// flush receive buffer explicit
while(UCSR1A & (1<<RXC1)) UDR1;
// enable RX-interrupts at the end
UCSR1B |= (1 << RXCIE1);
// -- End of USART1 initialisation
// restore global interrupt flags
SREG = sreg;
#endif
return;
}
 
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) Rainer Walther
// + RC-routines from original MK rc.c (c) H&I
// + Useful infos from Walter: http://www.rcgroups.com/forums/showthread.php?t=714299&page=2
// + only for non-profit use
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//
// 20080808 rw Modified for Spektrum AR6100 (PPM)
// 20080823 rw Add Spektrum satellite receiver on USART1 (644P only)
// 20081213 rw Add support for Spektrum DS9 Air-Tx-Module (9 channels)
// Replace AR6100-coding with original composit-signal routines
//
// ---
// Entweder Summensignal ODER Spektrum-Receiver anschließen. Nicht beides gleichzeitig betreiben!
// Binding is not implemented. Bind with external Receiver.
// Servo output J3, J4, J5 not serviced
//
// Anschuß Spektrum Receiver
// Orange: 3V von der FC (keinesfalls an 5V anschließen!)
// Schwarz: GND
// Grau: RXD1 (Pin 3) auf 10-Pol FC-Stecker
//
// ---
// Satellite-Reciever connected on USART1:
//
// DX7/DX6i: One data-frame at 115200 baud every 22ms.
// DX7se: One data-frame at 115200 baud every 11ms.
// byte1: unknown
// byte2: unknown
// byte3: and byte4: channel data (FLT-Mode)
// byte5: and byte6: channel data (Roll)
// byte7: and byte8: channel data (Nick)
// byte9: and byte10: channel data (Gier)
// byte11: and byte12: channel data (Gear Switch)
// byte13: and byte14: channel data (Gas)
// byte15: and byte16: channel data (AUX2)
//
// DS9 (9 Channel): One data-frame at 115200 baud every 11ms, alternating frame 1/2 for CH1-7 / CH8-9
// 1st Frame:
// byte1: unknown
// byte2: unknown
// byte3: and byte4: channel data
// byte5: and byte6: channel data
// byte7: and byte8: channel data
// byte9: and byte10: channel data
// byte11: and byte12: channel data
// byte13: and byte14: channel data
// byte15: and byte16: channel data
// 2nd Frame:
// byte1: unknown
// byte2: unknown
// byte3: and byte4: channel data
// byte5: and byte6: channel data
// byte7: and byte8: 0xffff
// byte9: and byte10: 0xffff
// byte11: and byte12: 0xffff
// byte13: and byte14: 0xffff
// byte15: and byte16: 0xffff
//
// Each channel data (16 bit= 2byte, first msb, second lsb) is arranged as:
//
// Bits: F 0 C3 C2 C1 C0 D9 D8 D7 D6 D5 D4 D3 D2 D1 D0
//
// 0 means a '0' bit
// F: 1 = indicates beginning of 2nd frame for CH8-9 (DS9 only)
// C3 to C0 is the channel number. 0 to 9 (4 bit, as assigned in the transmitter)
// D9 to D0 is the channel data (10 bit) 0xaa..0x200..0x356 for 100% transmitter-travel
//
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
#define MIN_FRAMEGAP 68 // 7ms
#define MAX_BYTEGAP 3 // 310us
 
 
//############################################################################
// Wird im UART-Interrupt aufgerufen
//############################################################################
void SpektrumParser(unsigned char c)
{
#ifdef WITHSPECTRUM /// MartinW main.h means no memsave
#warning : "### with left over Spectrum code ###"
static unsigned char Sync=0, FrameCnt=0, ByteHigh=0, ReSync=1, Frame2=0;
unsigned int Channel, index = 0;
signed int signal = 0, tmp;
int bCheckDelay;
// c = UDR1; // get data byte
if(ReSync == 1)
{
// wait for beginning of new frame
ReSync = 0;
SpektrumTimer = MIN_FRAMEGAP;
FrameCnt = 0;
Sync = 0;
ByteHigh = 0;
}
else
{
if(!SpektrumTimer) bCheckDelay = 1; else bCheckDelay = 0;//CheckDelay(FrameTimer);
if ( Sync == 0 )
{
if(bCheckDelay)
{
// nach einer Pause von mind. 7ms erstes Sync-Character gefunden
// Zeichen ignorieren, da Bedeutung unbekannt
Sync = 1;
FrameCnt ++;
SpektrumTimer = MAX_BYTEGAP;
}
else
{
// Zeichen kam vor Ablauf der 7ms Sync-Pause
// warten auf erstes Sync-Zeichen
SpektrumTimer = MIN_FRAMEGAP;
FrameCnt = 0;
Sync = 0;
ByteHigh = 0;
}
}
else if((Sync == 1) && !bCheckDelay)
{
// zweites Sync-Character ignorieren, Bedeutung unbekannt
Sync = 2;
FrameCnt ++;
SpektrumTimer = MAX_BYTEGAP;
}
else if((Sync == 2) && !bCheckDelay)
{
SpektrumTimer = MAX_BYTEGAP;
// Datenbyte high
ByteHigh = c;
if (FrameCnt == 2)
{
// is 1st Byte of Channel-data
// Frame 1 with Channel 1-7 comming next
Frame2 = 0;
if(ByteHigh & 0x80)
{
// DS9: Frame 2 with Channel 8-9 comming next
Frame2 = 1;
}
}
Sync = 3;
FrameCnt ++;
}
else if((Sync == 3) && !bCheckDelay)
{
// Datenbyte low
// High-Byte for next channel comes next
SpektrumTimer = MAX_BYTEGAP;
Sync = 2;
FrameCnt ++;
Channel = ((unsigned int)ByteHigh << 8) | c;
if(EE_Parameter.Receiver == RECEIVER_SPEKTRUM)
{
signal = Channel & 0x3ff;
signal -= 0x200; // Offset, range 0x000..0x3ff?
signal = signal/3; // scaling to fit PPM resolution
index = (ByteHigh >> 2) & 0x0f;
}
else
if(EE_Parameter.Receiver == RECEIVER_SPEKTRUM_HI_RES)
{
signal = Channel & 0x7ff;
signal -= 0x400; // Offset, range 0x000..0x7ff?
signal = signal/6; // scaling to fit PPM resolution
index = (ByteHigh >> 3) & 0x0f;
}
else
//if(EE_Parameter.Receiver == RECEIVER_SPEKTRUM_LOW_RES)
{
signal = Channel & 0x3ff;
signal -= 360; // Offset, range 0x000..0x3ff?
signal = signal/2; // scaling to fit PPM resolution
index = (ByteHigh >> 2) & 0x0f;
}
 
index++;
if(index < 13)
{
// Stabiles Signal
#if defined (RECEIVER_SPEKTRUM_DX7EXP) || defined (RECEIVER_SPEKTRUM_DX8EXP)
if (index == 2) index = 4; // Analog channel reassigment (2 <-> 4) for logical numbering (1,2,3,4)
else if (index == 4) index = 2;
#endif
if(abs(signal - PPM_in[index]) < 6)
{
if(SenderOkay < 200) SenderOkay += 10;
else
{
SenderOkay = 200;
TIMSK1 &= ~_BV(ICIE1); // disable PPM-Input
}
}
tmp = (3 * (PPM_in[index]) + signal) / 4;
if(tmp > signal+1) tmp--; else
if(tmp < signal-1) tmp++;
#ifdef RECEIVER_SPEKTRUM_DX7EXP
if(index == 6) // FLIGHT-MODE - The channel used for our data uplink
{
if (signal > 100) // SYNC received
{
if (s_exdata[s_excnt] == 125) s_exparity = ~s_exparity; // Bit = 1 -> Re-Invert parity bit
if ((s_excnt == 6 && ((s_exparity != 0 && s_exdata[s_excnt] == -125) || (s_exparity == 0 && s_exdata[s_excnt] == 125))) || (s_excnt == 9 && ((s_exparity == 0 && s_exdata[s_excnt] == -125) || (s_exparity != 0 && s_exdata[s_excnt] == 125)))) // Parity check
{
if (s_exdata[1] == 125 && s_exdata[2] == -125) PPM_in[5] = -125; // Reconstruct tripole Flight-Mode value (CH5)
else if (s_exdata[1] == -125 && s_exdata[2] == -125) PPM_in[5] = 0; // Reconstruct tripole Flight-Mode value (CH5)
else if (s_exdata[1] == -125 && s_exdata[2] == 125) PPM_in[5] = 125; // Reconstruct tripole Flight-Mode value (CH5)
PPM_in[6] = s_exdata[3]; // Elevator (CH6)
PPM_in[11] = s_exdata[4]; // Aileron (CH11)
PPM_in[12] = s_exdata[5]; // Rudder (CH12)
 
if (s_excnt == 9) // New Mode (12 Channels)
{
if (s_exdata[7] == 125) PPM_in[8] += 5; // Hover Pitch UP (CH8)
if (s_exdata[8] == 125) PPM_in[8] -= 5; // Hover Pitch DN (CH8)
if (PPM_in[8] < -125) PPM_in[8] = -125; // Range-Limit
else if (PPM_in[8] > 125) PPM_in[8] = 125; // Range-Limit
PPM_in[10] = s_exdata[6]; // AUX2 (CH10)
}
}
 
s_excnt = 0; // Reset bitcounter
s_exparity = 0; // Reset parity bit
}
 
if (signal < 10) s_exdata[++s_excnt] = -125; // Bit = 0 -> value = -125 (min)
if (s_excnt == 10) s_excnt = 0; // Overflow protection
if (signal < -100)
{
s_exdata[s_excnt] = 125; // Bit = 1 -> value = 125 (max)
s_exparity = ~s_exparity; // Bit = 1 -> Invert parity bit
}
 
}
 
#elif defined RECEIVER_SPEKTRUM_DX8EXP
if(index == 6) // FLIGHT-MODE - The channel used for our data uplink
{
if (signal > 100) // SYNC received
{
if (s_exdata[s_excnt] == 125) s_exparity = ~s_exparity; // Bit = 1 -> Re-Invert parity bit
if (s_excnt == 9 && ((s_exparity == 0 && s_exdata[s_excnt] == -125) || (s_exparity != 0 && s_exdata[s_excnt] == 125))) // Parity check
{
if (s_exdata[1] == 125 && s_exdata[2] == -125) PPM_in[5] = -125; // Reconstruct tripole Flight-Mode value (CH5)
else if (s_exdata[1] == -125 && s_exdata[2] == -125) PPM_in[5] = 0; // Reconstruct tripole Flight-Mode value (CH5)
else if (s_exdata[1] == -125 && s_exdata[2] == 125) PPM_in[5] = 125; // Reconstruct tripole Flight-Mode value (CH5)
 
if (s_exdata[3] == 125 && s_exdata[6] == -125) PPM_in[6] = 125; // Reconstruct tripole Elev D/R value (CH6)
else if (s_exdata[3] == -125 && s_exdata[6] == -125) PPM_in[6] = 0; // Reconstruct tripole Elev D/R value (CH6)
else if (s_exdata[3] == -125 && s_exdata[6] == 125) PPM_in[6] = -125; // Reconstruct tripole Elev D/R value (CH6)
 
 
if (s_exdata[7] == 125 && s_exdata[8] == -125) PPM_in[9] = -125; // Reconstruct tripole AIL D/R value (CH9)
else if (s_exdata[7] == -125 && s_exdata[8] == -125) PPM_in[9] = 0; // Reconstruct tripole AIL D/R value (CH9)
else if (s_exdata[7] == -125 && s_exdata[8] == 125) PPM_in[9] = 125; // Reconstruct tripole AIL D/R value (CH9)
 
PPM_in[10] = s_exdata[5]; // Gear (CH10)
PPM_in[12] = s_exdata[4]; // Mix (CH12)
}
 
s_excnt = 0; // Reset bitcounter
s_exparity = 0; // Reset parity bit
}
 
if (signal < 10) s_exdata[++s_excnt] = -125; // Bit = 0 -> value = -125 (min)
if (s_excnt == 10) s_excnt = 0; // Overflow protection
if (signal < -100)
{
s_exdata[s_excnt] = 125; // Bit = 1 -> value = 125 (max)
s_exparity = ~s_exparity; // Bit = 1 -> Invert parity bit
}
 
}
#endif
if(SenderOkay >= 180) PPM_diff[index] = ((tmp - PPM_in[index]) / 3) * 3;
else PPM_diff[index] = 0;
 
#ifdef RECEIVER_SPEKTRUM_DX7EXP
if (index < 5 ) PPM_in[index] = tmp; // Update normal potis (CH1-4)
else if (index == 5) PPM_in[7] = signal; // Gear (CH7)
else if (index == 7) PPM_in[9] = signal; // Hover Throttle (CH9)
#elif defined RECEIVER_SPEKTRUM_DX8EXP
if (index < 5 ) PPM_in[index] = tmp; // Update normal potis (CH1-4)
else if (index == 7) PPM_in[7] = signal; // R Trim (CH7)
else if (index == 5) PPM_in[8] = signal; // AUX2 (CH8)
else if (index == 8) PPM_in[11] = signal; // AUX3 (CH11)
#else
PPM_in[index] = tmp;
#endif
}
else if(index > 17) ReSync = 1; // hier stimmt was nicht: neu synchronisieren
}
else
{
// hier stimmt was nicht: neu synchronisieren
ReSync = 1;
FrameCnt = 0;
Frame2 = 0;
// new frame next, nach fruehestens 7ms erwartet
SpektrumTimer = MIN_FRAMEGAP;
}
 
// 16 Bytes eingetroffen -> Komplett
if(FrameCnt >= 16)
{
// Frame complete
if(Frame2 == 0)
{
// Null bedeutet: Neue Daten
// nur beim ersten Frame (CH 0-7) setzen
if(!ReSync) NewPpmData = 0;
}
FrameCnt = 0;
Frame2 = 0;
Sync = 0;
SpektrumTimer = MIN_FRAMEGAP;
}
}
#endif
}
/branches/V0.86d_MartinW_Jeti+V0.20/analog.c
0,0 → 1,291
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) Holger Buss, Ingo Busker
// + only for non-profit use
// + www.MikroKopter.com
// + porting the sources to other systems or using the software on other systems (except hardware from www.mikrokopter.de) is not allowed
// + see the File "License.txt" for further Informations
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
#include "main.h"
#include "eeprom.h"
volatile int Aktuell_Nick,Aktuell_Roll,Aktuell_Gier,Aktuell_ax, Aktuell_ay,Aktuell_az, UBat = 100;
volatile int AdWertNickFilter = 0, AdWertRollFilter = 0, AdWertGierFilter = 0;
volatile int HiResNick = 2500, HiResRoll = 2500;
volatile int AdWertNick = 0, AdWertRoll = 0, AdWertGier = 0;
volatile int AdWertAccRoll = 0,AdWertAccNick = 0,AdWertAccHoch = 0;
volatile char messanzahl_AccHoch = 0;
volatile long Luftdruck = 32000;
volatile long SummenHoehe = 0;
volatile int StartLuftdruck;
volatile unsigned int MessLuftdruck = 1023;
unsigned char DruckOffsetSetting;
signed char ExpandBaro = 0;
volatile int VarioMeter = 0;
volatile unsigned int ZaehlMessungen = 0;
unsigned char AnalogOffsetNick = 115,AnalogOffsetRoll = 115,AnalogOffsetGier = 115;
volatile unsigned char AdReady = 1;
float NeutralAccZ_float;
//#######################################################################################
//
void ADC_Init(void)
//#######################################################################################
{
ADMUX = 0;//Referenz ist extern
ANALOG_ON;
}
 
#define DESIRED_H_ADC 800
 
void SucheLuftruckOffset(void)
{
unsigned int off;
ExpandBaro = 0;
 
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
{
unsigned char off2;
OCR0A = 150;
off2 = GetParamByte(PID_PRESSURE_OFFSET);
if(off2 < 230) off2 += 10;
OCR0B = off2;
Delay_ms_Mess(100);
if(MessLuftdruck > DESIRED_H_ADC) off2 = 240;
for(; off2 >= 5; off2 -= 5)
{
OCR0B = off2;
Delay_ms_Mess(50);
printf("*");
if(MessLuftdruck > DESIRED_H_ADC) break;
}
SetParamByte(PID_PRESSURE_OFFSET, off2);
if(off2 >= 15) off = 140; else off = 0;
for(; off < 250;off++)
{
OCR0A = off;
Delay_ms_Mess(50);
printf(".");
if(MessLuftdruck < DESIRED_H_ADC) break;
}
DruckOffsetSetting = off;
}
#else
off = GetParamByte(PID_PRESSURE_OFFSET);
if(off > 20) off -= 10;
OCR0A = off;
Delay_ms_Mess(100);
if(MessLuftdruck < DESIRED_H_ADC) off = 0;
for(; off < 250;off++)
{
OCR0A = off;
Delay_ms_Mess(50);
printf(".");
if(MessLuftdruck < DESIRED_H_ADC) break;
}
DruckOffsetSetting = off;
SetParamByte(PID_PRESSURE_OFFSET, off);
#endif
if((EE_Parameter.GlobalConfig & CFG_HOEHENREGELUNG) && (DruckOffsetSetting < 10 || DruckOffsetSetting >= 245)) VersionInfo.HardwareError[0] |= FC_ERROR0_PRESSURE;
OCR0A = off;
Delay_ms_Mess(300);
}
 
 
void SucheGyroOffset(void)
{
unsigned char i, ready = 0;
int timeout;
timeout = SetDelay(2000);
for(i=140; i != 0; i--)
{
if(ready == 3 && i > 10) i = 9;
ready = 0;
if(AdWertNick < 1020) AnalogOffsetNick--; else if(AdWertNick > 1030) AnalogOffsetNick++; else ready++;
if(AdWertRoll < 1020) AnalogOffsetRoll--; else if(AdWertRoll > 1030) AnalogOffsetRoll++; else ready++;
if(AdWertGier < 1020) AnalogOffsetGier--; else if(AdWertGier > 1030) AnalogOffsetGier++; else ready++;
I2C_Start(TWI_STATE_GYRO_OFFSET_TX);
if(AnalogOffsetNick < 10) { VersionInfo.HardwareError[0] |= FC_ERROR0_GYRO_NICK; AnalogOffsetNick = 10;}; if(AnalogOffsetNick > 245) { VersionInfo.HardwareError[0] |= FC_ERROR0_GYRO_NICK; AnalogOffsetNick = 245;};
if(AnalogOffsetRoll < 10) { VersionInfo.HardwareError[0] |= FC_ERROR0_GYRO_ROLL; AnalogOffsetRoll = 10;}; if(AnalogOffsetRoll > 245) { VersionInfo.HardwareError[0] |= FC_ERROR0_GYRO_ROLL; AnalogOffsetRoll = 245;};
if(AnalogOffsetGier < 10) { VersionInfo.HardwareError[0] |= FC_ERROR0_GYRO_YAW; AnalogOffsetGier = 10;}; if(AnalogOffsetGier > 245) { VersionInfo.HardwareError[0] |= FC_ERROR0_GYRO_YAW; AnalogOffsetGier = 245;};
while(twi_state) if(CheckDelay(timeout)) {printf("\n\r DAC or I2C ERROR! Check I2C, 3Vref, DAC and BL-Ctrl"); break;}
AdReady = 0;
ANALOG_ON;
while(!AdReady);
if(i<10) Delay_ms_Mess(10);
}
Delay_ms_Mess(70);
}
 
/*
0 n
1 r
2 g
3 y
4 x
5 n
6 r
7 u
8 z
9 L
10 n
11 r
12 g
13 y
14 x
15 n
16 r
17 L
*/
 
//#######################################################################################
//
ISR(ADC_vect)
//#######################################################################################
{
static unsigned char kanal=0,state = 0;
static signed char subcount = 0;
static signed int gier1, roll1, nick1, nick_filter, roll_filter;
static signed int accy, accx;
static long tmpLuftdruck = 0;
static char messanzahl_Druck = 0;
switch(state++)
{
case 0:
nick1 = ADC;
kanal = AD_ROLL;
break;
case 1:
roll1 = ADC;
kanal = AD_GIER;
break;
case 2:
gier1 = ADC;
kanal = AD_ACC_Y;
break;
case 3:
Aktuell_ay = NeutralAccY - ADC;
accy = Aktuell_ay;
kanal = AD_ACC_X;
break;
case 4:
Aktuell_ax = ADC - NeutralAccX;
accx = Aktuell_ax;
kanal = AD_NICK;
break;
case 5:
nick1 += ADC;
kanal = AD_ROLL;
break;
case 6:
roll1 += ADC;
kanal = AD_UBAT;
break;
case 7:
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
if(EE_Parameter.ExtraConfig & CFG_3_3V_REFERENCE) UBat = (3 * UBat + (11 * ADC) / 30) / 4; // there were some single FC2.1 with 3.3V reference
else
#endif
UBat = (3 * UBat + ADC / 3) / 4;
kanal = AD_ACC_Z;
break;
case 8:
AdWertAccHoch = (signed int) ADC - NeutralAccZ;
if(AdWertAccHoch > 1)
{
if(NeutralAccZ < 750)
{
subcount += 5;
if(modell_fliegt < 500) subcount += 10;
}
if(subcount > 100) { NeutralAccZ++; subcount -= 100;}
}
else if(AdWertAccHoch < -1)
{
if(NeutralAccZ > 550)
{
subcount -= 5;
if(modell_fliegt < 500) subcount -= 10;
if(subcount < -100) { NeutralAccZ--; subcount += 100;}
}
}
messanzahl_AccHoch = 1;
Aktuell_az = ADC;
Mess_Integral_Hoch += AdWertAccHoch; // Integrieren
Mess_Integral_Hoch -= Mess_Integral_Hoch / 1024; // dämfen
kanal = AD_DRUCK;
break;
// "case 9:" fehlt hier absichtlich
case 10:
nick1 += ADC;
kanal = AD_ROLL;
break;
case 11:
roll1 += ADC;
kanal = AD_GIER;
break;
case 12:
if(PlatinenVersion == 10) AdWertGier = (ADC + gier1 + 1) / 2;
else
if(PlatinenVersion >= 20) AdWertGier = 2047 - (ADC + gier1);
else AdWertGier = (ADC + gier1);
kanal = AD_ACC_Y;
break;
case 13:
Aktuell_ay = NeutralAccY - ADC;
AdWertAccRoll = (Aktuell_ay + accy);
kanal = AD_ACC_X;
break;
case 14:
Aktuell_ax = ADC - NeutralAccX;
AdWertAccNick = (Aktuell_ax + accx);
kanal = AD_NICK;
break;
case 15:
nick1 += ADC;
if(PlatinenVersion == 10) nick1 *= 2; else nick1 *= 4;
AdWertNick = nick1 / 8;
nick_filter = (nick_filter + nick1) / 2;
HiResNick = nick_filter - AdNeutralNick;
AdWertNickFilter = (AdWertNickFilter + HiResNick) / 2;
kanal = AD_ROLL;
break;
case 16:
roll1 += ADC;
if(PlatinenVersion == 10) roll1 *= 2; else roll1 *= 4;
AdWertRoll = roll1 / 8;
roll_filter = (roll_filter + roll1) / 2;
HiResRoll = roll_filter - AdNeutralRoll;
AdWertRollFilter = (AdWertRollFilter + HiResRoll) / 2;
kanal = AD_DRUCK;
break;
case 17:
state = 0;
AdReady = 1;
ZaehlMessungen++;
// "break" fehlt hier absichtlich
case 9:
MessLuftdruck = ADC;
tmpLuftdruck += MessLuftdruck;
if(++messanzahl_Druck >= 18)
{
signed int tmp;
Luftdruck = (7 * Luftdruck + tmpLuftdruck - (18 * 523) * (long)ExpandBaro + 4) / 8; // -523.19 counts per 10 counts offset step
HoehenWert = StartLuftdruck - Luftdruck;
SummenHoehe -= SummenHoehe/SM_FILTER;
SummenHoehe += HoehenWert;
tmp = (HoehenWert - SummenHoehe/SM_FILTER);
if(tmp > 1024) tmp = 1024; else if(tmp < -1024) tmp = -1024;
if(abs(VarioMeter) > 700) VarioMeter = (15 * VarioMeter + 8 * tmp)/16;
else VarioMeter = (31 * VarioMeter + 8 * tmp)/32;
tmpLuftdruck /= 2;
messanzahl_Druck = 18/2;
}
kanal = AD_NICK;
break;
default:
kanal = 0; state = 0; kanal = AD_NICK;
break;
}
ADMUX = kanal;
if(state != 0) ANALOG_ON;
}
 
/branches/V0.86d_MartinW_Jeti+V0.20/capacity.c
0,0 → 1,154
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) Holger Buss, Ingo Busker
// + Thanks to Marcel Haller (Lion) for the nice idea and first implementation
// + Nur für den privaten Gebrauch
// + www.MikroKopter.com
// + porting the sources to other systems or using the software on other systems (except hardware from www.mikrokopter.de) is not allowed
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Es gilt für das gesamte Projekt (Hardware, Software, Binärfiles, Sourcecode und Dokumentation),
// + dass eine Nutzung (auch auszugsweise) nur für den privaten (nicht-kommerziellen) Gebrauch zulässig ist.
// + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt
// + bzgl. der Nutzungsbedingungen aufzunehmen.
// + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen,
// + Verkauf von Luftbildaufnahmen, usw.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht,
// + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts
// + auf anderen Webseiten oder sonstigen Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de"
// + eindeutig als Ursprung verlinkt werden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion
// + Benutzung auf eigene Gefahr
// + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Portierung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur
// + mit unserer Zustimmung zulässig
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Redistributions of source code (with or without modifications) must retain the above copyright notice,
// + this list of conditions and the following disclaimer.
// + * Neither the name of the copyright holders nor the names of contributors may be used to endorse or promote products derived
// + from this software without specific prior written permission.
// + * The use of this project (hardware, software, binary files, sources and documentation) is only permittet
// + for non-commercial use (directly or indirectly)
// + Commercial use (for excample: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted
// + with our written permission
// + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be
// + clearly linked as origin
// + * porting to systems other than hardware from www.mikrokopter.de is not allowed
// + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
// + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN// + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// + POSSIBILITY OF SUCH DAMAGE.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
#include "capacity.h"
#include "twimaster.h"
#include "main.h"
#include "timer0.h"
#include "analog.h"
 
#define CAPACITY_UPDATE_INTERVAL 10 // 10 ms
#define FC_OFFSET_CURRENT 5 // calculate with a current of 0.5A
#define BL_OFFSET_CURRENT 2 // calculate with a current of 0.2A
 
// global varialbles
unsigned short update_timer = 0;
Capacity_t Capacity;
 
// initialize capacity calculation
void Capacity_Init(void)
{
Capacity.ActualCurrent = 0;
Capacity.UsedCapacity = 0;
Capacity.ActualPower = 0;
Capacity.MinOfMaxPWM = 0;
//Capacity.RemainCapacity = (EE_Parameter.UserParam1*100);
update_timer = SetDelay(CAPACITY_UPDATE_INTERVAL);
}
 
 
// called in main loop at a regular interval
void Capacity_Update(void)
{
unsigned short Current, SetSum; // max value will be 255 * 12 = 3060
static unsigned short SubCounter = 0;
static unsigned short CurrentOffset = 0;
static unsigned long SumCurrentOffset = 0;
unsigned char i, NumOfMotors, MinOfMaxPWM;
 
if(CheckDelay(update_timer))
{
update_timer += CAPACITY_UPDATE_INTERVAL; // do not use SetDelay to avoid timing leaks
// determine sum of all present BL currents and setpoints
Current = 0;
SetSum = 0;
NumOfMotors = 0;
MinOfMaxPWM = 255;
for(i = 0; i < MAX_MOTORS; i++)
{
if(Motor[i].State & MOTOR_STATE_PRESENT_MASK)
{
NumOfMotors++;
Current += (unsigned int)(Motor[i].Current);
SetSum += (unsigned int)(Motor[i].SetPoint);
if(Motor[i].MaxPWM < MinOfMaxPWM) MinOfMaxPWM = Motor[i].MaxPWM;
}
}
Capacity.MinOfMaxPWM = MinOfMaxPWM;
 
if(SetSum == 0) // if all setpoints are 0
{ // determine offsets of motor currents
#define CURRENT_AVERAGE 8 // 8bit = 256 * 10 ms = 2.56s average time
CurrentOffset = (unsigned int)(SumCurrentOffset>>CURRENT_AVERAGE);
SumCurrentOffset -= CurrentOffset;
SumCurrentOffset += Current;
// after averaging set current to static offset
Current = FC_OFFSET_CURRENT;
}
else // some motors are running, includes also motor test condition, where "MotorRunning" is false
{ // subtract offset
if(Current > CurrentOffset) Current -= CurrentOffset;
else Current = 0;
// add the FC and BL Offsets
Current += FC_OFFSET_CURRENT + NumOfMotors * BL_OFFSET_CURRENT;
}
 
// update actual Current
Capacity.ActualCurrent = Current;
// update actual Power
if(Current < 255) Capacity.ActualPower = (UBat * Current) / 100; // in W higher resolution
else Capacity.ActualPower = (UBat * (Current/4)) / 25; // in W
 
// update used capacity
SubCounter += Current;
 
// 100mA * 1ms * CAPACITY_UPDATE_INTERVAL = 1 mA * 100 ms * CAPACITY_UPDATE_INTERVAL
// = 1mA * 0.1s * CAPACITY_UPDATE_INTERVAL = 1mA * 1min / (600 / CAPACITY_UPDATE_INTERVAL)
// = 1mAh / (36000 / CAPACITY_UPDATE_INTERVAL)
#define SUB_COUNTER_LIMIT (36000 / CAPACITY_UPDATE_INTERVAL)
if(SubCounter > SUB_COUNTER_LIMIT)
{
Capacity.UsedCapacity++; // we have one mAh more
SubCounter -= SUB_COUNTER_LIMIT; // keep the remaining sub part
#ifdef WITH_REMAINCAPACITY // only include functions if DEBUG is defined in main.h
 
#warning : "### with REMAIN CAPACITY ###"
Capacity.RemainCapacity=(EE_Parameter.UserParam1*100)-Capacity.UsedCapacity; //Added by metro
if((Capacity.RemainCapacity<=0)&&(Capacity.RemainCapacity%10==0)&&(EE_Parameter.UserParam1!=0)) beeptime = 1000;
if((Capacity.RemainCapacity<=500)&&(Capacity.RemainCapacity%100==0)&&(EE_Parameter.UserParam1!=0)) beeptime = 10000;
#endif
}
} // EOF check delay update timer
}
/branches/V0.86d_MartinW_Jeti+V0.20/debug.c
0,0 → 1,48
#include "main.h"
#include "debug.h"
 
#ifdef DEBUG // only include functions if DEBUG is defined in main.h
 
#warning : "### DEBUG-Funktion aktiv ###"
 
 
 
unsigned char Debug_BufPtr = 0;
struct str_Debug tDebug;
unsigned char SendDebugOutput = 0;
 
// function called from _printf_P to output character
void Debug_Putchar(char c)
{
if (!SendDebugOutput)
{
tDebug.Text[Debug_BufPtr++] = c; // copy character to buffer
if (Debug_BufPtr > 30) Debug_BufPtr = 30; // avoid buffer overflow
}
}
 
void DebugSend(unsigned char cmd)
{
if (!SendDebugOutput)
{
tDebug.Cmd = cmd;
tDebug.Text[Debug_BufPtr] = '\0'; // end of text marker
Debug_BufPtr = 0; // set bufferindex to 0
SendDebugOutput = 1; // set flag to trasmit data the next time in serial transmit function
}
}
#endif
 
/*
add the following code block to the serial transmit function
 
#ifdef DEBUG // only include functions if DEBUG is defined
if(SendDebugOutput && UebertragungAbgeschlossen)
{
SendOutData('0', FC_ADDRESS, 1, (unsigned char *) &tDebug, sizeof(tDebug));
SendDebugOutput = 0;
}
#endif
 
*/
 
/branches/V0.86d_MartinW_Jeti+V0.20/eeprom.c
0,0 → 1,625
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) Holger Buss, Ingo Busker
// + Nur für den privaten Gebrauch
// + porting the sources to other systems or using the software on other systems (except hardware from www.mikrokopter.de) is not allowed
// + www.MikroKopter.com
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Es gilt für das gesamte Projekt (Hardware, Software, Binärfiles, Sourcecode und Dokumentation),
// + dass eine Nutzung (auch auszugsweise) nur für den privaten (nicht-kommerziellen) Gebrauch zulässig ist.
// + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt
// + bzgl. der Nutzungsbedingungen aufzunehmen.
// + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen,
// + Verkauf von Luftbildaufnahmen, usw.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht,
// + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts
// + auf anderen Webseiten oder sonstigen Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de"
// + eindeutig als Ursprung verlinkt werden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion
// + Benutzung auf eigene Gefahr
// + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Portierung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur
// + mit unserer Zustimmung zulässig
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Redistributions of source code (with or without modifications) must retain the above copyright notice,
// + this list of conditions and the following disclaimer.
// + * Neither the name of the copyright holders nor the names of contributors may be used to endorse or promote products derived
// + from this software without specific prior written permission.
// + * The use of this project (hardware, software, binary files, sources and documentation) is only permittet
// + for non-commercial use (directly or indirectly)
// + Commercial use (for excample: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted
// + with our written permission
// + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be
// + clearly linked as origin
// + * porting to systems other than hardware from www.mikrokopter.de is not allowed
// + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
// + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN// + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// + POSSIBILITY OF SUCH DAMAGE.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
 
#ifndef EEMEM
#define EEMEM __attribute__ ((section (".eeprom")))
#endif
 
 
#include <avr/eeprom.h>
#include <string.h>
#include "eeprom.h"
#include "uart.h"
#include "led.h"
#include "main.h"
#include "fc.h"
#include "twimaster.h"
 
paramset_t EE_Parameter;
MixerTable_t Mixer;
uint8_t RequiredMotors;
 
 
uint8_t RAM_Checksum(uint8_t* pBuffer, uint16_t len)
{
uint8_t crc = 0xAA;
uint16_t i;
 
for(i=0; i<len; i++)
{
crc += pBuffer[i];
}
return crc;
}
 
uint8_t EEProm_Checksum(uint16_t EEAddr, uint16_t len)
{
uint8_t crc = 0xAA;
uint16_t off;
 
for(off=0; off<len; off++)
{
crc += eeprom_read_byte((uint8_t*)(EEAddr + off));;
}
return crc;
}
 
void ParamSet_DefaultStickMapping(void)
{
EE_Parameter.Kanalbelegung[K_GAS] = 1;
EE_Parameter.Kanalbelegung[K_ROLL] = 2;
EE_Parameter.Kanalbelegung[K_NICK] = 3;
EE_Parameter.Kanalbelegung[K_GIER] = 4;
EE_Parameter.Kanalbelegung[K_POTI1] = 5;
EE_Parameter.Kanalbelegung[K_POTI2] = 6;
EE_Parameter.Kanalbelegung[K_POTI3] = 7;
EE_Parameter.Kanalbelegung[K_POTI4] = 8;
EE_Parameter.Kanalbelegung[K_POTI5] = 9;
EE_Parameter.Kanalbelegung[K_POTI6] = 10;
EE_Parameter.Kanalbelegung[K_POTI7] = 11;
EE_Parameter.Kanalbelegung[K_POTI8] = 12;
}
 
 
/***************************************************/
/* Default Values for parameter set 1 */
/***************************************************/
void CommonDefaults(void)
{
EE_Parameter.Revision = EEPARAM_REVISION;
 
if(PlatinenVersion >= 20)
{
EE_Parameter.Gyro_D = 10;
EE_Parameter.Driftkomp = 0;
EE_Parameter.GyroAccFaktor = 27;
EE_Parameter.WinkelUmschlagNick = 78;
EE_Parameter.WinkelUmschlagRoll = 78;
}
else
{
EE_Parameter.Gyro_D = 3;
EE_Parameter.Driftkomp = 32;
EE_Parameter.GyroAccFaktor = 30;
EE_Parameter.WinkelUmschlagNick = 85;
EE_Parameter.WinkelUmschlagRoll = 85;
}
EE_Parameter.GyroAccAbgleich = 32; // 1/k
EE_Parameter.GlobalConfig = CFG_ACHSENKOPPLUNG_AKTIV | CFG_KOMPASS_AKTIV | CFG_GPS_AKTIV | CFG_HOEHEN_SCHALTER;
EE_Parameter.ExtraConfig = CFG_GPS_AID | CFG2_VARIO_BEEP;
EE_Parameter.Receiver = RECEIVER_JETI;
EE_Parameter.MotorSafetySwitch = 0;
EE_Parameter.ExternalControl = 0;
 
EE_Parameter.Gas_Min = 8; // Wert : 0-32
EE_Parameter.Gas_Max = 230; // Wert : 33-247
EE_Parameter.KompassWirkung = 64; // Wert : 0-247
 
EE_Parameter.Hoehe_MinGas = 30;
EE_Parameter.MaxHoehe = 255; // Wert : 0-247 255 -> Poti1
EE_Parameter.Hoehe_P = 15; // Wert : 0-32
EE_Parameter.Luftdruck_D = 30; // Wert : 0-247
EE_Parameter.Hoehe_ACC_Wirkung = 0; // Wert : 0-247
EE_Parameter.Hoehe_HoverBand = 8; // Wert : 0-247
EE_Parameter.Hoehe_GPS_Z = 64; // Wert : 0-247
EE_Parameter.Hoehe_StickNeutralPoint = 0;// Wert : 0-247 (0 = Hover-Estimation)
EE_Parameter.Hoehe_Verstaerkung = 15; // Wert : 0-50 (15 -> ca. +/- 5m/sek bei Stick-Voll-Ausschlag)
 
EE_Parameter.UserParam1 = 0; // zur freien Verwendung
EE_Parameter.UserParam2 = 0; // zur freien Verwendung
EE_Parameter.UserParam3 = 0; // zur freien Verwendung
EE_Parameter.UserParam4 = 0; // zur freien Verwendung
EE_Parameter.UserParam5 = 0; // zur freien Verwendung
EE_Parameter.UserParam6 = 0; // zur freien Verwendung
EE_Parameter.UserParam7 = 0; // zur freien Verwendung
EE_Parameter.UserParam8 = 0; // zur freien Verwendung
 
EE_Parameter.ServoNickControl = 128; // Wert : 0-247 // Stellung des Servos
EE_Parameter.ServoNickComp = 50; // Wert : 0-247 // Einfluss Gyro/Servo
EE_Parameter.ServoCompInvert = 2; // Wert : 0-247 // Richtung Einfluss Gyro/Servo
EE_Parameter.ServoNickMin = 15; // Wert : 0-247 // Anschlag
EE_Parameter.ServoNickMax = 230; // Wert : 0-247 // Anschlag
EE_Parameter.ServoNickRefresh = 4;
EE_Parameter.Servo3 = 125;
EE_Parameter.Servo4 = 125;
EE_Parameter.Servo5 = 125;
EE_Parameter.ServoRollControl = 128; // Wert : 0-247 // Stellung des Servos
EE_Parameter.ServoRollComp = 85; // Wert : 0-247 // Einfluss Gyro/Servo
EE_Parameter.ServoRollMin = 70; // Wert : 0-247 // Anschlag
EE_Parameter.ServoRollMax = 220; // Wert : 0-247 // Anschlag
EE_Parameter.ServoManualControlSpeed = 60;
EE_Parameter.CamOrientation = 0; // Wert : 0-24 -> 0-360 -> 15° steps
 
EE_Parameter.J16Bitmask = 95;
EE_Parameter.J17Bitmask = 243;
EE_Parameter.WARN_J16_Bitmask = 0xAA;
EE_Parameter.WARN_J17_Bitmask = 0xAA;
EE_Parameter.J16Timing = 20;
EE_Parameter.J17Timing = 20;
 
EE_Parameter.LoopGasLimit = 50;
EE_Parameter.LoopThreshold = 90; // Wert: 0-247 Schwelle für Stickausschlag
EE_Parameter.LoopHysterese = 50;
EE_Parameter.BitConfig = 0; // Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
 
EE_Parameter.NaviGpsModeControl = 254; // 254 -> Poti 2
EE_Parameter.NaviGpsGain = 100;
EE_Parameter.NaviGpsP = 90;
EE_Parameter.NaviGpsI = 90;
EE_Parameter.NaviGpsD = 90;
EE_Parameter.NaviGpsPLimit = 75;
EE_Parameter.NaviGpsILimit = 85;
EE_Parameter.NaviGpsDLimit = 75;
EE_Parameter.NaviGpsACC = 0;
EE_Parameter.NaviGpsMinSat = 6;
EE_Parameter.NaviStickThreshold = 8;
EE_Parameter.NaviWindCorrection = 90;
EE_Parameter.NaviAccCompensation = 42;
EE_Parameter.NaviOperatingRadius = 245;
EE_Parameter.NaviAngleLimitation = 140;
EE_Parameter.NaviPH_LoginTime = 5;
EE_Parameter.OrientationAngle = 0;
EE_Parameter.CareFreeModeControl = 0;
EE_Parameter.UnterspannungsWarnung = 33; // Wert : 0-247 ( Automatische Zellenerkennung bei < 50)
EE_Parameter.NotGas = 45; // Wert : 0-247 // Gaswert bei Empangsverlust
EE_Parameter.NotGasZeit = 90; // Wert : 0-247 // Zeit bis auf NotGas geschaltet wird, wg. Rx-Problemen
EE_Parameter.MotorSmooth = 0;
EE_Parameter.ComingHomeAltitude = 0; // 0 = don't change
EE_Parameter.FailSafeTime = 0; // 0 = off
EE_Parameter.MaxAltitude = 150; // 0 = off
EE_Parameter.AchsKopplung1 = 90;
EE_Parameter.AchsKopplung2 = 55;
}
/*
void ParamSet_DefaultSet1(void) // sport
{
CommonDefaults();
EE_Parameter.Stick_P = 14; // Wert : 1-20
EE_Parameter.Stick_D = 16; // Wert : 0-20
EE_Parameter.StickGier_P = 12; // Wert : 1-20
EE_Parameter.Gyro_P = 80; // Wert : 0-247
EE_Parameter.Gyro_I = 150; // Wert : 0-247
EE_Parameter.Gyro_Gier_P = 80; // Wert : 0-247
EE_Parameter.Gyro_Gier_I = 150; // Wert : 0-247
EE_Parameter.Gyro_Stability = 6; // Wert : 1-8
EE_Parameter.I_Faktor = 32;
EE_Parameter.CouplingYawCorrection = 1;
EE_Parameter.GyroAccAbgleich = 16; // 1/k;
EE_Parameter.DynamicStability = 100;
memcpy(EE_Parameter.Name, "Sport\0", 12);
EE_Parameter.crc = RAM_Checksum((uint8_t*)(&EE_Parameter), sizeof(EE_Parameter)-1);
}
*/
 
/***************************************************/
/* Default Values for parameter set 1 */
/***************************************************/
void ParamSet_DefaultSet1(void) // normal
{
CommonDefaults();
EE_Parameter.Stick_P = 10; // Wert : 1-20
EE_Parameter.Stick_D = 16; // Wert : 0-20
EE_Parameter.StickGier_P = 6; // Wert : 1-20
EE_Parameter.Gyro_P = 90; // Wert : 0-247
EE_Parameter.Gyro_I = 120; // Wert : 0-247
EE_Parameter.Gyro_Gier_P = 90; // Wert : 0-247
EE_Parameter.Gyro_Gier_I = 120; // Wert : 0-247
EE_Parameter.Gyro_Stability = 6; // Wert : 1-8
EE_Parameter.I_Faktor = 32;
EE_Parameter.CouplingYawCorrection = 60;
EE_Parameter.DynamicStability = 75;
memcpy(EE_Parameter.Name, "Fast\0", 12);
EE_Parameter.crc = RAM_Checksum((uint8_t*)(&EE_Parameter), sizeof(EE_Parameter)-1);
}
 
 
/***************************************************/
/* Default Values for parameter set 2 */
/***************************************************/
void ParamSet_DefaultSet2(void) // beginner
{
CommonDefaults();
EE_Parameter.Stick_P = 8; // Wert : 1-20
EE_Parameter.Stick_D = 16; // Wert : 0-20
EE_Parameter.StickGier_P = 6; // Wert : 1-20
EE_Parameter.Gyro_P = 100; // Wert : 0-247
EE_Parameter.Gyro_I = 120; // Wert : 0-247
EE_Parameter.Gyro_Gier_P = 100; // Wert : 0-247
EE_Parameter.Gyro_Gier_I = 120; // Wert : 0-247
EE_Parameter.Gyro_Stability = 6; // Wert : 1-8
EE_Parameter.I_Faktor = 16;
EE_Parameter.CouplingYawCorrection = 70;
EE_Parameter.DynamicStability = 70;
memcpy(EE_Parameter.Name, "Normal\0", 12);
EE_Parameter.crc = RAM_Checksum((uint8_t*)(&EE_Parameter), sizeof(EE_Parameter)-1);
}
 
/***************************************************/
/* Default Values for parameter set 3 */
/***************************************************/
void ParamSet_DefaultSet3(void) // beginner
{
CommonDefaults();
EE_Parameter.Stick_P = 6; // Wert : 1-20
EE_Parameter.Stick_D = 10; // Wert : 0-20
EE_Parameter.StickGier_P = 4; // Wert : 1-20
EE_Parameter.Gyro_P = 100; // Wert : 0-247
EE_Parameter.Gyro_I = 120; // Wert : 0-247
EE_Parameter.Gyro_Gier_P = 100; // Wert : 0-247
EE_Parameter.Gyro_Gier_I = 120; // Wert : 0-247
EE_Parameter.Gyro_Stability = 6; // Wert : 1-8
EE_Parameter.I_Faktor = 16;
EE_Parameter.CouplingYawCorrection = 70;
EE_Parameter.DynamicStability = 70;
memcpy(EE_Parameter.Name, "Easy\0", 12);
EE_Parameter.crc = RAM_Checksum((uint8_t*)(&EE_Parameter), sizeof(EE_Parameter)-1);
}
 
 
/***************************************************/
/* Read Parameter from EEPROM as byte */
/***************************************************/
uint8_t GetParamByte(uint16_t param_id)
{
return eeprom_read_byte((uint8_t*)(EEPROM_ADR_PARAM_BEGIN + param_id));
}
 
/***************************************************/
/* Write Parameter to EEPROM as byte */
/***************************************************/
void SetParamByte(uint16_t param_id, uint8_t value)
{
eeprom_write_byte((uint8_t*)(EEPROM_ADR_PARAM_BEGIN + param_id), value);
}
 
/***************************************************/
/* Read Parameter from EEPROM as word */
/***************************************************/
uint16_t GetParamWord(uint16_t param_id)
{
return eeprom_read_word((uint16_t *)(EEPROM_ADR_PARAM_BEGIN + param_id));
}
 
/***************************************************/
/* Write Parameter to EEPROM as word */
/***************************************************/
void SetParamWord(uint16_t param_id, uint16_t value)
{
eeprom_write_word((uint16_t*)(EEPROM_ADR_PARAM_BEGIN + param_id), value);
}
 
/***************************************************/
/* Read Parameter Set from EEPROM */
/***************************************************/
// number [1..5]
uint8_t ParamSet_ReadFromEEProm(uint8_t setnumber)
{
uint8_t crc;
uint16_t eeaddr;
 
// range the setnumber
if((1 > setnumber) || (setnumber > 5)) setnumber = 3;
 
// calculate eeprom addr
eeaddr = EEPROM_ADR_PARAMSET + PARAMSET_STRUCT_LEN * (setnumber - 1);
 
// calculate checksum from eeprom
crc = EEProm_Checksum(eeaddr, PARAMSET_STRUCT_LEN - 1);
 
// check crc
if(crc != eeprom_read_byte((uint8_t*)(eeaddr + PARAMSET_STRUCT_LEN - 1))) return 0;
 
// check revision
if(eeprom_read_byte((uint8_t*)(eeaddr)) != EEPARAM_REVISION) return 0;
 
// read paramset from eeprom
eeprom_read_block((void *) &EE_Parameter, (void*)(EEPROM_ADR_PARAMSET + PARAMSET_STRUCT_LEN * (setnumber - 1)), PARAMSET_STRUCT_LEN);
LED_Init();
#if ((defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__)) && defined(WITH_HOTTMENU))
#warning : "### with Hottmenu ###"
LIBFC_HoTT_Clear();
#endif
return 1;
}
 
/***************************************************/
/* Write Parameter Set to EEPROM */
/***************************************************/
// number [1..5]
uint8_t ParamSet_WriteToEEProm(uint8_t setnumber)
{
uint8_t crc;
 
if(EE_Parameter.Revision == EEPARAM_REVISION) // write only the right revision to eeprom
{
if(setnumber > 5) setnumber = 5;
if(setnumber < 1) return 0;
LIBFC_CheckSettings();
// update checksum
EE_Parameter.crc = RAM_Checksum((uint8_t*)(&EE_Parameter), sizeof(EE_Parameter)-1);
 
// write paramset to eeprom
eeprom_write_block((void *) &EE_Parameter, (void*)(EEPROM_ADR_PARAMSET + PARAMSET_STRUCT_LEN * (setnumber - 1)), PARAMSET_STRUCT_LEN);
 
// backup channel settings to separate block in eeprom
eeprom_write_block( (void*)(EE_Parameter.Kanalbelegung), (void*)(EEPROM_ADR_CHANNELS), sizeof(EE_Parameter.Kanalbelegung));
 
// write crc of channel block to eeprom
crc = RAM_Checksum((uint8_t*)(EE_Parameter.Kanalbelegung), sizeof(EE_Parameter.Kanalbelegung));
eeprom_write_byte((uint8_t*)(EEPROM_ADR_CHANNELS + sizeof(EE_Parameter.Kanalbelegung)), crc);
 
// update active settings number
SetActiveParamSet(setnumber);
LED_Init();
#if ((defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__)) && defined(WITH_HOTTMENU))
#warning : "### with Hottmenu ###"
LIBFC_HoTT_Clear();
#endif
return 1;
}
// wrong revision
return 0;
}
 
/***************************************************/
/* Read MixerTable from EEPROM */
/***************************************************/
uint8_t MixerTable_ReadFromEEProm(void)
{
uint8_t crc;
 
// calculate checksum in eeprom
crc = EEProm_Checksum(EEPROM_ADR_MIXERTABLE, sizeof(Mixer) - 1);
 
// check crc
if( crc != eeprom_read_byte((uint8_t*)(EEPROM_ADR_MIXERTABLE + sizeof(Mixer) - 1)) ) return 0;
 
// check revision
if(eeprom_read_byte((uint8_t*)(EEPROM_ADR_MIXERTABLE)) != EEMIXER_REVISION) return 0;
 
// read mixer table
eeprom_read_block((void *) &Mixer, (void*)(EEPROM_ADR_MIXERTABLE), sizeof(Mixer));
return 1;
}
 
/***************************************************/
/* Write Mixer Table to EEPROM */
/***************************************************/
uint8_t MixerTable_WriteToEEProm(void)
{
if(Mixer.Revision == EEMIXER_REVISION)
{
// update crc
Mixer.crc = RAM_Checksum((uint8_t*)(&Mixer), sizeof(Mixer) - 1);
 
// write to eeprom
eeprom_write_block((void *) &Mixer, (void*)(EEPROM_ADR_MIXERTABLE), sizeof(Mixer));
return 1;
}
else return 0;
}
 
/***************************************************/
/* Default Values for Mixer Table */
/***************************************************/
void MixerTable_Default(void) // Quadro
{
uint8_t i;
 
Mixer.Revision = EEMIXER_REVISION;
// clear mixer table
for(i = 0; i < 16; i++)
{
Mixer.Motor[i][MIX_GAS] = 0;
Mixer.Motor[i][MIX_NICK] = 0;
Mixer.Motor[i][MIX_ROLL] = 0;
Mixer.Motor[i][MIX_YAW] = 0;
}
// default = Quadro
Mixer.Motor[0][MIX_GAS] = 64; Mixer.Motor[0][MIX_NICK] = +64; Mixer.Motor[0][MIX_ROLL] = 0; Mixer.Motor[0][MIX_YAW] = +64;
Mixer.Motor[1][MIX_GAS] = 64; Mixer.Motor[1][MIX_NICK] = -64; Mixer.Motor[1][MIX_ROLL] = 0; Mixer.Motor[1][MIX_YAW] = +64;
Mixer.Motor[2][MIX_GAS] = 64; Mixer.Motor[2][MIX_NICK] = 0; Mixer.Motor[2][MIX_ROLL] = -64; Mixer.Motor[2][MIX_YAW] = -64;
Mixer.Motor[3][MIX_GAS] = 64; Mixer.Motor[3][MIX_NICK] = 0; Mixer.Motor[3][MIX_ROLL] = +64; Mixer.Motor[3][MIX_YAW] = -64;
memcpy(Mixer.Name, "Quadro\0", 7);
Mixer.crc = Mixer.crc = RAM_Checksum((uint8_t*)(&Mixer), sizeof(Mixer) - 1);
}
 
/***************************************************/
/* Get active parameter set */
/***************************************************/
uint8_t GetActiveParamSet(void)
{
uint8_t setnumber;
setnumber = eeprom_read_byte((uint8_t*)(EEPROM_ADR_PARAM_BEGIN + PID_ACTIVE_SET));
if(setnumber > 5)
{
setnumber = 3;
eeprom_write_byte((void*)(EEPROM_ADR_PARAM_BEGIN+PID_ACTIVE_SET), setnumber);
}
return(setnumber);
}
 
/***************************************************/
/* Set active parameter set */
/***************************************************/
void SetActiveParamSet(uint8_t setnumber)
{
if(setnumber > 5) setnumber = 5;
if(setnumber < 1) setnumber = 1;
eeprom_write_byte((uint8_t*)(EEPROM_ADR_PARAM_BEGIN + PID_ACTIVE_SET), setnumber);
}
 
/***************************************************/
/* Set default parameter set */
/***************************************************/
void SetDefaultParameter(uint8_t set, uint8_t restore_channels)
{
 
if(set > 5) set = 5;
else if(set < 1) set = 1;
 
switch(set)
{
case 1:
ParamSet_DefaultSet1(); // Fill ParamSet Structure to default parameter set 1 (Sport)
break;
case 2:
ParamSet_DefaultSet2(); // Kamera
break;
case 3:
ParamSet_DefaultSet3(); // Beginner
break;
default:
ParamSet_DefaultSet3(); // Beginner
break;
}
if(restore_channels)
{
uint8_t crc;
// 1st check for a valid channel backup in eeprom
crc = EEProm_Checksum(EEPROM_ADR_CHANNELS, sizeof(EE_Parameter.Kanalbelegung));
if(crc == eeprom_read_byte((uint8_t*)(EEPROM_ADR_CHANNELS + sizeof(EE_Parameter.Kanalbelegung))) )
{
eeprom_read_block((void *)EE_Parameter.Kanalbelegung, (void*)(EEPROM_ADR_CHANNELS), sizeof(EE_Parameter.Kanalbelegung));
}
else ParamSet_DefaultStickMapping();
}
else ParamSet_DefaultStickMapping();
ParamSet_WriteToEEProm(set);
}
 
/***************************************************/
/* Initialize EEPROM Parameter Sets */
/***************************************************/
void ParamSet_Init(void)
{
uint8_t channel_backup = 0, bad_params = 0, ee_default = 0,i;
 
 
if(EEPARAM_REVISION != GetParamByte(PID_EE_REVISION) )
{
ee_default = 1; // software update or forced by mktool
}
 
 
// 1st check for a valid channel backup in eeprom
i = EEProm_Checksum(EEPROM_ADR_CHANNELS, sizeof(EE_Parameter.Kanalbelegung));
if(i == eeprom_read_byte((uint8_t*)(EEPROM_ADR_CHANNELS + sizeof(EE_Parameter.Kanalbelegung))) ) channel_backup = 1;
 
 
// parameter check
 
// check all 5 parameter settings
for (i = 1;i < 6; i++)
{
if(ee_default || !ParamSet_ReadFromEEProm(i)) // could not read paramset from eeprom
{
bad_params = 1;
printf("\n\rGenerating default Parameter Set %d",i);
switch(i)
{
case 1:
ParamSet_DefaultSet1(); // Fill ParamSet Structure to default parameter set 1 (Sport)
break;
case 2:
ParamSet_DefaultSet2(); // Kamera
break;
case 3:
ParamSet_DefaultSet3(); // Beginner
break;
default:
ParamSet_DefaultSet3(); // Kamera
break;
}
if(channel_backup) // if we have an channel mapping backup in eeprom
{ // restore it from eeprom
eeprom_read_block((void *)EE_Parameter.Kanalbelegung, (void*)(EEPROM_ADR_CHANNELS), sizeof(EE_Parameter.Kanalbelegung));
}
else
{ // use default mapping
ParamSet_DefaultStickMapping();
}
ParamSet_WriteToEEProm(i);
}
}
if(bad_params) // at least one of the parameter settings were invalid
{
// default-Setting is parameter set 3
SetActiveParamSet(3);
}
 
 
// read active parameter set to ParamSet stucture
i = GetActiveParamSet();
ParamSet_ReadFromEEProm(i);
printf("\n\rUsing Parameter Set %d", i);
 
// load mixer table
if(GetParamByte(PID_EE_REVISION) == 0xff || !MixerTable_ReadFromEEProm() )
{
printf("\n\rGenerating default Mixer Table");
MixerTable_Default(); // Quadro
MixerTable_WriteToEEProm();
}
if(ee_default) SetParamByte(PID_EE_REVISION, EEPARAM_REVISION);
// determine motornumber
RequiredMotors = 0;
for(i = 0; i < 16; i++)
{
if(Mixer.Motor[i][MIX_GAS] > 0) RequiredMotors++;
}
 
printf("\n\rMixer-Config: '%s' (%u Motors)",Mixer.Name, RequiredMotors);
//printf("\n\r==============================");
printf("\n\r="); /// Martinw; removed memorysaving
}
/branches/V0.86d_MartinW_Jeti+V0.20/fc.c
0,0 → 1,1903
/*#######################################################################################
Flight Control
#######################################################################################*/
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) Holger Buss, Ingo Busker
// + Nur für den privaten Gebrauch / NON-COMMERCIAL USE ONLY
// + www.MikroKopter.com
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Es gilt für das gesamte Projekt (Hardware, Software, Binärfiles, Sourcecode und Dokumentation),
// + dass eine Nutzung (auch auszugsweise) nur für den privaten (nicht-kommerziellen) Gebrauch zulässig ist.
// + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt
// + bzgl. der Nutzungsbedingungen aufzunehmen.
// + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen,
// + Verkauf von Luftbildaufnahmen, usw.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht,
// + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts
// + auf anderen Webseiten oder sonstigen Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de"
// + eindeutig als Ursprung verlinkt werden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion
// + Benutzung auf eigene Gefahr
// + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Portierung oder Nutzung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur
// + mit unserer Zustimmung zulässig
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Redistributions of source code (with or without modifications) must retain the above copyright notice,
// + this list of conditions and the following disclaimer.
// + * Neither the name of the copyright holders nor the names of contributors may be used to endorse or promote products derived
// + from this software without specific prior written permission.
// + * The use of this project (hardware, software, binary files, sources and documentation) is only permittet
// + for non-commercial use (directly or indirectly)
// + Commercial use (for excample: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted
// + with our written permission
// + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be
// + clearly linked as origin
// + * porting the sources to other systems or using the software on other systems (except hardware from www.mikrokopter.de) is not allowed
// + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
// + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// + POSSIBILITY OF SUCH DAMAGE.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
#include "main.h"
#include "mymath.h"
#include "isqrt.h"
 
 
//MartinW; added vars
unsigned char loop1, loop2, loop3;
unsigned char settingdest = 5;
int keynumber=-7;
 
unsigned short CurrentOffset = 0;///
 
unsigned char pos1, pos2, pos3, pos4=0;
unsigned char Motors[8];
unsigned char Motorsmax[8];
unsigned short MotorsTmax;
unsigned char updatemotors=2;
 
//Panorama Trigger;
int degreeold =0;
int degreedivold =0;
int degreediv =0;
unsigned int panograd=0;
unsigned char panotrigger=0;
unsigned char calibration_done = 0;
///MartinW; added vars END
 
 
 
unsigned char h,m,s;
unsigned int BaroExpandActive = 0;
int MesswertNick,MesswertRoll,MesswertGier,MesswertGierBias, RohMesswertNick,RohMesswertRoll;
int TrimNick, TrimRoll;
int AdNeutralNick = 0,AdNeutralRoll = 0,AdNeutralGier = 0,StartNeutralRoll = 0,StartNeutralNick = 0;
int Mittelwert_AccNick, Mittelwert_AccRoll;
unsigned int NeutralAccX=0, NeutralAccY=0;
int NaviAccNick, NaviAccRoll,NaviCntAcc = 0;
int NeutralAccZ = 0;
unsigned char ControlHeading = 0;// in 2°
long IntegralNick = 0,IntegralNick2 = 0;
long IntegralRoll = 0,IntegralRoll2 = 0;
long IntegralAccNick = 0,IntegralAccRoll = 0,IntegralAccZ = 0;
long Integral_Gier = 0;
long Mess_IntegralNick = 0,Mess_IntegralNick2 = 0;
long Mess_IntegralRoll = 0,Mess_IntegralRoll2 = 0;
//long Mess_Integral_Gier = 0,Mess_Integral_Gier2 = 0; ///MartinW so war es
long Mess_Integral_Gier = 0; ///MartinW: Mess_Integral_Gier2 unbenutzt
 
long MittelIntegralNick,MittelIntegralRoll,MittelIntegralNick2,MittelIntegralRoll2;
long SummeNick=0,SummeRoll=0;
volatile long Mess_Integral_Hoch = 0;
int KompassValue = -1;
int KompassSollWert = 0;
//int KompassRichtung = 0;
char CalculateCompassTimer = 100;
unsigned char KompassFusion = 32;
unsigned int KompassSignalSchlecht = 50;
unsigned char MAX_GAS,MIN_GAS;
unsigned char HoehenReglerAktiv = 0;
unsigned char TrichterFlug = 0;
long Umschlag180Nick = 250000L, Umschlag180Roll = 250000L;
long ErsatzKompass;
int ErsatzKompassInGrad; // Kompasswert in Grad
int GierGyroFehler = 0;
char GyroFaktor,GyroFaktorGier;
char IntegralFaktor,IntegralFaktorGier;
int DiffNick,DiffRoll;
int StickGasHover = 120, HoverGasMin = 0, HoverGasMax = 1023;
int StickNick = 0,StickRoll = 0,StickGier = 0,StickGas = 0;
//int Poti1 = 0, Poti2 = 0, Poti3 = 0, Poti4 = 0, Poti5 = 0, Poti6 = 0, Poti7 = 0, Poti8 = 0;
unsigned char Poti[9] = {0,0,0,0,0,0,0,0};
volatile unsigned char SenderOkay = 0;
char MotorenEin = 0,StartTrigger = 0;
long HoehenWert = 0;
long SollHoehe = 0;
signed int AltitudeSetpointTrimming = 0;
long FromNC_AltitudeSetpoint = 0;
unsigned char FromNC_AltitudeSpeed = 0;
unsigned char carefree_old = 50; // to make the Beep when switching
signed char WaypointTrimming = 0;
int CompassGierSetpoint = 0;
int LageKorrekturRoll = 0,LageKorrekturNick = 0, HoverGas = 0;
//float Ki = FAKTOR_I;
int Ki = 10300 / 33;
unsigned char Looping_Nick = 0,Looping_Roll = 0;
unsigned char Looping_Links = 0, Looping_Rechts = 0, Looping_Unten = 0, Looping_Oben = 0;
 
unsigned char Parameter_Luftdruck_D = 48; // Wert : 0-250
unsigned char Parameter_HoehenSchalter = 251; // Wert : 0-250
unsigned char Parameter_Hoehe_P = 16; // Wert : 0-32
unsigned char Parameter_Hoehe_ACC_Wirkung = 58; // Wert : 0-250
unsigned char Parameter_KompassWirkung = 64; // Wert : 0-250
unsigned char Parameter_Hoehe_GPS_Z = 64; // Wert : 0-250
unsigned char Parameter_Gyro_D = 8; // Wert : 0-250
unsigned char Parameter_Gyro_P = 150; // Wert : 10-250
unsigned char Parameter_Gyro_I = 150; // Wert : 0-250
unsigned char Parameter_Gyro_Gier_P = 150; // Wert : 10-250
unsigned char Parameter_Gyro_Gier_I = 150; // Wert : 10-250
unsigned char Parameter_Gier_P = 2; // Wert : 1-20
unsigned char Parameter_I_Faktor = 10; // Wert : 1-20
unsigned char Parameter_UserParam1 = 0;
unsigned char Parameter_UserParam2 = 0;
unsigned char Parameter_UserParam3 = 0;
unsigned char Parameter_UserParam4 = 0;
unsigned char Parameter_UserParam5 = 0;
unsigned char Parameter_UserParam6 = 0;
unsigned char Parameter_UserParam7 = 0;
unsigned char Parameter_UserParam8 = 0;
unsigned char Parameter_ServoNickControl = 100;
unsigned char Parameter_ServoRollControl = 100;
unsigned char Parameter_LoopGasLimit = 70;
unsigned char Parameter_AchsKopplung1 = 90;
unsigned char Parameter_AchsKopplung2 = 65;
unsigned char Parameter_CouplingYawCorrection = 64;
//unsigned char Parameter_AchsGegenKopplung1 = 0;
unsigned char Parameter_DynamicStability = 100;
unsigned char Parameter_J16Bitmask; // for the J16 Output
unsigned char Parameter_J16Timing; // for the J16 Output
unsigned char Parameter_J17Bitmask; // for the J17 Output
unsigned char Parameter_J17Timing; // for the J17 Output
unsigned char Parameter_NaviGpsModeControl; // Parameters for the Naviboard
unsigned char Parameter_NaviGpsGain;
unsigned char Parameter_NaviGpsP;
unsigned char Parameter_NaviGpsI;
unsigned char Parameter_NaviGpsD;
unsigned char Parameter_NaviGpsACC;
unsigned char Parameter_NaviOperatingRadius;
unsigned char Parameter_NaviWindCorrection;
unsigned char Parameter_NaviSpeedCompensation;
unsigned char Parameter_ExternalControl;
unsigned char Parameter_GlobalConfig;
unsigned char Parameter_ExtraConfig;
unsigned char Parameter_MaximumAltitude;
unsigned char Parameter_Servo3,Parameter_Servo4,Parameter_Servo5;
unsigned char CareFree = 0;
const signed char sintab[31] = { 0, 2, 4, 6, 7, 8, 8, 8, 7, 6, 4, 2, 0, -2, -4, -6, -7, -8, -8, -8, -7, -6, -4, -2, 0, 2, 4, 6, 7, 8, 8}; // 15° steps
 
signed int ExternStickNick = 0,ExternStickRoll = 0,ExternStickGier = 0, ExternHoehenValue = -20;
int MaxStickNick = 0,MaxStickRoll = 0;
unsigned int modell_fliegt = 0;
volatile unsigned char FC_StatusFlags = 0, FC_StatusFlags2 = 0;
long GIER_GRAD_FAKTOR = 1291;
signed int KopplungsteilNickRoll,KopplungsteilRollNick;
signed int tmp_motorwert[MAX_MOTORS];
char VarioCharacter = ' ';
 
#define LIMIT_MIN(value, min) {if(value <= min) value = min;}
#define LIMIT_MAX(value, max) {if(value >= max) value = max;}
#define LIMIT_MIN_MAX(value, min, max) {if(value <= min) value = min; else if(value >= max) value = max;}
 
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Debugwerte zuordnen
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
void CopyDebugValues(void)
{
DebugOut.Analog[0] = IntegralNick / (EE_Parameter.GyroAccFaktor * 4);
DebugOut.Analog[1] = IntegralRoll / (EE_Parameter.GyroAccFaktor * 4);
DebugOut.Analog[2] = Mittelwert_AccNick / 4;
DebugOut.Analog[3] = Mittelwert_AccRoll / 4;
DebugOut.Analog[4] = (signed int) AdNeutralGier - AdWertGier;
DebugOut.Analog[5] = HoehenWert/5;
DebugOut.Analog[6] = AdWertAccHoch;//(Mess_Integral_Hoch / 512);// Aktuell_az;
DebugOut.Analog[8] = KompassValue;
DebugOut.Analog[9] = UBat;
DebugOut.Analog[10] = SenderOkay;
DebugOut.Analog[11] = ErsatzKompassInGrad;
DebugOut.Analog[12] = Motor[0].SetPoint;
DebugOut.Analog[13] = Motor[1].SetPoint;
DebugOut.Analog[14] = Motor[2].SetPoint;
DebugOut.Analog[15] = Motor[3].SetPoint;
///MartinW added Debug ouputs
DebugOut.Analog[16] = Motor[4].SetPoint;
DebugOut.Analog[17] = Motor[5].SetPoint;
DebugOut.Analog[18] = FromNC_AltitudeSpeed; ///
 
//DebugOut.Analog[18] = Motor[6].SetPoint; // v0.84a
//DebugOut.Analog[24] = Motor[6].SetPoint; // on v0.84a = SollHoehe/5
DebugOut.Analog[25] = Motor[6].SetPoint;
DebugOut.Analog[26] = Motor[7].SetPoint;
//DebugOut.Analog[27] = Motor[9].SetPoint; // on v0.84a = KompassSollWert
///MartinW added Debug ouputs END
 
DebugOut.Analog[20] = ServoNickValue;
DebugOut.Analog[22] = Capacity.ActualCurrent;
#ifdef WITH_REMAINCAPACITY // only include functions if DEBUG is defined in main.h
 
#warning : "### with REMAIN CAPACITY ###"
DebugOut.Analog[23] = Capacity.RemainCapacity;
#else
DebugOut.Analog[23] = Capacity.UsedCapacity;
#endif
 
DebugOut.Analog[24] = SollHoehe/5;
// DebugOut.Analog[22] = FromNaviCtrl_Value.GpsZ;
// DebugOut.Analog[29] = FromNaviCtrl_Value.SerialDataOkay;
DebugOut.Analog[27] = KompassSollWert;
DebugOut.Analog[29] = Capacity.MinOfMaxPWM;
DebugOut.Analog[30] = GPS_Nick;
DebugOut.Analog[31] = GPS_Roll;
if(VersionInfo.HardwareError[0] || VersionInfo.HardwareError[1]) DebugOut.Status[1] |= 1; else DebugOut.Status[1] &= 0xfe;
}
 
 
 
void Piep(unsigned char Anzahl, unsigned int dauer)
{
if(MotorenEin) return; //auf keinen Fall im Flug!
GRN_OFF;
while(Anzahl--)
{
beeptime = dauer;
while(beeptime);
Delay_ms(dauer * 2);
}
GRN_ON;
}
 
//############################################################################
// Messwerte beim Ermitteln der Nullage
void CalibrierMittelwert(void)
//############################################################################
{
unsigned char i;
if(PlatinenVersion == 13) SucheGyroOffset();
// ADC auschalten, damit die Werte sich nicht während der Berechnung ändern
ANALOG_OFF;
MesswertNick = AdWertNick;
MesswertRoll = AdWertRoll;
MesswertGier = AdWertGier;
Mittelwert_AccNick = ACC_AMPLIFY * AdWertAccNick;
Mittelwert_AccRoll = ACC_AMPLIFY * AdWertAccRoll;
// ADC einschalten
ANALOG_ON;
for(i=0;i<8;i++)
{
int tmp;
tmp = PPM_in[EE_Parameter.Kanalbelegung[K_POTI1 + i]] + 127;
LIMIT_MIN_MAX(tmp, 0, 255);
if(Poti[i] > tmp) Poti[i]--; else if(Poti[i] < tmp) Poti[i]++;
}
Umschlag180Nick = (long) EE_Parameter.WinkelUmschlagNick * 2500L;
Umschlag180Roll = (long) EE_Parameter.WinkelUmschlagRoll * 2500L;
}
 
//############################################################################
// Nullwerte ermitteln
void SetNeutral(unsigned char AccAdjustment)
//############################################################################
{
unsigned char i;
unsigned int gier_neutral=0, nick_neutral=0, roll_neutral=0;
VersionInfo.HardwareError[0] = 0;
HEF4017R_ON;
NeutralAccX = 0;
NeutralAccY = 0;
NeutralAccZ = 0;
 
AdNeutralNick = 0;
AdNeutralRoll = 0;
AdNeutralGier = 0;
 
Parameter_AchsKopplung1 = 0;
Parameter_AchsKopplung2 = 0;
 
ExpandBaro = 0;
 
CalibrierMittelwert();
Delay_ms_Mess(100);
 
CalibrierMittelwert();
 
if((EE_Parameter.GlobalConfig & CFG_HOEHENREGELUNG)) // Höhenregelung aktiviert?
{
if((MessLuftdruck > 950) || (MessLuftdruck < 750)) SucheLuftruckOffset();
}
#define NEUTRAL_FILTER 32
for(i=0; i<NEUTRAL_FILTER; i++)
{
Delay_ms_Mess(10);
gier_neutral += AdWertGier;
nick_neutral += AdWertNick;
roll_neutral += AdWertRoll;
}
AdNeutralNick= (nick_neutral+NEUTRAL_FILTER/2) / (NEUTRAL_FILTER / 8);
AdNeutralRoll= (roll_neutral+NEUTRAL_FILTER/2) / (NEUTRAL_FILTER / 8);
AdNeutralGier= (gier_neutral+NEUTRAL_FILTER/2) / (NEUTRAL_FILTER);
 
StartNeutralRoll = AdNeutralRoll;
StartNeutralNick = AdNeutralNick;
 
if(AccAdjustment)
{
NeutralAccX = abs(Mittelwert_AccNick) / (2*ACC_AMPLIFY);
NeutralAccY = abs(Mittelwert_AccRoll) / (2*ACC_AMPLIFY);
NeutralAccZ = Aktuell_az;
 
// Save ACC neutral settings to eeprom
SetParamWord(PID_ACC_NICK, (uint16_t)NeutralAccX);
SetParamWord(PID_ACC_ROLL, (uint16_t)NeutralAccY);
SetParamWord(PID_ACC_TOP, (uint16_t)NeutralAccZ);
}
else
{
// restore from eeprom
NeutralAccX = (int16_t)GetParamWord(PID_ACC_NICK);
NeutralAccY = (int16_t)GetParamWord(PID_ACC_ROLL);
NeutralAccZ = (int16_t)GetParamWord(PID_ACC_TOP);
// strange settings?
if(((unsigned int) NeutralAccX > 2048) || ((unsigned int) NeutralAccY > 2048) || ((unsigned int) NeutralAccZ > 1024))
{
printf("\n\rACC not calibrated!\r\n");
NeutralAccX = abs(Mittelwert_AccNick) / (2*ACC_AMPLIFY);
NeutralAccY = abs(Mittelwert_AccRoll) / (2*ACC_AMPLIFY);
NeutralAccZ = Aktuell_az;
}
}
 
MesswertNick = 0;
MesswertRoll = 0;
MesswertGier = 0;
Delay_ms_Mess(100);
Mittelwert_AccNick = ACC_AMPLIFY * AdWertAccNick;
Mittelwert_AccRoll = ACC_AMPLIFY * AdWertAccRoll;
IntegralNick = EE_Parameter.GyroAccFaktor * (long)Mittelwert_AccNick;
IntegralRoll = EE_Parameter.GyroAccFaktor * (long)Mittelwert_AccRoll;
Mess_IntegralNick2 = IntegralNick;
Mess_IntegralRoll2 = IntegralRoll;
Mess_Integral_Gier = 0;
StartLuftdruck = Luftdruck;
VarioMeter = 0;
Mess_Integral_Hoch = 0;
KompassSollWert = KompassValue;
KompassSignalSchlecht = 100;
beeptime = 50;
Umschlag180Nick = ((long) EE_Parameter.WinkelUmschlagNick * 2500L) + 15000L;
Umschlag180Roll = ((long) EE_Parameter.WinkelUmschlagRoll * 2500L) + 15000L;
ExternHoehenValue = 0;
ErsatzKompass = KompassValue * GIER_GRAD_FAKTOR;
GierGyroFehler = 0;
SendVersionToNavi = 1;
LED_Init();
FC_StatusFlags |= FC_STATUS_CALIBRATE;
FromNaviCtrl_Value.Kalman_K = -1;
FromNaviCtrl_Value.Kalman_MaxDrift = 0;
FromNaviCtrl_Value.Kalman_MaxFusion = 32;
for(i=0;i<8;i++)
{
Poti[i] = PPM_in[EE_Parameter.Kanalbelegung[K_POTI1 + i]] + 127;
}
SenderOkay = 100;
if(ServoActive)
{
HEF4017R_ON;
DDRD |=0x80; // enable J7 -> Servo signal
}
 
if((AdNeutralNick < 150 * 16) || (AdNeutralNick > 850 * 16)) { VersionInfo.HardwareError[0] |= FC_ERROR0_GYRO_NICK; };
if((AdNeutralRoll < 150 * 16) || (AdNeutralRoll > 850 * 16)) { VersionInfo.HardwareError[0] |= FC_ERROR0_GYRO_ROLL; };
if((AdNeutralGier < 150 * 2) || (AdNeutralGier > 850 * 2)) { VersionInfo.HardwareError[0] |= FC_ERROR0_GYRO_YAW; };
if((NeutralAccX < 300) || (NeutralAccX > 750)) { VersionInfo.HardwareError[0] |= FC_ERROR0_ACC_NICK; };
if((NeutralAccY < 300) || (NeutralAccY > 750)) { VersionInfo.HardwareError[0] |= FC_ERROR0_ACC_ROLL; };
if((NeutralAccZ < 512) || (NeutralAccZ > 850)) { VersionInfo.HardwareError[0] |= FC_ERROR0_ACC_TOP; };
carefree_old = 70;
#if ((defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__)) && defined(WITH_HOTTMENU))
#warning : "### with Hottmenu ###"
LIBFC_HoTT_Clear();
#endif
}
 
 
//############################################################################
// Bearbeitet die Messwerte
void Mittelwert(void)
//############################################################################
{
static signed long tmpl,tmpl2,tmpl3,tmpl4;
static signed int oldNick, oldRoll, d2Roll, d2Nick;
signed long winkel_nick, winkel_roll;
MesswertGier = (signed int) AdNeutralGier - AdWertGier;
MesswertNick = (signed int) AdWertNickFilter / 8;
MesswertRoll = (signed int) AdWertRollFilter / 8;
RohMesswertNick = MesswertNick;
RohMesswertRoll = MesswertRoll;
 
// Beschleunigungssensor ++++++++++++++++++++++++++++++++++++++++++++++++
Mittelwert_AccNick = (Mittelwert_AccNick * 3 + ((ACC_AMPLIFY * AdWertAccNick))) / 4L;
Mittelwert_AccRoll = (Mittelwert_AccRoll * 3 + ((ACC_AMPLIFY * AdWertAccRoll))) / 4L;
IntegralAccNick += ACC_AMPLIFY * AdWertAccNick;
IntegralAccRoll += ACC_AMPLIFY * AdWertAccRoll;
NaviAccNick += AdWertAccNick;
NaviAccRoll += AdWertAccRoll;
NaviCntAcc++;
IntegralAccZ += Aktuell_az - NeutralAccZ;
 
//++++++++++++++++++++++++++++++++++++++++++++++++
// ADC einschalten
ANALOG_ON;
AdReady = 0;
//++++++++++++++++++++++++++++++++++++++++++++++++
 
if(Mess_IntegralRoll > 93000L) winkel_roll = 93000L;
else if(Mess_IntegralRoll <-93000L) winkel_roll = -93000L;
else winkel_roll = Mess_IntegralRoll;
 
if(Mess_IntegralNick > 93000L) winkel_nick = 93000L;
else if(Mess_IntegralNick <-93000L) winkel_nick = -93000L;
else winkel_nick = Mess_IntegralNick;
 
// Gier ++++++++++++++++++++++++++++++++++++++++++++++++
Mess_Integral_Gier += MesswertGier;
ErsatzKompass += MesswertGier;
// Kopplungsanteil +++++++++++++++++++++++++++++++++++++
if(!Looping_Nick && !Looping_Roll && (Parameter_GlobalConfig & CFG_ACHSENKOPPLUNG_AKTIV))
{
tmpl3 = (MesswertRoll * winkel_nick) / 2048L;
tmpl3 *= Parameter_AchsKopplung2; //65
tmpl3 /= 4096L;
tmpl4 = (MesswertNick * winkel_roll) / 2048L;
tmpl4 *= Parameter_AchsKopplung2; //65
tmpl4 /= 4096L;
KopplungsteilNickRoll = tmpl3;
KopplungsteilRollNick = tmpl4;
tmpl4 -= tmpl3;
ErsatzKompass += tmpl4;
if(!Parameter_CouplingYawCorrection) Mess_Integral_Gier -= tmpl4/2; // Gier nachhelfen
 
tmpl = ((MesswertGier + tmpl4) * winkel_nick) / 2048L;
tmpl *= Parameter_AchsKopplung1; // 90
tmpl /= 4096L;
tmpl2 = ((MesswertGier + tmpl4) * winkel_roll) / 2048L;
tmpl2 *= Parameter_AchsKopplung1;
tmpl2 /= 4096L;
if(abs(MesswertGier) > 64) if(labs(tmpl) > 128 || labs(tmpl2) > 128) TrichterFlug = 1;
//MesswertGier += (Parameter_CouplingYawCorrection * tmpl4) / 256;
}
else tmpl = tmpl2 = KopplungsteilNickRoll = KopplungsteilRollNick = 0;
TrimRoll = tmpl - tmpl2 / 100L;
TrimNick = -tmpl2 + tmpl / 100L;
// Kompasswert begrenzen ++++++++++++++++++++++++++++++++++++++++++++++++
if(ErsatzKompass >= (360L * GIER_GRAD_FAKTOR)) ErsatzKompass -= 360L * GIER_GRAD_FAKTOR; // 360° Umschlag
if(ErsatzKompass < 0) ErsatzKompass += 360L * GIER_GRAD_FAKTOR;
// Roll ++++++++++++++++++++++++++++++++++++++++++++++++
Mess_IntegralRoll2 += MesswertRoll + TrimRoll;
Mess_IntegralRoll += MesswertRoll + TrimRoll - LageKorrekturRoll;
if(Mess_IntegralRoll > Umschlag180Roll)
{
Mess_IntegralRoll = -(Umschlag180Roll - 25000L);
Mess_IntegralRoll2 = Mess_IntegralRoll;
}
if(Mess_IntegralRoll <-Umschlag180Roll)
{
Mess_IntegralRoll = (Umschlag180Roll - 25000L);
Mess_IntegralRoll2 = Mess_IntegralRoll;
}
// Nick ++++++++++++++++++++++++++++++++++++++++++++++++
Mess_IntegralNick2 += MesswertNick + TrimNick;
Mess_IntegralNick += MesswertNick + TrimNick - LageKorrekturNick;
if(Mess_IntegralNick > Umschlag180Nick)
{
Mess_IntegralNick = -(Umschlag180Nick - 25000L);
Mess_IntegralNick2 = Mess_IntegralNick;
}
if(Mess_IntegralNick <-Umschlag180Nick)
{
Mess_IntegralNick = (Umschlag180Nick - 25000L);
Mess_IntegralNick2 = Mess_IntegralNick;
}
 
Integral_Gier = Mess_Integral_Gier;
IntegralNick = Mess_IntegralNick;
IntegralRoll = Mess_IntegralRoll;
IntegralNick2 = Mess_IntegralNick2;
IntegralRoll2 = Mess_IntegralRoll2;
 
#define D_LIMIT 128
 
MesswertNick = HiResNick / 8;
MesswertRoll = HiResRoll / 8;
 
if(AdWertNick < 15) MesswertNick = -1000; if(AdWertNick < 7) MesswertNick = -2000;
if(PlatinenVersion == 10) { if(AdWertNick > 1010) MesswertNick = +1000; if(AdWertNick > 1017) MesswertNick = +2000; }
else { if(AdWertNick > 2000) MesswertNick = +1000; if(AdWertNick > 2015) MesswertNick = +2000; }
if(AdWertRoll < 15) MesswertRoll = -1000; if(AdWertRoll < 7) MesswertRoll = -2000;
if(PlatinenVersion == 10) { if(AdWertRoll > 1010) MesswertRoll = +1000; if(AdWertRoll > 1017) MesswertRoll = +2000; }
else { if(AdWertRoll > 2000) MesswertRoll = +1000; if(AdWertRoll > 2015) MesswertRoll = +2000; }
 
if(Parameter_Gyro_D)
{
d2Nick = HiResNick - oldNick;
oldNick = (oldNick + HiResNick)/2;
if(d2Nick > D_LIMIT) d2Nick = D_LIMIT;
else if(d2Nick < -D_LIMIT) d2Nick = -D_LIMIT;
 
d2Roll = HiResRoll - oldRoll;
oldRoll = (oldRoll + HiResRoll)/2;
if(d2Roll > D_LIMIT) d2Roll = D_LIMIT;
else if(d2Roll < -D_LIMIT) d2Roll = -D_LIMIT;
 
MesswertNick += (d2Nick * (signed int) Parameter_Gyro_D) / 16;
MesswertRoll += (d2Roll * (signed int) Parameter_Gyro_D) / 16;
HiResNick += (d2Nick * (signed int) Parameter_Gyro_D);
HiResRoll += (d2Roll * (signed int) Parameter_Gyro_D);
}
 
if(RohMesswertRoll > 0) TrimRoll += ((long) abs(KopplungsteilNickRoll) * Parameter_CouplingYawCorrection) / 64L;
else TrimRoll -= ((long) abs(KopplungsteilNickRoll) * Parameter_CouplingYawCorrection) / 64L;
if(RohMesswertNick > 0) TrimNick += ((long) abs(KopplungsteilRollNick) * Parameter_CouplingYawCorrection) / 64L;
else TrimNick -= ((long) abs(KopplungsteilRollNick) * Parameter_CouplingYawCorrection) / 64L;
 
if(Parameter_GlobalConfig & CFG_DREHRATEN_BEGRENZER && !Looping_Nick && !Looping_Roll)
{
if(RohMesswertNick > 256) MesswertNick += 1 * (RohMesswertNick - 256);
else if(RohMesswertNick < -256) MesswertNick += 1 * (RohMesswertNick + 256);
if(RohMesswertRoll > 256) MesswertRoll += 1 * (RohMesswertRoll - 256);
else if(RohMesswertRoll < -256) MesswertRoll += 1 * (RohMesswertRoll + 256);
}
}
 
//############################################################################
// Senden der Motorwerte per I2C-Bus
void SendMotorData(void)
//############################################################################
{
unsigned char i;
if(!MotorenEin)
{
FC_StatusFlags &= ~(FC_STATUS_MOTOR_RUN | FC_STATUS_FLY);
for(i=0;i<MAX_MOTORS;i++)
{
if(!PC_MotortestActive) MotorTest[i] = 0;
Motor[i].SetPoint = MotorTest[i];
Motor[i].SetPointLowerBits = 0;
/*
Motor[i].SetPoint = MotorTest[i] / 4; // testing the high resolution
Motor[i].SetPointLowerBits = MotorTest[i] % 4;
*/
}
if(PC_MotortestActive) PC_MotortestActive--;
}
else FC_StatusFlags |= FC_STATUS_MOTOR_RUN;
 
if(I2C_TransferActive)
{
I2C_TransferActive = 0; // enable for the next time
}
else
{
motor_write = 0;
I2C_Start(TWI_STATE_MOTOR_TX); //Start I2C Interrupt Mode
}
}
 
 
 
//############################################################################
// Trägt ggf. das Poti als Parameter ein
void ParameterZuordnung(void)
//############################################################################
{
unsigned char tmp,i;
for(i=0;i<8;i++)
{
int tmp2;
tmp = EE_Parameter.Kanalbelegung[K_POTI1 + i];
tmp2 = PPM_in[tmp] + 127;
if(tmp2 > 255) tmp2 = 255; else if(tmp2 < 0) tmp2 = 0;
 
if(tmp == 25) Poti[i] = tmp2; // 25 = WaypointEvent channel -> no filter
else
if(tmp2 != Poti[i])
{
Poti[i] += (tmp2 - Poti[i]) / 4;
if(Poti[i] > tmp2) Poti[i]--;
else Poti[i]++;
}
}
CHK_POTI_MM(Parameter_Luftdruck_D,EE_Parameter.Luftdruck_D,0,100);
CHK_POTI_MM(Parameter_Hoehe_P,EE_Parameter.Hoehe_P,0,100);
CHK_POTI_MM(Parameter_Gyro_P,EE_Parameter.Gyro_P,10,255);
CHK_POTI_MM(Parameter_J16Timing,EE_Parameter.J16Timing,5,255);
CHK_POTI_MM(Parameter_J17Timing,EE_Parameter.J17Timing,5,255);
CHK_POTI(Parameter_Servo3,EE_Parameter.Servo3);
CHK_POTI(Parameter_Servo4,EE_Parameter.Servo4);
CHK_POTI(Parameter_Servo5,EE_Parameter.Servo5);
CHK_POTI(Parameter_HoehenSchalter,EE_Parameter.MaxHoehe);
CHK_POTI(Parameter_Hoehe_ACC_Wirkung,EE_Parameter.Hoehe_ACC_Wirkung);
CHK_POTI(Parameter_Hoehe_GPS_Z,EE_Parameter.Hoehe_GPS_Z);
CHK_POTI(Parameter_KompassWirkung,EE_Parameter.KompassWirkung);
CHK_POTI(Parameter_Gyro_I,EE_Parameter.Gyro_I);
CHK_POTI(Parameter_Gyro_D,EE_Parameter.Gyro_D);
CHK_POTI(Parameter_Gyro_Gier_P,EE_Parameter.Gyro_Gier_P);
CHK_POTI(Parameter_Gyro_Gier_I,EE_Parameter.Gyro_Gier_I);
CHK_POTI(Parameter_I_Faktor,EE_Parameter.I_Faktor);
CHK_POTI(Parameter_UserParam1,EE_Parameter.UserParam1);
CHK_POTI(Parameter_UserParam2,EE_Parameter.UserParam2);
CHK_POTI(Parameter_UserParam3,EE_Parameter.UserParam3);
CHK_POTI(Parameter_UserParam4,EE_Parameter.UserParam4);
CHK_POTI(Parameter_UserParam5,EE_Parameter.UserParam5);
CHK_POTI(Parameter_UserParam6,EE_Parameter.UserParam6);
CHK_POTI(Parameter_UserParam7,EE_Parameter.UserParam7);
CHK_POTI(Parameter_UserParam8,EE_Parameter.UserParam8);
CHK_POTI(Parameter_ServoNickControl,EE_Parameter.ServoNickControl);
CHK_POTI(Parameter_ServoRollControl,EE_Parameter.ServoRollControl);
CHK_POTI(Parameter_LoopGasLimit,EE_Parameter.LoopGasLimit);
CHK_POTI(Parameter_AchsKopplung1,EE_Parameter.AchsKopplung1);
CHK_POTI(Parameter_AchsKopplung2,EE_Parameter.AchsKopplung2);
CHK_POTI(Parameter_CouplingYawCorrection,EE_Parameter.CouplingYawCorrection);
CHK_POTI(Parameter_MaximumAltitude,EE_Parameter.MaxAltitude);
Parameter_GlobalConfig = EE_Parameter.GlobalConfig;
Parameter_ExtraConfig = EE_Parameter.ExtraConfig;
// CHK_POTI(Parameter_AchsGegenKopplung1,EE_Parameter.AchsGegenKopplung1,0,255);
CHK_POTI(Parameter_DynamicStability,EE_Parameter.DynamicStability);
CHK_POTI(Parameter_ExternalControl,EE_Parameter.ExternalControl);
Ki = 10300 / (Parameter_I_Faktor + 1);
MAX_GAS = EE_Parameter.Gas_Max;
MIN_GAS = EE_Parameter.Gas_Min;
 
tmp = EE_Parameter.CareFreeModeControl;
if(tmp > 50)
{
CareFree = 1;
if(tmp >= 248 && Poti[255 - tmp] < 50) CareFree = 0;
if(carefree_old != CareFree)
{
if(carefree_old < 3)
{
if(CareFree) beeptime = 1500;
else beeptime = 200;
carefree_old = CareFree;
} else carefree_old--;
}
if(FromNaviCtrl.CompassValue < 0 && CareFree) VersionInfo.HardwareError[0] |= FC_ERROR0_CAREFREE; //else VersionInfo.HardwareError[0] &= ~FC_ERROR0_CAREFREE;
}
else
{
CareFree = 0;
carefree_old = 10;
}
 
if(FromNaviCtrl.CompassValue < 0 && MotorenEin && CareFree && BeepMuster == 0xffff) // ungültiger Kompasswert
{
beeptime = 15000;
BeepMuster = 0xA400;
CareFree = 0;
}
if(CareFree) { FC_StatusFlags2 |= FC_STATUS2_CAREFREE; if(Parameter_AchsKopplung1 < 210) Parameter_AchsKopplung1 += 30;} else FC_StatusFlags2 &= ~FC_STATUS2_CAREFREE;
}
 
//############################################################################
//
void MotorRegler(void)
//############################################################################
{
int pd_ergebnis_nick,pd_ergebnis_roll,tmp_int, tmp_int2;
int GierMischanteil,GasMischanteil;
static long sollGier = 0,tmp_long,tmp_long2;
static long IntegralFehlerNick = 0;
static long IntegralFehlerRoll = 0;
static unsigned int RcLostTimer;
static unsigned char delay_neutral = 0;
static unsigned char delay_einschalten = 0,delay_ausschalten = 0;
static unsigned char calibration_done = 0;
static char NeueKompassRichtungMerken = 0;
static long ausgleichNick, ausgleichRoll;
int IntegralNickMalFaktor,IntegralRollMalFaktor;
unsigned char i;
Mittelwert();
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Gaswert ermitteln
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
GasMischanteil = StickGas;
if(GasMischanteil < MIN_GAS + 10) GasMischanteil = MIN_GAS + 10;
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Empfang schlecht
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(SenderOkay < 100 && !(FC_StatusFlags2 & FC_STATUS2_RC_FAILSAVE_ACTIVE))
{
if(RcLostTimer) RcLostTimer--;
else
{
MotorenEin = 0;
modell_fliegt = 0;
FC_StatusFlags &= ~(FC_STATUS_EMERGENCY_LANDING | FC_STATUS_FLY);
}
ROT_ON;
if(modell_fliegt > 1000) // wahrscheinlich in der Luft --> langsam absenken
{
GasMischanteil = EE_Parameter.NotGas;
FC_StatusFlags |= FC_STATUS_EMERGENCY_LANDING;
PPM_diff[EE_Parameter.Kanalbelegung[K_NICK]] = 0;
PPM_diff[EE_Parameter.Kanalbelegung[K_ROLL]] = 0;
PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] = 0;
PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]] = 0;
PPM_in[EE_Parameter.Kanalbelegung[K_GIER]] = 0;
}
else
{
MotorenEin = 0;
}
}
else
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Emfang gut
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(SenderOkay > 140)
{
FC_StatusFlags &= ~FC_STATUS_EMERGENCY_LANDING;
RcLostTimer = EE_Parameter.NotGasZeit * 50;
if(GasMischanteil > 40 && MotorenEin)
{
if(modell_fliegt < 0xffff) modell_fliegt++;
}
if((modell_fliegt < 256))
{
SummeNick = 0;
SummeRoll = 0;
sollGier = 0;
Mess_Integral_Gier = 0;
} else FC_StatusFlags |= FC_STATUS_FLY;
 
if((PPM_in[EE_Parameter.Kanalbelegung[K_GAS]] > 80) && MotorenEin == 0)
{
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// auf Nullwerte kalibrieren
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(PPM_in[EE_Parameter.Kanalbelegung[K_GIER]] > 75) // Neutralwerte
{
if(++delay_neutral > 200) // nicht sofort
{
MotorenEin = 0;
delay_neutral = 0;
modell_fliegt = 0;
if(PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] > 70 || abs(PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]]) > 70)
{
unsigned char setting=1;
if(PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]] > 70 && PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] < 70) setting = 1;
if(PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]] > 70 && PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] > 70) setting = 2;
if(PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]] < 70 && PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] > 70) setting = 3;
if(PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]] <-70 && PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] > 70) setting = 4;
if(PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]] <-70 && PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] < 70) setting = 5;
SetActiveParamSet(setting); // aktiven Datensatz merken
}
if(abs(PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]]) < 30 && PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] < -70)
{
WinkelOut.CalcState = 1;
beeptime = 1000;
}
else
{
ParamSet_ReadFromEEProm(GetActiveParamSet());
LipoDetection(0);
LIBFC_ReceiverInit(EE_Parameter.Receiver);
if((Parameter_GlobalConfig & CFG_HOEHENREGELUNG)) // Höhenregelung aktiviert?
{
if((MessLuftdruck > 950) || (MessLuftdruck < 750)) SucheLuftruckOffset();
}
ServoActive = 0;
SetNeutral(0);
calibration_done = 1;
ServoActive = 1;
DDRD |=0x80; // enable J7 -> Servo signal
Piep(GetActiveParamSet(),120);
}
}
}
else
if(PPM_in[EE_Parameter.Kanalbelegung[K_GIER]] < -75) // ACC Neutralwerte speichern
{
if(++delay_neutral > 200) // nicht sofort
{
MotorenEin = 0;
delay_neutral = 0;
modell_fliegt = 0;
SetNeutral(1);
calibration_done = 1;
Piep(GetActiveParamSet(),120);
}
}
else delay_neutral = 0;
}
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Gas ist unten
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
if(PPM_in[EE_Parameter.Kanalbelegung[K_GAS]] < 35-120)
{
// Motoren Starten
if(!MotorenEin)
{
if((PPM_in[EE_Parameter.Kanalbelegung[K_GIER]] < -75) && (PPM_in[EE_Parameter.MotorSafetySwitch] < -75 || EE_Parameter.MotorSafetySwitch == 0))
{
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Einschalten
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(++delay_einschalten > 200)
{
delay_einschalten = 0;
if(!VersionInfo.HardwareError[0] && calibration_done && !NC_ErrorCode)
{
modell_fliegt = 1;
MotorenEin = 1;
sollGier = 0;
Mess_Integral_Gier = 0;
// Mess_Integral_Gier2 = 0;
Mess_IntegralNick = EE_Parameter.GyroAccFaktor * (long)Mittelwert_AccNick;
Mess_IntegralRoll = EE_Parameter.GyroAccFaktor * (long)Mittelwert_AccRoll;
Mess_IntegralNick2 = IntegralNick;
Mess_IntegralRoll2 = IntegralRoll;
SummeNick = 0;
SummeRoll = 0;
FC_StatusFlags |= FC_STATUS_START;
// ControlHeading = (((int) EE_Parameter.OrientationAngle * 15 + KompassValue) % 360) / 2;
NeueKompassRichtungMerken = 100; // 2 sekunden
}
else
{
beeptime = 1500; // indicate missing calibration
}
}
}
else delay_einschalten = 0;
}
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Auschalten
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
else // only if motors are running
{
if((PPM_in[EE_Parameter.Kanalbelegung[K_GIER]] > 75) && (PPM_in[EE_Parameter.MotorSafetySwitch] < -75 || EE_Parameter.MotorSafetySwitch == 0))
{
if(++delay_ausschalten > 200) // nicht sofort
{
MotorenEin = 0;
delay_ausschalten = 0;
modell_fliegt = 0;
}
}
else delay_ausschalten = 0;
}
}
}
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// neue Werte von der Funke
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
if(!NewPpmData-- || (FC_StatusFlags & FC_STATUS_EMERGENCY_LANDING))
{
static int stick_nick,stick_roll;
unsigned char stick_p;
ParameterZuordnung();
stick_p = EE_Parameter.Stick_P;
stick_nick = (stick_nick * 3 + PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] * stick_p) / 4;
stick_nick += PPM_diff[EE_Parameter.Kanalbelegung[K_NICK]] * EE_Parameter.Stick_D;
stick_roll = (stick_roll * 3 + PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]] * stick_p) / 4;
stick_roll += PPM_diff[EE_Parameter.Kanalbelegung[K_ROLL]] * EE_Parameter.Stick_D;
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// CareFree und freie Wahl der vorderen Richtung
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(CareFree)
{
signed int nick, roll;
nick = stick_nick / 4;
roll = stick_roll / 4;
StickNick = ((FromNC_Rotate_C * nick) + (FromNC_Rotate_S * roll)) / (32 / 4);
StickRoll = ((FromNC_Rotate_C * roll) - (FromNC_Rotate_S * nick)) / (32 / 4);
}
else
{
FromNC_Rotate_C = sintab[EE_Parameter.OrientationAngle + 6];
FromNC_Rotate_S = sintab[EE_Parameter.OrientationAngle];
StickNick = ((FromNC_Rotate_C * stick_nick) + (FromNC_Rotate_S * stick_roll)) / 8;
StickRoll = ((FromNC_Rotate_C * stick_roll) - (FromNC_Rotate_S * stick_nick)) / 8;
}
 
StickGier = -PPM_in[EE_Parameter.Kanalbelegung[K_GIER]];
if(StickGier > 4) StickGier -= 4; else
if(StickGier < -4) StickGier += 4; else StickGier = 0;
 
if(GPS_Aid_StickMultiplikator) // in that case the GPS controls stronger
{
StickNick = (GPS_Aid_StickMultiplikator * (StickNick / 8)) / 16;
StickRoll = (GPS_Aid_StickMultiplikator * (StickRoll / 8)) / 16;
}
 
StickNick -= GPS_Nick;
StickRoll -= GPS_Roll;
StickGas = PPM_in[EE_Parameter.Kanalbelegung[K_GAS]] + 127;
 
GyroFaktor = (Parameter_Gyro_P + 10.0);
IntegralFaktor = Parameter_Gyro_I;
GyroFaktorGier = (Parameter_Gyro_Gier_P + 10.0);
IntegralFaktorGier = Parameter_Gyro_Gier_I;
 
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//+ Analoge Steuerung per Seriell
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
#ifdef WITH_ExternControl /// MartinW memorysaving
#warning : "### with ExternControl ###"
if(ExternControl.Config & 0x01 && Parameter_ExternalControl > 128)
{
StickNick += (int) ExternControl.Nick * (int) EE_Parameter.Stick_P;
StickRoll += (int) ExternControl.Roll * (int) EE_Parameter.Stick_P;
StickGier += ExternControl.Gier;
ExternHoehenValue = (int) ExternControl.Hight * (int)EE_Parameter.Hoehe_Verstaerkung;
if(ExternControl.Gas < StickGas) StickGas = ExternControl.Gas;
}
if(StickGas < 0) StickGas = 0;
 
if(Parameter_GlobalConfig & CFG_HEADING_HOLD) IntegralFaktor = 0;
 
if(abs(StickNick/STICK_GAIN) > MaxStickNick)
{
MaxStickNick = abs(StickNick)/STICK_GAIN;
if(MaxStickNick > 100) MaxStickNick = 100;
}
else MaxStickNick--;
if(abs(StickRoll/STICK_GAIN) > MaxStickRoll)
{
MaxStickRoll = abs(StickRoll)/STICK_GAIN;
if(MaxStickRoll > 100) MaxStickRoll = 100;
}
else MaxStickRoll--;
if(FC_StatusFlags & FC_STATUS_EMERGENCY_LANDING) {MaxStickNick = 0; MaxStickRoll = 0;}
#else
#warning : "### without ExternControl ###"
#endif
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Looping?
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if((PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]] > EE_Parameter.LoopThreshold) && EE_Parameter.BitConfig & CFG_LOOP_LINKS) Looping_Links = 1;
else
{
{
if((PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]] < (EE_Parameter.LoopThreshold - EE_Parameter.LoopHysterese))) Looping_Links = 0;
}
}
if((PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]] < -EE_Parameter.LoopThreshold) && EE_Parameter.BitConfig & CFG_LOOP_RECHTS) Looping_Rechts = 1;
else
{
if(Looping_Rechts) // Hysterese
{
if(PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]] > -(EE_Parameter.LoopThreshold - EE_Parameter.LoopHysterese)) Looping_Rechts = 0;
}
}
 
if((PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] > EE_Parameter.LoopThreshold) && EE_Parameter.BitConfig & CFG_LOOP_OBEN) Looping_Oben = 1;
else
{
if(Looping_Oben) // Hysterese
{
if((PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] < (EE_Parameter.LoopThreshold - EE_Parameter.LoopHysterese))) Looping_Oben = 0;
}
}
if((PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] < -EE_Parameter.LoopThreshold) && EE_Parameter.BitConfig & CFG_LOOP_UNTEN) Looping_Unten = 1;
else
{
if(Looping_Unten) // Hysterese
{
if(PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] > -(EE_Parameter.LoopThreshold - EE_Parameter.LoopHysterese)) Looping_Unten = 0;
}
}
 
if(Looping_Links || Looping_Rechts) Looping_Roll = 1; else Looping_Roll = 0;
if(Looping_Oben || Looping_Unten) { Looping_Nick = 1; Looping_Roll = 0; Looping_Links = 0; Looping_Rechts = 0;} else Looping_Nick = 0;
} // Ende neue Funken-Werte
 
if(Looping_Roll || Looping_Nick)
{
if(GasMischanteil > EE_Parameter.LoopGasLimit) GasMischanteil = EE_Parameter.LoopGasLimit;
TrichterFlug = 1;
}
 
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Bei Empfangsausfall im Flug
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(FC_StatusFlags2 & FC_STATUS2_RC_FAILSAVE_ACTIVE)
{
StickNick = -GPS_Nick;
StickRoll = -GPS_Roll;
StickGas = StickGasHover;
Parameter_GlobalConfig &= ~(CFG_HEADING_HOLD | CFG_DREHRATEN_BEGRENZER);
Parameter_GlobalConfig |= CFG_HOEHENREGELUNG | CFG_ACHSENKOPPLUNG_AKTIV | CFG_KOMPASS_AKTIV | CFG_GPS_AKTIV | CFG_HOEHEN_SCHALTER | CFG_GPS_AKTIV;
Parameter_ExtraConfig &= ~(CFG2_HEIGHT_LIMIT | CFG_LEARNABLE_CAREFREE | CFG2_VARIO_BEEP);
Parameter_HoehenSchalter = 200; // switch on
}
else
if(FC_StatusFlags & FC_STATUS_EMERGENCY_LANDING)
{
StickGier = 0;
StickNick = 0;
StickRoll = 0;
GyroFaktor = 90;
IntegralFaktor = 120;
GyroFaktorGier = 90;
IntegralFaktorGier = 120;
Looping_Roll = 0;
Looping_Nick = 0;
}
 
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Integrale auf ACC-Signal abgleichen
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
#define ABGLEICH_ANZAHL 256L
 
MittelIntegralNick += IntegralNick; // Für die Mittelwertbildung aufsummieren
MittelIntegralRoll += IntegralRoll;
MittelIntegralNick2 += IntegralNick2;
MittelIntegralRoll2 += IntegralRoll2;
 
if(Looping_Nick || Looping_Roll)
{
IntegralAccNick = 0;
IntegralAccRoll = 0;
MittelIntegralNick = 0;
MittelIntegralRoll = 0;
MittelIntegralNick2 = 0;
MittelIntegralRoll2 = 0;
Mess_IntegralNick2 = Mess_IntegralNick;
Mess_IntegralRoll2 = Mess_IntegralRoll;
ZaehlMessungen = 0;
LageKorrekturNick = 0;
LageKorrekturRoll = 0;
}
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(!Looping_Nick && !Looping_Roll && (Aktuell_az > 512 || MotorenEin))
{
long tmp_long, tmp_long2;
if(FromNaviCtrl_Value.Kalman_K > 0 /*&& !TrichterFlug*/)
{
tmp_long = (long)(IntegralNick / EE_Parameter.GyroAccFaktor - (long)(Mittelwert_AccNick - FromNaviCtrl.AccErrorN));
tmp_long2 = (long)(IntegralRoll / EE_Parameter.GyroAccFaktor - (long)(Mittelwert_AccRoll - FromNaviCtrl.AccErrorR));
tmp_long = (tmp_long * FromNaviCtrl_Value.Kalman_K) / (32 * 16);
tmp_long2 = (tmp_long2 * FromNaviCtrl_Value.Kalman_K) / (32 * 16);
if((MaxStickNick > 64) || (MaxStickRoll > 64))
{
tmp_long /= 2;
tmp_long2 /= 2;
}
if(abs(PPM_in[EE_Parameter.Kanalbelegung[K_GIER]]) > 25)
{
tmp_long /= 3;
tmp_long2 /= 3;
}
if(tmp_long > (long) FromNaviCtrl_Value.Kalman_MaxFusion) tmp_long = (long) FromNaviCtrl_Value.Kalman_MaxFusion;
if(tmp_long < (long)-FromNaviCtrl_Value.Kalman_MaxFusion) tmp_long = (long)-FromNaviCtrl_Value.Kalman_MaxFusion;
if(tmp_long2 > (long) FromNaviCtrl_Value.Kalman_MaxFusion) tmp_long2 = (long) FromNaviCtrl_Value.Kalman_MaxFusion;
if(tmp_long2 < (long)-FromNaviCtrl_Value.Kalman_MaxFusion) tmp_long2 = (long)-FromNaviCtrl_Value.Kalman_MaxFusion;
}
else
{
tmp_long = (long)(IntegralNick / EE_Parameter.GyroAccFaktor - (long)Mittelwert_AccNick);
tmp_long2 = (long)(IntegralRoll / EE_Parameter.GyroAccFaktor - (long)Mittelwert_AccRoll);
tmp_long /= 16;
tmp_long2 /= 16;
if((MaxStickNick > 64) || (MaxStickRoll > 64))
{
tmp_long /= 3;
tmp_long2 /= 3;
}
if(abs(PPM_in[EE_Parameter.Kanalbelegung[K_GIER]]) > 25)
{
tmp_long /= 3;
tmp_long2 /= 3;
}
KompassFusion = 25;
#define AUSGLEICH 32
if(tmp_long > AUSGLEICH) tmp_long = AUSGLEICH;
if(tmp_long < -AUSGLEICH) tmp_long =-AUSGLEICH;
if(tmp_long2 > AUSGLEICH) tmp_long2 = AUSGLEICH;
if(tmp_long2 <-AUSGLEICH) tmp_long2 =-AUSGLEICH;
}
 
Mess_IntegralNick -= tmp_long;
Mess_IntegralRoll -= tmp_long2;
}
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(ZaehlMessungen >= ABGLEICH_ANZAHL)
{
static int cnt = 0;
static char last_n_p,last_n_n,last_r_p,last_r_n;
static long MittelIntegralNick_Alt,MittelIntegralRoll_Alt;
if(!Looping_Nick && !Looping_Roll && !TrichterFlug && EE_Parameter.Driftkomp)
{
MittelIntegralNick /= ABGLEICH_ANZAHL;
MittelIntegralRoll /= ABGLEICH_ANZAHL;
IntegralAccNick = (EE_Parameter.GyroAccFaktor * IntegralAccNick) / ABGLEICH_ANZAHL;
IntegralAccRoll = (EE_Parameter.GyroAccFaktor * IntegralAccRoll) / ABGLEICH_ANZAHL;
IntegralAccZ = IntegralAccZ / ABGLEICH_ANZAHL;
#define MAX_I 0
// Nick ++++++++++++++++++++++++++++++++++++++++++++++++
IntegralFehlerNick = (long)(MittelIntegralNick - (long)IntegralAccNick);
ausgleichNick = IntegralFehlerNick / EE_Parameter.GyroAccAbgleich;
// Roll ++++++++++++++++++++++++++++++++++++++++++++++++
IntegralFehlerRoll = (long)(MittelIntegralRoll - (long)IntegralAccRoll);
ausgleichRoll = IntegralFehlerRoll / EE_Parameter.GyroAccAbgleich;
 
LageKorrekturNick = ausgleichNick / ABGLEICH_ANZAHL;
LageKorrekturRoll = ausgleichRoll / ABGLEICH_ANZAHL;
 
if(((MaxStickNick > 64) || (MaxStickRoll > 64) || (abs(PPM_in[EE_Parameter.Kanalbelegung[K_GIER]]) > 25)) && (FromNaviCtrl_Value.Kalman_K == -1))
{
LageKorrekturNick /= 2;
LageKorrekturRoll /= 2;
}
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Gyro-Drift ermitteln
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
MittelIntegralNick2 /= ABGLEICH_ANZAHL;
MittelIntegralRoll2 /= ABGLEICH_ANZAHL;
tmp_long = IntegralNick2 - IntegralNick;
tmp_long2 = IntegralRoll2 - IntegralRoll;
 
IntegralFehlerNick = tmp_long;
IntegralFehlerRoll = tmp_long2;
Mess_IntegralNick2 -= IntegralFehlerNick;
Mess_IntegralRoll2 -= IntegralFehlerRoll;
 
if(EE_Parameter.Driftkomp)
{
if(GierGyroFehler > ABGLEICH_ANZAHL/2) { AdNeutralGier++; }
if(GierGyroFehler <-ABGLEICH_ANZAHL/2) { AdNeutralGier--; }
}
GierGyroFehler = 0;
 
#define FEHLER_LIMIT (ABGLEICH_ANZAHL / 2)
#define FEHLER_LIMIT1 (ABGLEICH_ANZAHL * 2) //4
#define FEHLER_LIMIT2 (ABGLEICH_ANZAHL * 16) //16
#define BEWEGUNGS_LIMIT 20000
// Nick +++++++++++++++++++++++++++++++++++++++++++++++++
cnt = 1;// + labs(IntegralFehlerNick) / 4096;
if(labs(IntegralFehlerNick) > FEHLER_LIMIT1) cnt = 4;
if(labs(MittelIntegralNick_Alt - MittelIntegralNick) < BEWEGUNGS_LIMIT || (FromNaviCtrl_Value.Kalman_MaxDrift > 3*8))
{
if(IntegralFehlerNick > FEHLER_LIMIT2)
{
if(last_n_p)
{
cnt += labs(IntegralFehlerNick) / (FEHLER_LIMIT2 / 8);
ausgleichNick = IntegralFehlerNick / 8;
if(ausgleichNick > 5000) ausgleichNick = 5000;
LageKorrekturNick += ausgleichNick / ABGLEICH_ANZAHL;
}
else last_n_p = 1;
} else last_n_p = 0;
if(IntegralFehlerNick < -FEHLER_LIMIT2)
{
if(last_n_n)
{
cnt += labs(IntegralFehlerNick) / (FEHLER_LIMIT2 / 8);
ausgleichNick = IntegralFehlerNick / 8;
if(ausgleichNick < -5000) ausgleichNick = -5000;
LageKorrekturNick += ausgleichNick / ABGLEICH_ANZAHL;
}
else last_n_n = 1;
} else last_n_n = 0;
}
else
{
cnt = 0;
KompassSignalSchlecht = 100;
}
if(cnt > EE_Parameter.Driftkomp) cnt = EE_Parameter.Driftkomp;
if(FromNaviCtrl_Value.Kalman_MaxDrift) if(cnt > FromNaviCtrl_Value.Kalman_MaxDrift) cnt = FromNaviCtrl_Value.Kalman_MaxDrift;
if(IntegralFehlerNick > FEHLER_LIMIT) AdNeutralNick += cnt;
if(IntegralFehlerNick < -FEHLER_LIMIT) AdNeutralNick -= cnt;
 
// Roll +++++++++++++++++++++++++++++++++++++++++++++++++
cnt = 1;// + labs(IntegralFehlerRoll) / 4096;
if(labs(IntegralFehlerRoll) > FEHLER_LIMIT1) cnt = 4;
if(labs(MittelIntegralRoll_Alt - MittelIntegralRoll) < BEWEGUNGS_LIMIT || (FromNaviCtrl_Value.Kalman_MaxDrift > 3*8))
{
if(IntegralFehlerRoll > FEHLER_LIMIT2)
{
if(last_r_p)
{
cnt += labs(IntegralFehlerRoll) / (FEHLER_LIMIT2 / 8);
ausgleichRoll = IntegralFehlerRoll / 8;
if(ausgleichRoll > 5000) ausgleichRoll = 5000;
LageKorrekturRoll += ausgleichRoll / ABGLEICH_ANZAHL;
}
else last_r_p = 1;
} else last_r_p = 0;
if(IntegralFehlerRoll < -FEHLER_LIMIT2)
{
if(last_r_n)
{
cnt += labs(IntegralFehlerRoll) / (FEHLER_LIMIT2 / 8);
ausgleichRoll = IntegralFehlerRoll / 8;
if(ausgleichRoll < -5000) ausgleichRoll = -5000;
LageKorrekturRoll += ausgleichRoll / ABGLEICH_ANZAHL;
}
else last_r_n = 1;
} else last_r_n = 0;
} else
{
cnt = 0;
KompassSignalSchlecht = 100;
}
if(cnt > EE_Parameter.Driftkomp) cnt = EE_Parameter.Driftkomp;
if(FromNaviCtrl_Value.Kalman_MaxDrift) if(cnt > FromNaviCtrl_Value.Kalman_MaxDrift) cnt = FromNaviCtrl_Value.Kalman_MaxDrift;
if(IntegralFehlerRoll > FEHLER_LIMIT) AdNeutralRoll += cnt;
if(IntegralFehlerRoll < -FEHLER_LIMIT) AdNeutralRoll -= cnt;
}
else
{
LageKorrekturRoll = 0;
LageKorrekturNick = 0;
TrichterFlug = 0;
}
 
if(!IntegralFaktor) { LageKorrekturRoll = 0; LageKorrekturNick = 0;} // z.B. bei HH
// +++++++++++++++++++++++++++++++++++++++++++++++++++++
MittelIntegralNick_Alt = MittelIntegralNick;
MittelIntegralRoll_Alt = MittelIntegralRoll;
// +++++++++++++++++++++++++++++++++++++++++++++++++++++
IntegralAccNick = 0;
IntegralAccRoll = 0;
IntegralAccZ = 0;
MittelIntegralNick = 0;
MittelIntegralRoll = 0;
MittelIntegralNick2 = 0;
MittelIntegralRoll2 = 0;
ZaehlMessungen = 0;
} // ZaehlMessungen >= ABGLEICH_ANZAHL
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Gieren
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(abs(StickGier) > 3) // war 15
{
// KompassSignalSchlecht = 1000;
if(!(Parameter_GlobalConfig & CFG_KOMPASS_FIX))
{
NeueKompassRichtungMerken = 50; // eine Sekunde zum Einloggen
};
}
tmp_int = (long) EE_Parameter.StickGier_P * ((long)StickGier * abs(StickGier)) / 512L; // expo y = ax + bx²
tmp_int += (EE_Parameter.StickGier_P * StickGier) / 4;
tmp_int += CompassGierSetpoint;
sollGier = tmp_int;
Mess_Integral_Gier -= tmp_int;
if(Mess_Integral_Gier > 50000) Mess_Integral_Gier = 50000; // begrenzen
if(Mess_Integral_Gier <-50000) Mess_Integral_Gier =-50000;
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Kompass
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(KompassValue >= 0 && (Parameter_GlobalConfig & CFG_KOMPASS_AKTIV))
{
if(CalculateCompassTimer-- == 1)
{
int w,v,r,fehler,korrektur; // wird von der SPI-Routine auf 1 gesetzt
CalculateCompassTimer = 13; // falls keine Navi-Daten
// max. Korrekturwert schätzen
w = abs(IntegralNick /512); // mit zunehmender Neigung den Einfluss drosseln
v = abs(IntegralRoll /512);
if(v > w) w = v; // grösste Neigung ermitteln
// korrektur = w / 4 + 1;
korrektur = w / 8 + 2;
ErsatzKompassInGrad = ErsatzKompass/GIER_GRAD_FAKTOR;
// Kompassfehlerwert bestimmen
fehler = ((540 + KompassValue - ErsatzKompassInGrad) % 360) - 180;
// GIER_GRAD_FAKTOR ist ca. 1200
// Kompasswert einloggen
if(KompassSignalSchlecht) KompassSignalSchlecht--;
else
if(w < 25)
{
GierGyroFehler += fehler;
if(NeueKompassRichtungMerken)
{
if(--NeueKompassRichtungMerken == 0)
{
KompassSollWert = ErsatzKompassInGrad;
}
}
}
// Kompass fusionieren
if(!KompassSignalSchlecht) ErsatzKompass += (fehler * KompassFusion) / korrektur;
// MK Gieren
if(!NeueKompassRichtungMerken)
{
r = ((540 + (KompassSollWert - ErsatzKompassInGrad)) % 360) - 180;
v = r * (Parameter_KompassWirkung/2); // nach Kompass ausrichten
CompassGierSetpoint = v / 16;
}
else CompassGierSetpoint = 0;
} // CalculateCompassTimer
}
else CompassGierSetpoint = 0;
 
//DebugOut.Analog[16] = KompassFusion;
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Drehgeschwindigkeit und -winkel zu einem Istwert zusammenfassen
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(TrichterFlug) { SummeRoll = 0; SummeNick = 0;};
 
if(!Looping_Nick) IntegralNickMalFaktor = (IntegralNick * IntegralFaktor) / (44000 / STICK_GAIN); else IntegralNickMalFaktor = 0;
if(!Looping_Roll) IntegralRollMalFaktor = (IntegralRoll * IntegralFaktor) / (44000 / STICK_GAIN); else IntegralRollMalFaktor = 0;
 
#define TRIM_MAX 200
if(TrimNick > TRIM_MAX) TrimNick = TRIM_MAX; else if(TrimNick <-TRIM_MAX) TrimNick =-TRIM_MAX;
if(TrimRoll > TRIM_MAX) TrimRoll = TRIM_MAX; else if(TrimRoll <-TRIM_MAX) TrimRoll =-TRIM_MAX;
 
MesswertNick = IntegralNickMalFaktor + (long)((long)MesswertNick * GyroFaktor + (long)TrimNick * 128L) / (256L / STICK_GAIN);
MesswertRoll = IntegralRollMalFaktor + (long)((long)MesswertRoll * GyroFaktor + (long)TrimRoll * 128L) / (256L / STICK_GAIN);
MesswertGier = (long)(MesswertGier * 2 * (long)GyroFaktorGier) / (256L / STICK_GAIN) + (long)(Integral_Gier * IntegralFaktorGier) / (2 * (44000 / STICK_GAIN));
 
// Maximalwerte abfangen
#define MAX_SENSOR (4096)
if(MesswertNick > MAX_SENSOR) MesswertNick = MAX_SENSOR;
if(MesswertNick < -MAX_SENSOR) MesswertNick = -MAX_SENSOR;
if(MesswertRoll > MAX_SENSOR) MesswertRoll = MAX_SENSOR;
if(MesswertRoll < -MAX_SENSOR) MesswertRoll = -MAX_SENSOR;
if(MesswertGier > MAX_SENSOR) MesswertGier = MAX_SENSOR;
if(MesswertGier < -MAX_SENSOR) MesswertGier = -MAX_SENSOR;
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Höhenregelung
// Die Höhenregelung schwächt lediglich das Gas ab, erhöht es allerdings nicht
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(UBat > BattLowVoltageWarning) GasMischanteil = ((unsigned int)GasMischanteil * BattLowVoltageWarning) / UBat; // Gas auf das aktuelle Spannungvieveau beziehen
GasMischanteil *= STICK_GAIN;
// if height control is activated
if((Parameter_GlobalConfig & CFG_HOEHENREGELUNG) && !(Looping_Roll || Looping_Nick)) // Höhenregelung
{
#define HOVER_GAS_AVERAGE 16384L // 16384 * 2ms = 32s averaging
#define HC_GAS_AVERAGE 4 // 4 * 2ms= 8ms averaging
 
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
#define OPA_OFFSET_STEP 15
#else
#define OPA_OFFSET_STEP 10
#endif
int HCGas, HeightDeviation = 0,GasReduction = 0;
static int HeightTrimming = 0; // rate for change of height setpoint
static int FilterHCGas = 0;
static unsigned long HoverGasFilter = 0;
static unsigned char delay = 100, BaroAtUpperLimit = 0, BaroAtLowerLimit = 0;
int CosAttitude; // for projection of hoover gas
 
// get the current hooverpoint
DebugOut.Analog[21] = HoverGas;
 
// Expand the measurement
// measurement of air pressure close to upper limit and no overflow in correction of the new OCR0A value occurs
if(!BaroExpandActive)
{
if(MessLuftdruck > 920)
{ // increase offset
if(OCR0A < (255 - OPA_OFFSET_STEP))
{
ExpandBaro -= 1;
OCR0A = DruckOffsetSetting - OPA_OFFSET_STEP * ExpandBaro; // increase offset to shift ADC down
beeptime = 300;
BaroExpandActive = 350;
}
else
{
BaroAtLowerLimit = 1;
}
}
// measurement of air pressure close to lower limit and
else
if(MessLuftdruck < 100)
{ // decrease offset
if(OCR0A > OPA_OFFSET_STEP)
{
ExpandBaro += 1;
OCR0A = DruckOffsetSetting - OPA_OFFSET_STEP * ExpandBaro; // decrease offset to shift ADC up
beeptime = 300;
BaroExpandActive = 350;
}
else
{
BaroAtUpperLimit = 1;
}
}
else
{
BaroAtUpperLimit = 0;
BaroAtLowerLimit = 0;
}
}
else // delay, because of expanding the Baro-Range
{
// now clear the D-values
SummenHoehe = HoehenWert * SM_FILTER;
VarioMeter = 0;
BaroExpandActive--;
}
 
// if height control is activated by an rc channel
if(Parameter_GlobalConfig & CFG_HOEHEN_SCHALTER) // Regler wird über Schalter gesteuert
{ // check if parameter is less than activation threshold
if(Parameter_HoehenSchalter < 50) // for 3 or 2-state switch height control is disabled in lowest position
{ //height control not active
if(!delay--)
{
HoehenReglerAktiv = 0; // disable height control
SollHoehe = HoehenWert; // update SetPoint with current reading
delay = 1;
}
}
else
{ //height control is activated
HoehenReglerAktiv = 1; // enable height control
delay = 200;
}
}
else // no switchable height control
{
SollHoehe = ((int16_t) ExternHoehenValue + (int16_t) Parameter_HoehenSchalter) * (int)EE_Parameter.Hoehe_Verstaerkung;
HoehenReglerAktiv = 1;
}
 
// calculate cos of nick and roll angle used for projection of the vertical hoover gas
tmp_int = (int)(IntegralNick/GIER_GRAD_FAKTOR); // nick angle in deg
tmp_int2 = (int)(IntegralRoll/GIER_GRAD_FAKTOR); // roll angle in deg
CosAttitude = (int16_t)ihypot(tmp_int, tmp_int2); // phytagoras gives effective attitude angle in deg
LIMIT_MAX(CosAttitude, 60); // limit effective attitude angle
CosAttitude = c_cos_8192(CosAttitude); // cos of actual attitude
VarioCharacter = ' ';
AltitudeSetpointTrimming = 0;
if(HoehenReglerAktiv && !(FC_StatusFlags & FC_STATUS_EMERGENCY_LANDING))
{
#define HEIGHT_CONTROL_STICKTHRESHOLD 15
// Holger original version
// start of height control algorithm
// the height control is only an attenuation of the actual gas stick.
// I.e. it will work only if the gas stick is higher than the hover gas
// and the hover height will be allways larger than height setpoint.
FC_StatusFlags2 |= FC_STATUS2_ALTITUDE_CONTROL;
if((Parameter_ExtraConfig & CFG2_HEIGHT_LIMIT) || !(Parameter_GlobalConfig & CFG_HOEHEN_SCHALTER)) // Regler wird über Schalter gesteuert)
{ // old version
HCGas = GasMischanteil; // take current stick gas as neutral point for the height control
HeightTrimming = 0;
AltitudeSetpointTrimming = 0;
// set both flags to indicate no vario mode
FC_StatusFlags |= (FC_STATUS_VARIO_TRIM_UP|FC_STATUS_VARIO_TRIM_DOWN);
}
else
{
// alternative height control
// PD-Control with respect to hoover point
// the thrust loss out of horizontal attitude is compensated
// the setpoint will be fine adjusted with the gas stick position
if(FC_StatusFlags & FC_STATUS_FLY) // trim setpoint only when flying
{ // gas stick is above hoover point
if(StickGas > (StickGasHover + HEIGHT_CONTROL_STICKTHRESHOLD) && !BaroAtUpperLimit)
{
if(FC_StatusFlags & FC_STATUS_VARIO_TRIM_DOWN)
{
FC_StatusFlags &= ~FC_STATUS_VARIO_TRIM_DOWN;
SollHoehe = HoehenWert; // update setpoint to current heigth
}
FC_StatusFlags |= FC_STATUS_VARIO_TRIM_UP;
// Limit the maximum Altitude
if(Parameter_MaximumAltitude && (SollHoehe/100 > Parameter_MaximumAltitude)) AltitudeSetpointTrimming = 0;
else
{
// SollHoehe = (long) Parameter_MaximumAltitude * 100L;
// HeightTrimming += abs(StickGas - (StickGasHover - HEIGHT_CONTROL_STICKTHRESHOLD));
AltitudeSetpointTrimming = abs(StickGas - (StickGasHover + HEIGHT_CONTROL_STICKTHRESHOLD));
VarioCharacter = '+';
}
WaypointTrimming = 0;
} // gas stick is below hoover point
else if(StickGas < (StickGasHover - HEIGHT_CONTROL_STICKTHRESHOLD) && !BaroAtLowerLimit )
{
if(FC_StatusFlags & FC_STATUS_VARIO_TRIM_UP)
{
FC_StatusFlags &= ~FC_STATUS_VARIO_TRIM_UP;
SollHoehe = HoehenWert; // update setpoint to current heigth
}
FC_StatusFlags |= FC_STATUS_VARIO_TRIM_DOWN;
AltitudeSetpointTrimming = -abs(StickGas - (StickGasHover - HEIGHT_CONTROL_STICKTHRESHOLD));
// HeightTrimming -= abs(StickGas - (StickGasHover - HEIGHT_CONTROL_STICKTHRESHOLD));
VarioCharacter = '-';
WaypointTrimming = 0;
}
else // Gas Stick in Hover Range
{
VarioCharacter = '=';
if(FromNC_AltitudeSpeed && FromNC_AltitudeSetpoint > SollHoehe) // von NC gesteuert -> Steigen
{
FC_StatusFlags |= FC_STATUS_VARIO_TRIM_UP;
AltitudeSetpointTrimming = FromNC_AltitudeSpeed;
//HeightTrimming += FromNC_AltitudeSpeed;
WaypointTrimming = 10;
VarioCharacter = '^';
if(FC_StatusFlags & FC_STATUS_VARIO_TRIM_DOWN) // changed from sinking to rising
{
FC_StatusFlags &= ~FC_STATUS_VARIO_TRIM_DOWN;
SollHoehe = HoehenWert; // update setpoint to current heigth
}
}
else
if(FromNC_AltitudeSpeed && FromNC_AltitudeSetpoint < SollHoehe) // von NC gesteuert -> sinken
{
FC_StatusFlags |= FC_STATUS_VARIO_TRIM_DOWN;
AltitudeSetpointTrimming = -FromNC_AltitudeSpeed;
//HeightTrimming -= FromNC_AltitudeSpeed;
WaypointTrimming = -10;
VarioCharacter = 'v';
if(FC_StatusFlags & FC_STATUS_VARIO_TRIM_UP) // changed from rising to sinking
{
FC_StatusFlags &= ~FC_STATUS_VARIO_TRIM_UP;
SollHoehe = HoehenWert; // update setpoint to current heigth
}
}
else
if(FC_StatusFlags & (FC_STATUS_VARIO_TRIM_UP|FC_STATUS_VARIO_TRIM_DOWN))
{
if(!WaypointTrimming) LIMIT_MIN_MAX(SollHoehe, (HoehenWert-128), (HoehenWert+128)) // max. 1m Unterschied
else WaypointTrimming = 0;
FC_StatusFlags &= ~(FC_STATUS_VARIO_TRIM_UP|FC_STATUS_VARIO_TRIM_DOWN);
HeightTrimming = 0;
if(Parameter_ExtraConfig & CFG2_VARIO_BEEP) beeptime = 500;
if(!StartTrigger && HoehenWert > 50)
{
StartTrigger = 1;
}
}
}
// Trim height set point
HeightTrimming += AltitudeSetpointTrimming;
if(abs(HeightTrimming) > 500) // bei Waypoint-Flug ist das ca. die 500Hz
{
if(WaypointTrimming)
{
if(abs(FromNC_AltitudeSetpoint - SollHoehe) < 10) SollHoehe = FromNC_AltitudeSetpoint;
else SollHoehe += WaypointTrimming;
}
else
{
if(HeightTrimming > 0) SollHoehe += EE_Parameter.Hoehe_Verstaerkung / 3;
else SollHoehe -= EE_Parameter.Hoehe_Verstaerkung / 3;
}
HeightTrimming = 0;
LIMIT_MIN_MAX(SollHoehe, (HoehenWert-1024), (HoehenWert+1024)); // max. 10m Unterschied
if(Parameter_ExtraConfig & CFG2_VARIO_BEEP) beeptime = 100;
//update hoover gas stick value when setpoint is shifted
if(!EE_Parameter.Hoehe_StickNeutralPoint && FromNC_AltitudeSpeed == 0)
{
StickGasHover = HoverGas/STICK_GAIN; //rescale back to stick value
StickGasHover = (StickGasHover * UBat) / BattLowVoltageWarning;
if(StickGasHover < 70) StickGasHover = 70;
else if(StickGasHover > 150) StickGasHover = 150;
}
}
if(BaroExpandActive) SollHoehe = HoehenWert; // update setpoint to current altitude if Expanding is active
} //if FCFlags & MKFCFLAG_FLY
else
{
SollHoehe = HoehenWert - 400;
if(EE_Parameter.Hoehe_StickNeutralPoint) StickGasHover = EE_Parameter.Hoehe_StickNeutralPoint;
else StickGasHover = 120;
HoverGas = GasMischanteil;
VarioCharacter = '.';
}
HCGas = HoverGas; // take hover gas (neutral point)
}
if(HoehenWert > SollHoehe || !(Parameter_ExtraConfig & CFG2_HEIGHT_LIMIT))
{
// from this point the Heigth Control Algorithm is identical for both versions
if(BaroExpandActive) // baro range expanding active
{
HCGas = HoverGas; // hover while expanding baro adc range
HeightDeviation = 0;
} // EOF // baro range expanding active
else // valid data from air pressure sensor
{
// ------------------------- P-Part ----------------------------
tmp_long = (HoehenWert - SollHoehe); // positive when too high
LIMIT_MIN_MAX(tmp_long, -32767L, 32767L); // avoid overflov when casting to int16_t
HeightDeviation = (int)(tmp_long); // positive when too high
tmp_long = (tmp_long * (long)Parameter_Hoehe_P) / 32L; // p-part
LIMIT_MIN_MAX(tmp_long, -127 * STICK_GAIN, 256 * STICK_GAIN); // more than the full range makes no sense
GasReduction = tmp_long;
// ------------------------- D-Part 1: Vario Meter ----------------------------
tmp_int = VarioMeter / 8;
LIMIT_MIN_MAX(tmp_int, -127, 128);
tmp_int = (tmp_int * (long)Parameter_Luftdruck_D) / 4L; // scale to d-gain parameter
LIMIT_MIN_MAX(tmp_int,-64 * STICK_GAIN, 64 * STICK_GAIN);
if(FC_StatusFlags & (FC_STATUS_VARIO_TRIM_UP|FC_STATUS_VARIO_TRIM_DOWN)) tmp_int /= 4; // reduce d-part while trimming setpoint
else
if(Parameter_ExtraConfig & CFG2_HEIGHT_LIMIT) tmp_int /= 8; // reduce d-part in "Deckel" mode
GasReduction += tmp_int;
} // EOF no baro range expanding
// ------------------------ D-Part 2: ACC-Z Integral ------------------------
if(Parameter_Hoehe_ACC_Wirkung)
{
tmp_long = ((Mess_Integral_Hoch / 128L) * (int32_t) Parameter_Hoehe_ACC_Wirkung) / (128L / STICK_GAIN);
LIMIT_MIN_MAX(tmp_long, -32 * STICK_GAIN, 64 * STICK_GAIN);
GasReduction += tmp_long;
}
// ------------------------ D-Part 3: GpsZ ----------------------------------
tmp_int = (Parameter_Hoehe_GPS_Z * (int)FromNaviCtrl_Value.GpsZ)/128L;
LIMIT_MIN_MAX(tmp_int, -32 * STICK_GAIN, 64 * STICK_GAIN);
GasReduction += tmp_int;
GasReduction = (long)((long)GasReduction * HoverGas) / 512; // scale to the gas value
// ------------------------ ----------------------------------
HCGas -= GasReduction;
// limit deviation from hoover point within the target region
if(!AltitudeSetpointTrimming && HoverGas > 0) // height setpoint is not changed and hoover gas not zero
{
unsigned int tmp;
tmp = abs(HeightDeviation);
if(tmp <= 60)
{
LIMIT_MIN_MAX(HCGas, HoverGasMin, HoverGasMax); // limit gas around the hoover point
}
else
{
tmp = (tmp - 60) / 32;
if(tmp > 15) tmp = 15;
if(HeightDeviation > 0)
{
tmp = (HoverGasMin * (16 - tmp)) / 16;
LIMIT_MIN_MAX(HCGas, tmp, HoverGasMax); // limit gas around the hoover point
}
else
{
tmp = (HoverGasMax * (tmp + 16)) / 16;
LIMIT_MIN_MAX(HCGas, HoverGasMin, tmp); // limit gas around the hoover point
}
}
}
// strech control output by inverse attitude projection 1/cos
// + 1/cos(angle) ++++++++++++++++++++++++++
tmp_long2 = (int32_t)HCGas;
tmp_long2 *= 8192L;
tmp_long2 /= CosAttitude;
HCGas = (int16_t)tmp_long2;
// update height control gas averaging
FilterHCGas = (FilterHCGas * (HC_GAS_AVERAGE - 1) + HCGas) / HC_GAS_AVERAGE;
// limit height control gas pd-control output
LIMIT_MIN_MAX(FilterHCGas, EE_Parameter.Hoehe_MinGas * STICK_GAIN, (MAX_GAS - 20) * STICK_GAIN);
// set GasMischanteil to HeightControlGasFilter
if(Parameter_ExtraConfig & CFG2_HEIGHT_LIMIT)
{ // old version
LIMIT_MAX(FilterHCGas, GasMischanteil); // nicht mehr als Gas
GasMischanteil = FilterHCGas;
}
else GasMischanteil = FilterHCGas + (GasMischanteil - HoverGas) / 4; // only in Vario-Mode
}
}// EOF height control active
else // HC not active
{
//update hoover gas stick value when HC is not active
if(!EE_Parameter.Hoehe_StickNeutralPoint)
{
StickGasHover = HoverGas/STICK_GAIN; // rescale back to stick value
StickGasHover = (StickGasHover * UBat) / BattLowVoltageWarning;
}
else StickGasHover = EE_Parameter.Hoehe_StickNeutralPoint;
LIMIT_MIN_MAX(StickGasHover, 70, 150); // reserve some range for trim up and down
FilterHCGas = GasMischanteil;
// set both flags to indicate no vario mode
FC_StatusFlags |= (FC_STATUS_VARIO_TRIM_UP|FC_STATUS_VARIO_TRIM_DOWN);
FC_StatusFlags2 &= ~FC_STATUS2_ALTITUDE_CONTROL;
}
// Hover gas estimation by averaging gas control output on small z-velocities
// this is done only if height contol option is selected in global config and aircraft is flying
if((FC_StatusFlags & FC_STATUS_FLY))// && !(FC_SatusFlags & FC_STATUS_EMERGENCY_LANDING))
{
if(HoverGasFilter == 0 || StartTrigger == 1) HoverGasFilter = HOVER_GAS_AVERAGE * (unsigned long)(GasMischanteil); // init estimation
if(StartTrigger == 1) StartTrigger = 2;
tmp_long2 = (int32_t)GasMischanteil; // take current thrust
tmp_long2 *= CosAttitude; // apply attitude projection
tmp_long2 /= 8192;
// average vertical projected thrust
if(modell_fliegt < 4000) // the first 8 seconds
{ // reduce the time constant of averaging by factor of 4 to get much faster a stable value
HoverGasFilter -= HoverGasFilter/(HOVER_GAS_AVERAGE/16L);
HoverGasFilter += 16L * tmp_long2;
}
if(modell_fliegt < 8000) // the first 16 seconds
{ // reduce the time constant of averaging by factor of 2 to get much faster a stable value
HoverGasFilter -= HoverGasFilter/(HOVER_GAS_AVERAGE/4L);
HoverGasFilter += 4L * tmp_long2;
}
else //later
if(abs(VarioMeter) < 100 && abs(HoehenWert - SollHoehe) < 256) // only on small vertical speed & difference is small (only descending)
{
HoverGasFilter -= HoverGasFilter/HOVER_GAS_AVERAGE;
HoverGasFilter += tmp_long2;
}
HoverGas = (int16_t)(HoverGasFilter/HOVER_GAS_AVERAGE);
if(EE_Parameter.Hoehe_HoverBand)
{
int16_t band;
band = HoverGas / EE_Parameter.Hoehe_HoverBand; // the higher the parameter the smaller the range
HoverGasMin = HoverGas - band;
HoverGasMax = HoverGas + band;
}
else
{ // no limit
HoverGasMin = 0;
HoverGasMax = 1023;
}
}
else
{
StartTrigger = 0;
HoverGasFilter = 0;
HoverGas = 0;
}
}// EOF Parameter_GlobalConfig & CFG_HEIGHT_CONTROL
else
{
// set undefined state to indicate vario off
FC_StatusFlags |= (FC_STATUS_VARIO_TRIM_UP|FC_STATUS_VARIO_TRIM_DOWN);
} // EOF no height control
 
// limit gas to parameter setting
LIMIT_MIN(GasMischanteil, (MIN_GAS + 10) * STICK_GAIN);
if(GasMischanteil > (MAX_GAS - 20) * STICK_GAIN) GasMischanteil = (MAX_GAS - 20) * STICK_GAIN;
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// all BL-Ctrl connected?
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(MissingMotor || Capacity.MinOfMaxPWM != 255 || NC_ErrorCode) // wait until all BL-Ctrls started and no Errors
if(modell_fliegt > 1 && modell_fliegt < 50 && GasMischanteil > 0) // only during start-phase
{
modell_fliegt = 1;
GasMischanteil = (MIN_GAS + 10) * STICK_GAIN;
}
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Mischer und PI-Regler
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
DebugOut.Analog[7] = GasMischanteil;
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Gier-Anteil
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
GierMischanteil = MesswertGier - sollGier * STICK_GAIN; // Regler für Gier
#define MIN_GIERGAS (40*STICK_GAIN) // unter diesem Gaswert trotzdem Gieren
if(GasMischanteil > MIN_GIERGAS)
{
if(GierMischanteil > (GasMischanteil / 2)) GierMischanteil = GasMischanteil / 2;
if(GierMischanteil < -(GasMischanteil / 2)) GierMischanteil = -(GasMischanteil / 2);
}
else
{
if(GierMischanteil > (MIN_GIERGAS / 2)) GierMischanteil = MIN_GIERGAS / 2;
if(GierMischanteil < -(MIN_GIERGAS / 2)) GierMischanteil = -(MIN_GIERGAS / 2);
}
tmp_int = MAX_GAS*STICK_GAIN;
if(GierMischanteil > ((tmp_int - GasMischanteil))) GierMischanteil = ((tmp_int - GasMischanteil));
if(GierMischanteil < -((tmp_int - GasMischanteil))) GierMischanteil = -((tmp_int - GasMischanteil));
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Nick-Achse
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
DiffNick = MesswertNick - StickNick; // Differenz bestimmen
if(IntegralFaktor) SummeNick += IntegralNickMalFaktor - StickNick; // I-Anteil bei Winkelregelung
else SummeNick += DiffNick; // I-Anteil bei HH
if(SummeNick > (STICK_GAIN * 16000L)) SummeNick = (STICK_GAIN * 16000L);
if(SummeNick < -(16000L * STICK_GAIN)) SummeNick = -(16000L * STICK_GAIN);
 
if(EE_Parameter.Gyro_Stability <= 8) pd_ergebnis_nick = (EE_Parameter.Gyro_Stability * DiffNick) / 8; // PI-Regler für Nick
else pd_ergebnis_nick = ((EE_Parameter.Gyro_Stability / 2) * DiffNick) / 4; // Überlauf verhindern
pd_ergebnis_nick += SummeNick / Ki;
 
tmp_int = (long)((long)Parameter_DynamicStability * (long)(GasMischanteil + abs(GierMischanteil)/2)) / 64;
if(pd_ergebnis_nick > tmp_int) pd_ergebnis_nick = tmp_int;
if(pd_ergebnis_nick < -tmp_int) pd_ergebnis_nick = -tmp_int;
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Roll-Achse
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
DiffRoll = MesswertRoll - StickRoll; // Differenz bestimmen
if(IntegralFaktor) SummeRoll += IntegralRollMalFaktor - StickRoll;// I-Anteil bei Winkelregelung
else SummeRoll += DiffRoll; // I-Anteil bei HH
if(SummeRoll > (STICK_GAIN * 16000L)) SummeRoll = (STICK_GAIN * 16000L);
if(SummeRoll < -(16000L * STICK_GAIN)) SummeRoll = -(16000L * STICK_GAIN);
 
if(EE_Parameter.Gyro_Stability <= 8) pd_ergebnis_roll = (EE_Parameter.Gyro_Stability * DiffRoll) / 8; // PI-Regler für Roll
else pd_ergebnis_roll = ((EE_Parameter.Gyro_Stability / 2) * DiffRoll) / 4; // Überlauf verhindern
pd_ergebnis_roll += SummeRoll / Ki;
tmp_int = (long)((long)Parameter_DynamicStability * (long)(GasMischanteil + abs(GierMischanteil)/2)) / 64;
if(pd_ergebnis_roll > tmp_int) pd_ergebnis_roll = tmp_int;
if(pd_ergebnis_roll < -tmp_int) pd_ergebnis_roll = -tmp_int;
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Universal Mixer
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
for(i=0; i<MAX_MOTORS; i++)
{
signed int tmp_int;
if(Mixer.Motor[i][0] > 0)
{
// Gas
if(Mixer.Motor[i][0] == 64) tmp_int = GasMischanteil; else tmp_int = ((long)GasMischanteil * Mixer.Motor[i][0]) / 64L;
// Nick
if(Mixer.Motor[i][1] == 64) tmp_int += pd_ergebnis_nick;
else if(Mixer.Motor[i][1] == -64) tmp_int -= pd_ergebnis_nick;
else tmp_int += ((long)pd_ergebnis_nick * Mixer.Motor[i][1]) / 64L;
// Roll
if(Mixer.Motor[i][2] == 64) tmp_int += pd_ergebnis_roll;
else if(Mixer.Motor[i][2] == -64) tmp_int -= pd_ergebnis_roll;
else tmp_int += ((long)pd_ergebnis_roll * Mixer.Motor[i][2]) / 64L;
// Gier
if(Mixer.Motor[i][3] == 64) tmp_int += GierMischanteil;
else if(Mixer.Motor[i][3] == -64) tmp_int -= GierMischanteil;
else tmp_int += ((long)GierMischanteil * Mixer.Motor[i][3]) / 64L;
 
if(tmp_int > tmp_motorwert[i]) tmp_int = (tmp_motorwert[i] + tmp_int) / 2; // MotorSmoothing
// else tmp_int = 2 * tmp_int - tmp_motorwert[i]; // original MotorSmoothing
else
{
if(EE_Parameter.MotorSmooth == 0)
{
tmp_int = 2 * tmp_int - tmp_motorwert[i]; // original MotorSmoothing
}
else // 1 means tmp_int = tmp_int;
if(EE_Parameter.MotorSmooth > 1)
{
// If >= 2 then allow >= 50% of the intended step down to rapidly reach the intended value.
tmp_int = tmp_int + ((tmp_motorwert[i] - tmp_int)/EE_Parameter.MotorSmooth);
}
}
 
LIMIT_MIN_MAX(tmp_int,(int) MIN_GAS * 4,(int) MAX_GAS * 4);
Motor[i].SetPoint = tmp_int / 4;
Motor[i].SetPointLowerBits = (tmp_int % 4)<<1; // (3 bits total)
tmp_motorwert[i] = tmp_int;
}
else
{
Motor[i].SetPoint = 0;
Motor[i].SetPointLowerBits = 0;
}
}
}
/branches/V0.86d_MartinW_Jeti+V0.20/hottmenu.c
0,0 → 1,593
#include "libfc.h"
#include "printf_P.h"
#include "main.h"
#include "spi.h"
#include "capacity.h"
 
#if ((defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__)) && defined(WITH_HOTTMENU))
#warning : "### with Hottmenu ###"
 
#define HoTT_printf(format, args...) { _printf_P(&LIBFC_HoTT_Putchar, PSTR(format) , ## args);}
#define HoTT_printfxy(x,y,format, args...) { LIBFC_HoTT_SetPos(y * 21 + x); _printf_P(&LIBFC_HoTT_Putchar, PSTR(format) , ## args);}
#define HoTT_printfxy_INV(x,y,format, args...) { LIBFC_HoTT_SetPos(y * 21 + x); _printf_P(&LIBFC_HoTT_Putchar_INV, PSTR(format) , ## args);}
#define HoTT_printfxy_BLINK(x,y,format, args...) { LIBFC_HoTT_SetPos(y * 21 + x); _printf_P(&LIBFC_HoTT_Putchar_BLINK, PSTR(format) , ## args);}
#define HoTT_printf_BLINK(format, args...) { _printf_P(&LIBFC_HoTT_Putchar_BLINK, PSTR(format) , ## args);}
#define HoTT_printf_INV(format, args...) { _printf_P(&LIBFC_HoTT_Putchar_INV, PSTR(format) , ## args);}
 
#define VOICE_MINIMALE_EINGANSSPANNUNG 16
#define VOICE_BEEP 5
#define HoTT_GRAD 96
#define HoTT_LINKS 123
#define HoTT_RECHTS 124
#define HoTT_OBEN 125
#define HoTT_UNTEN 126
 
#define HOTT_KEY_RIGHT 1
#define HOTT_KEY_DOWN 2
#define HOTT_KEY_UP 4
#define HOTT_KEY_SET 6
#define HOTT_KEY_LEFT 8
#endif
 
#if ((defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__)))
GPSPacket_t GPSPacket;
VarioPacket_t VarioPacket;
ASCIIPacket_t ASCIIPacket;
ElectricAirPacket_t ElectricAirPacket;
HoTTGeneral_t HoTTGeneral;
int HoTTVarioMeter = 0;
 
const char PROGMEM NC_ERROR_TEXT[MAX_ERR_NUMBER][17] =
{
//0123456789123456
"No Error \0", // 0
"Not compatible \0", // 1
"MK3Mag not compa\0", // 2
"No FC communicat\0", // 3
"MK3Mag communica\0", // 4
"GPS communicatio\0", // 5
"compass value \0", // 6
"RC Signal lost \0", // 7
"FC spi rx error \0", // 8
"No NC communicat\0", // 9
"FC Nick Gyro \0", // 10
"FC Roll Gyro \0", // 11
"FC Yaw Gyro \0", // 12
"FC Nick ACC \0", // 13
"FC Roll ACC \0", // 14
"FC Z-ACC \0", // 15
"Pressure sensor \0", // 16
"I2C FC->BL-Ctrl \0", // 17
"Bl Missing \0", // 18
"Mixer Error \0", // 19
"Carefree Error \0", // 20
"GPS Fix lost \0", // 21
"Magnet Error \0", // 22
"Motor restart \0", // 23
"BL Limitation \0" // 24
};
#endif
 
#ifndef WITH_HOTTMENU
unsigned char HoTT_Telemety(unsigned char packet_request)
{
return(0);
}
#endif
 
#if ((defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__)) && defined(WITH_HOTTMENU))
#warning : "### with Hottmenu ###"
 
unsigned char MaxBlTempertaure = 0;
unsigned char MinBlTempertaure = 0;
unsigned char HottestBl = 0;
 
void GetHottestBl(void)
{
static unsigned char search = 0,tmp_max,tmp_min,who;
if(Motor[search].Temperature > tmp_max) { tmp_max = Motor[search].Temperature; who = search;}
else
if(Motor[search].Temperature) if(Motor[search].Temperature < tmp_min) tmp_min = Motor[search].Temperature;
if(++search > MAX_MOTORS)
{
search = 0;
if(tmp_min != 255) MinBlTempertaure = tmp_min; else MinBlTempertaure = 0;
MaxBlTempertaure = tmp_max;
HottestBl = who;
tmp_min = 255;
tmp_max = 0;
who = 0;
}
}
 
//---------------------------------------------------------------
void Hott_ClearLine(unsigned char line)
{
HoTT_printfxy(0,line," ");
}
//---------------------------------------------------------------
 
unsigned char HoTT_Waring(void)
{
if(FC_StatusFlags & FC_STATUS_LOWBAT) return(VOICE_MINIMALE_EINGANSSPANNUNG);
if(MotorenEin && NC_ErrorCode) return(VOICE_BEEP);
return(0);
}
 
//---------------------------------------------------------------
void NC_Fills_HoTT_Telemety(void)
{
unsigned char *ptr;
unsigned char max = 0,i,z;
switch(FromNaviCtrl.Param.Byte[11])
{
case HOTT_VARIO_PACKET_ID:
ptr = (unsigned char *) &VarioPacket;
max = sizeof(VarioPacket);
break;
case HOTT_GPS_PACKET_ID:
ptr = (unsigned char *) &GPSPacket;
max = sizeof(GPSPacket);
break;
case HOTT_ELECTRIC_AIR_PACKET_ID:
ptr = (unsigned char *) &ElectricAirPacket;
max = sizeof(ElectricAirPacket);
break;
case HOTT_GENERAL_PACKET_ID:
ptr = (unsigned char *) &HoTTGeneral;
max = sizeof(HoTTGeneral);
break;
}
z = FromNaviCtrl.Param.Byte[0]; // Data allocation
 
for(i=0; i < FromNaviCtrl.Param.Byte[1]; i++)
{
if(z >= max) break;
ptr[z] = FromNaviCtrl.Param.Byte[2+i];
z++;
}
}
 
unsigned int BuildHoTT_Vario(void)
{
unsigned int tmp = 30000;
if(VarioCharacter == '+' || VarioCharacter == '-')
{
tmp = 30000 + (AltitudeSetpointTrimming * EE_Parameter.Hoehe_Verstaerkung) / 3;
if(tmp < 30000 && tmp > 30000 - 50) tmp = 30000 - 50; // weil es sonst erst bei < 0,5m/sek piept
}
else
if((VarioCharacter == ' ') && (FC_StatusFlags & FC_STATUS_FLY))
{
tmp = 30000 + HoTTVarioMeter;
if(tmp > 30000)
{
if(tmp < 30000 + 100) tmp = 30000;
else tmp -= 100;
}
if(tmp < 30000)
{
if(tmp > 30000 - 100) tmp = 30000;
else tmp += 100;
}
}
else
if(VarioCharacter == '^') tmp = 30000 + FromNC_AltitudeSpeed * 10;
else
if(VarioCharacter == 'v') tmp = 30000 - FromNC_AltitudeSpeed * 10;
 
return(tmp);
}
 
 
//---------------------------------------------------------------
unsigned char HoTT_Telemety(unsigned char packet_request)
{
switch(packet_request)
{
case HOTT_VARIO_PACKET_ID:
VarioPacket.Altitude = HoehenWert/100 + 500;
VarioPacket.m_sec = BuildHoTT_Vario();
VarioPacket.m_3sec = VarioPacket.m_sec;
VarioPacket.m_10sec = VarioPacket.m_sec;
if (VarioPacket.Altitude < VarioPacket.MinAltitude) VarioPacket.MinAltitude = VarioPacket.Altitude;
if (VarioPacket.Altitude > VarioPacket.MaxAltitude) VarioPacket.MaxAltitude = VarioPacket.Altitude;
VarioPacket.WarnBeep = HoTT_Waring();
HoTT_DataPointer = (unsigned char *) &VarioPacket;
return(sizeof(VarioPacket));
break;
 
case HOTT_GPS_PACKET_ID:
GPSPacket.Altitude = HoehenWert/100 + 500;
// GPSPacket.Distance = GPSInfo.HomeDistance/10; // macht die NC
// GPSPacket.Heading = GPSInfo.HomeBearing/2; // macht die NC
// GPSPacket.Speed = (GPSInfo.Speed * 36) / 10; // macht die NC
GPSPacket.m_sec = BuildHoTT_Vario();
GPSPacket.m_3sec = 120;
GPSPacket.m_10sec = 0;
GPSPacket.WarnBeep = HoTT_Waring();
HoTT_DataPointer = (unsigned char *) &GPSPacket;
return(sizeof(GPSPacket));
break;
case HOTT_ELECTRIC_AIR_PACKET_ID:
GetHottestBl();
ElectricAirPacket.Altitude = HoehenWert/100 + 500;
ElectricAirPacket.Battery1 = UBat;
ElectricAirPacket.Battery2 = UBat;
ElectricAirPacket.VoltageCell1 = ErsatzKompassInGrad / 2;
ElectricAirPacket.VoltageCell8 = ElectricAirPacket.VoltageCell1;
ElectricAirPacket.VoltageCell6 = GPSInfo.HomeBearing / 2;
ElectricAirPacket.VoltageCell7 = GPSInfo.HomeDistance/20;
ElectricAirPacket.VoltageCell13 = ElectricAirPacket.VoltageCell6;
ElectricAirPacket.VoltageCell14 = ElectricAirPacket.VoltageCell7;
ElectricAirPacket.m_sec = BuildHoTT_Vario();
ElectricAirPacket.m_3sec = 120;
ElectricAirPacket.InputVoltage = UBat;
ElectricAirPacket.Temperature1 = MinBlTempertaure + 20;
ElectricAirPacket.Temperature2 = MaxBlTempertaure + 20;
ElectricAirPacket.Capacity = Capacity.UsedCapacity/10;
ElectricAirPacket.WarnBeep = HoTT_Waring();
ElectricAirPacket.Current = Capacity.ActualCurrent;
HoTT_DataPointer = (unsigned char *) &ElectricAirPacket;
return(sizeof(ElectricAirPacket));
break;
case HOTT_GENERAL_PACKET_ID:
GetHottestBl();
HoTTGeneral.Rpm = GPSInfo.HomeDistance/100;
HoTTGeneral.VoltageCell1 = ErsatzKompassInGrad / 2;
HoTTGeneral.VoltageCell6 = GPSInfo.HomeBearing / 2;
if(UBat > BattLowVoltageWarning + 5) HoTTGeneral.FuelPercent = (UBat - (BattLowVoltageWarning + 6)) * 3;
else HoTTGeneral.FuelPercent = 0;
HoTTGeneral.FuelCapacity = HoehenWert/100;
if(HoTTGeneral.FuelCapacity < 0) HoTTGeneral.FuelCapacity = 0;
HoTTGeneral.Altitude = HoehenWert/100 + 500;
HoTTGeneral.Battery1 = UBat;
HoTTGeneral.Battery2 = UBat;
HoTTGeneral.m_sec = BuildHoTT_Vario();
HoTTGeneral.m_3sec = 120;
HoTTGeneral.InputVoltage = UBat;
HoTTGeneral.Temperature1 = MinBlTempertaure + 20;
HoTTGeneral.Temperature2 = MaxBlTempertaure + 20;
HoTTGeneral.Capacity = Capacity.UsedCapacity/10;
HoTTGeneral.WarnBeep = HoTT_Waring();
HoTTGeneral.Current = Capacity.ActualCurrent;
HoTT_DataPointer = (unsigned char *) &HoTTGeneral;
return(sizeof(HoTTGeneral));
break;
default: return(0);
}
}
 
//---------------------------------------------------------------
void HoTT_Menu(void)
{
static unsigned char line, page = 0,show_current = 0,show_mag = 0, show_poti = 0;
unsigned char tmp;
HoTTVarioMeter = (HoTTVarioMeter * 7 + VarioMeter) / 8;
if(page == 0)
switch(line++)
{
case 0:
if(FC_StatusFlags & FC_STATUS_LOWBAT)
HoTT_printfxy_BLINK(0,0," %2i.%1iV ",UBat/10, UBat%10)
else
HoTT_printfxy(0,0," %2i.%1iV ",UBat/10, UBat%10)
 
if(Parameter_GlobalConfig & CFG_HOEHENREGELUNG)
{
if(HoehenReglerAktiv) HoTT_printfxy_INV(10,0,"ALT:%4im %c", (int16_t)(HoehenWert/100),VarioCharacter)
else HoTT_printfxy(10,0,"ALT:%4im ", (int16_t)(HoehenWert/100))
}
else HoTT_printfxy(10,0,"ALT:---- ");
break;
case 1:
if(FC_StatusFlags & FC_STATUS_LOWBAT)
HoTT_printfxy_BLINK(0,1," %2i:%02i ",FlugSekunden/60,FlugSekunden%60)
else HoTT_printfxy(0,1," %2i:%02i ",FlugSekunden/60,FlugSekunden%60);
HoTT_printfxy(10,1,"DIR: %3d%c",ErsatzKompassInGrad, HoTT_GRAD);
if(FC_StatusFlags2 & FC_STATUS2_CAREFREE) HoTT_printfxy_INV(20,1,"C") else HoTT_printfxy(20,1," ");
break;
case 2:
if(FC_StatusFlags & FC_STATUS_LOWBAT)
HoTT_printfxy_BLINK(0,2," %5i ",Capacity.UsedCapacity)
else HoTT_printfxy(0,2," %5i ",Capacity.UsedCapacity);
HoTT_printfxy(12,2,"I:%2i.%1iA ",Capacity.ActualCurrent/10, Capacity.ActualCurrent%10);
break;
case 3:
HoTT_printfxy(9,0,"I");
HoTT_printfxy(9,1,"I");
HoTT_printfxy(9,2,"I");
HoTT_printfxy(0,3,"---------+-----------");
HoTT_printfxy(0,6,"---------------------");
break;
case 4:
if(NaviDataOkay)
{
HoTT_printfxy(9,4,"I");
HoTT_printfxy(0,4,"SAT:%2d ",GPSInfo.NumOfSats);
HoTT_printfxy(10,4,"DIST:%3dm",GPSInfo.HomeDistance/10);
switch (GPSInfo.SatFix)
{
case SATFIX_3D:
if(GPSInfo.Flags & FLAG_DIFFSOLN) HoTT_printfxy(7,4,"D ")
else HoTT_printfxy(7,4,"3D");
break;
default:
HoTT_printfxy_BLINK(7,4,"!!");
break;
}
}
else
{
Hott_ClearLine(4);
}
break;
case 5:
if(NaviDataOkay)
{
if(show_mag)
{
HoTT_printfxy(0,5,"MAG:%3u%% ",EarthMagneticField);
HoTT_printfxy(12,5,"HM:%3d%c %c", GPSInfo.HomeBearing, HoTT_GRAD, NC_GPS_ModeCharacter);
HoTT_printfxy(9,5,"incl:%2d%c(%2i)",EarthMagneticInclination, HoTT_GRAD,EarthMagneticInclinationTheoretic);
}
else
{
HoTT_printfxy(9,5,"I");
HoTT_printfxy(0,5," %2um/s",GPSInfo.Speed,GPSInfo.NumOfSats);
HoTT_printfxy(11,5," HM:%3d%c %c", GPSInfo.HomeBearing, HoTT_GRAD, NC_GPS_ModeCharacter);
}
}
else Hott_ClearLine(5);
break;
case 6:
break;
case 7: if(NC_ErrorCode)
{
if(HoTTBlink && NC_ErrorCode < MAX_ERR_NUMBER)
{
Hott_ClearLine(7);
HoTT_printfxy_INV(0,7,"ERR: %2d !",NC_ErrorCode);
}
else
{
HoTT_printfxy(0,7,"ERR: "); _printf_P(&LIBFC_HoTT_Putchar, NC_ERROR_TEXT[NC_ErrorCode] , 0);};
}
else HoTT_printfxy(0,7," www.MikroKopter.de ");
break;
case 8: ASCIIPacket.WarnBeep = HoTT_Waring();
// ASCIIPacket.WarnBeep = Parameter_UserParam1;
case 9:
case 10:
case 11:
case 12:
case 13:
case 14:
case 15:
case 16:
if(HottKeyboard == HOTT_KEY_SET) { if(show_mag) show_mag = 0; else show_mag = 1;}
else
if(HottKeyboard == HOTT_KEY_LEFT) { LIBFC_HoTT_Clear(); page = 1; line = 0;};
HottKeyboard = 0;
break;
default: line = 0;
break;
}
else
if(page == 1)
switch(line++)
{
case 0:
if(FC_StatusFlags & FC_STATUS_LOWBAT)
HoTT_printfxy_BLINK(0,0," %2i:%02i %2i.%1iV %4imAh",FlugSekunden/60,FlugSekunden%60,UBat/10, UBat%10,Capacity.UsedCapacity)
else HoTT_printfxy(0,0," %2i:%02i %2i.%1iV %4imAh",FlugSekunden/60,FlugSekunden%60,UBat/10, UBat%10,Capacity.UsedCapacity);
break;
case 1:
HoTT_printfxy(0,1,"DIR:%3d%c",KompassValue, HoTT_GRAD);
if(Parameter_GlobalConfig & CFG_HOEHENREGELUNG)
{
if(HoehenReglerAktiv) HoTT_printfxy_INV(10,1,"ALT:%4im", (int16_t)(HoehenWert/100))
else HoTT_printfxy(10,1,"ALT:%4im", (int16_t)(HoehenWert/100))
}
else HoTT_printfxy(10,1,"ALT:---- ");
HoTT_printfxy(20,1,"%c",VarioCharacter);
break;
case 2:
if(NaviDataOkay)
{
HoTT_printfxy(1,2,"HM:%3d%c DIST:%3dm %c", GPSInfo.HomeBearing, HoTT_GRAD, GPSInfo.HomeDistance/10, NC_GPS_ModeCharacter);
}
else
{
Hott_ClearLine(2);
}
break;
case 3:
HoTT_printfxy(0,3,"PWR:%2i.%1iA (%iW) ",Capacity.ActualCurrent/10, Capacity.ActualCurrent%10,Capacity.ActualPower);
if(FC_StatusFlags2 & FC_STATUS2_CAREFREE) HoTT_printfxy_INV(19,3,"CF") else HoTT_printfxy(19,3," ");
break;
case 4:
if(NaviDataOkay)
{
HoTT_printfxy(0,4,"GPS:%2um/s SAT:%d ",GPSInfo.Speed,GPSInfo.NumOfSats);
switch (GPSInfo.SatFix)
{
case SATFIX_3D:
HoTT_printfxy(16,4," 3D ");
break;
//case SATFIX_2D:
//case SATFIX_NONE:
default:
HoTT_printfxy_BLINK(16,4,"NOFIX");
break;
}
if(GPSInfo.Flags & FLAG_DIFFSOLN)
{
HoTT_printfxy(16,4,"DGPS ");
}
}
else
{ //012345678901234567890
HoTT_printfxy(0,4," No NaviCtrl ");
}
break;
case 5:
if(show_current)
{
HoTT_printfxy(0,5,"%2i.%i %2i.%i %2i.%i %2i.%iA", Motor[0].Current/10,Motor[0].Current%10,Motor[1].Current/10,Motor[1].Current%10,Motor[2].Current/10,Motor[2].Current%10,Motor[3].Current/10,Motor[3].Current%10);
}
else
{
HoTT_printfxy(0,5,"%3i %3i %3i %3i%cC", Motor[0].Temperature, Motor[1].Temperature, Motor[2].Temperature, Motor[3].Temperature,HoTT_GRAD);
}
break;
case 6:
if(show_current)
{
if(RequiredMotors == 4) Hott_ClearLine(6);
else
if(RequiredMotors == 6) HoTT_printfxy(0,6,"%2i.%i %2i.%iA", Motor[4].Current/10,Motor[4].Current%10,Motor[5].Current/10,Motor[5].Current%10)
else
if(RequiredMotors > 6) HoTT_printfxy(0,6,"%2i.%i %2i.%i %2i.%i %2i.%iA", Motor[4].Current/10,Motor[4].Current%10,Motor[5].Current/10,Motor[5].Current%10,Motor[6].Current/10,Motor[6].Current%10,Motor[7].Current/10,Motor[7].Current%10);
}
else
{
if(RequiredMotors == 4) Hott_ClearLine(6);
else
if(RequiredMotors == 6) HoTT_printfxy(0,6,"%3i %3i%cC ", Motor[4].Temperature, Motor[5].Temperature,HoTT_GRAD)
else
if(RequiredMotors > 6) HoTT_printfxy(0,6,"%3i %3i %3i %3i%cC", Motor[4].Temperature, Motor[5].Temperature, Motor[6].Temperature, Motor[7].Temperature,HoTT_GRAD);
}
break;
case 7: if(NC_ErrorCode)
{
if(HoTTBlink && NC_ErrorCode < MAX_ERR_NUMBER)
{
Hott_ClearLine(7);
HoTT_printfxy_INV(0,7,"ERR: %2d !",NC_ErrorCode);
}
else
{
HoTT_printfxy(0,7,"ERR: "); _printf_P(&LIBFC_HoTT_Putchar, NC_ERROR_TEXT[NC_ErrorCode] , 0);};
}
else HoTT_printfxy(0,7," www.MikroKopter.de ");
break;
case 8: ASCIIPacket.WarnBeep = HoTT_Waring();
// ASCIIPacket.WarnBeep = Parameter_UserParam1;
case 9:
case 10:
case 11:
case 12:
case 13:
case 14:
case 15:
case 16:
if(HottKeyboard == HOTT_KEY_SET) { if(show_current) show_current = 0; else show_current = 1; Hott_ClearLine(5); Hott_ClearLine(6);}
else
if(HottKeyboard == HOTT_KEY_LEFT) { LIBFC_HoTT_Clear(); page = 2; line = 0;}
else
if(HottKeyboard == HOTT_KEY_RIGHT) { LIBFC_HoTT_Clear(); page = 0; line = 0;}
//if(HottKeyboard) HoTT_printfxy(15,6,"%KEY:%02x ",HottKeyboard);
HottKeyboard = 0;
break;
default: line = 0;
break;
}
else
if(page == 2)
switch(line++)
{
case 0:
HoTT_printfxy_INV(0,0,"Setting:%u %s ",GetActiveParamSet(),EE_Parameter.Name);
break;
case 1: HoTT_printfxy(0,1,"Min:%2i.%1iV %s ",BattLowVoltageWarning/10, BattLowVoltageWarning%10, Mixer.Name);
break;
case 2: HoTT_printfxy(0,2,"ALT:");
if(Parameter_GlobalConfig & CFG_HOEHENREGELUNG)
{
if(!(EE_Parameter.GlobalConfig & CFG_HOEHEN_SCHALTER)) HoTT_printf("POTI:%3u ", Parameter_HoehenSchalter)
else
{
if(Parameter_HoehenSchalter > 50) HoTT_printf("(ON) ") else HoTT_printf("(OFF) ");
if((Parameter_ExtraConfig & CFG2_HEIGHT_LIMIT)) HoTT_printf("LIMIT", Parameter_HoehenSchalter)
else HoTT_printf("VARIO", Parameter_HoehenSchalter);
}
}
else
HoTT_printf("DISABLED");
break;
case 3: HoTT_printfxy(0,3,"CF:");
if(!EE_Parameter.CareFreeModeControl) HoTT_printf("DISABLED")
else
{
if(CareFree) HoTT_printf(" (ON) ") else HoTT_printf(" (OFF)");
if(EE_Parameter.ExtraConfig & CFG_LEARNABLE_CAREFREE) HoTT_printf(" TEACH");
}
break;
case 4: HoTT_printfxy(0,4,"GPS:");
if(!(Parameter_GlobalConfig & CFG_GPS_AKTIV)) HoTT_printf("DISABLED")
else
{
CHK_POTI(tmp,EE_Parameter.NaviGpsModeControl);
if(tmp < 50) HoTT_printf("(FREE)")
else
if(tmp >= 180) HoTT_printf("(HOME)")
else
if(EE_Parameter.ExtraConfig & CFG_GPS_AID) HoTT_printf("(AID) ")
else HoTT_printf("(HOLD)")
}
if(EE_Parameter.FailSafeTime) HoTT_printfxy(10,4," FS:%usek ",EE_Parameter.FailSafeTime)
 
break;
case 5: HoTT_printfxy(0,5,"HOME ALT:");
if(EE_Parameter.ComingHomeAltitude) HoTT_printf("%um",EE_Parameter.ComingHomeAltitude) else HoTT_printf("HOLD ");
break;
case 6:
if(!show_poti)
{
HoTT_printfxy(0,6,"Ni:%4i Ro:%4i C:%3i",PPM_in[EE_Parameter.Kanalbelegung[K_NICK]],PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]], Parameter_ServoNickControl);
HoTT_printfxy(0,7,"Gs:%4i Ya:%4i ",PPM_in[EE_Parameter.Kanalbelegung[K_GAS]]+127,PPM_in[EE_Parameter.Kanalbelegung[K_GIER]]);
}
else
{
HoTT_printfxy(0,6,"P1:%4i P2:%4i 3:%3i",Poti1,Poti2, Poti3);
HoTT_printfxy(0,7,"P4:%4i P5:%4i 6:%3i",Poti4,Poti5, Poti6);
}
break;
case 7: //HoTT_printfxy(0,6,"WARNINGS:");
if(HoTTBlink)
{
LIBFC_HoTT_SetPos(6 * 21);
if(!(Parameter_GlobalConfig & CFG_ACHSENKOPPLUNG_AKTIV)) HoTT_printf_BLINK("COUPLING OFF! ");
if(EE_Parameter.BitConfig & (CFG_LOOP_LINKS | CFG_LOOP_RECHTS | CFG_LOOP_UNTEN | CFG_LOOP_OBEN)) HoTT_printf_BLINK("LOOPING! ");
if(Parameter_GlobalConfig & CFG_HEADING_HOLD) HoTT_printf_BLINK("HH! ");
if(!(Parameter_GlobalConfig & CFG_KOMPASS_AKTIV)) HoTT_printf_BLINK("COMPASS OFF! ");
}
break;
case 8: ASCIIPacket.WarnBeep = HoTT_Waring();
break;
case 9:
case 10:
case 11:
case 12:
case 13:
case 14:
case 15:
case 16:
if(HottKeyboard == HOTT_KEY_SET) { if(show_poti) show_poti = 0; else show_poti = 1; Hott_ClearLine(6); Hott_ClearLine(7);}
else
if(HottKeyboard == HOTT_KEY_RIGHT) { LIBFC_HoTT_Clear(); page = 1; line = 0;};
HottKeyboard = 0;
break;
default: line = 0;
break;
}
else page = 0;
}
 
#endif
 
 
/branches/V0.86d_MartinW_Jeti+V0.20/led.c
0,0 → 1,98
#include <inttypes.h>
#include "main.h"
 
uint16_t LED1_Timing = 0;
uint16_t LED2_Timing = 0;
unsigned char J16Blinkcount = 0, J16Mask = 1;
unsigned char J17Blinkcount = 0, J17Mask = 1;
 
// initializes the LED control outputs J16, J17
void LED_Init(void)
{
// set PC2 & PC3 as output (control of J16 & J17)
DDRC |= (1<<DDC2)|(1<<DDC3);
/// J16_OFF; /// MartinW: removed because of switching during calibration, not useful for activate fireworks
/// J17_OFF;
J16Blinkcount = 0; J16Mask = 128;
J17Blinkcount = 0; J17Mask = 128;
}
 
// called in UpdateMotors() every 2ms
void LED_Update(void)
{
static char delay = 0;
static unsigned char J16Bitmask = 0;
static unsigned char J17Bitmask = 0;
static unsigned char J16Warn = 0, J17Warn = 0;
if(!delay--) // 20ms Intervall
{
delay = 9;
if(FC_StatusFlags & (FC_STATUS_LOWBAT | FC_STATUS_EMERGENCY_LANDING) || (VersionInfo.HardwareError[1] & FC_ERROR1_I2C))
{
if(EE_Parameter.WARN_J16_Bitmask)
{
if(!J16Warn) J16Blinkcount = 4;
J16Warn = 1;
}
if(EE_Parameter.WARN_J17_Bitmask)
{
if(!J17Warn) J17Blinkcount = 4;
J17Warn = 1;
}
}
else
{
J16Warn = 0;
J17Warn = 0;
J16Bitmask = EE_Parameter.J16Bitmask;
J17Bitmask = EE_Parameter.J17Bitmask;
}
 
if(!J16Warn)
{
if((EE_Parameter.BitConfig & CFG_MOTOR_BLINK1) && !MotorenEin) {if(EE_Parameter.BitConfig & CFG_MOTOR_OFF_LED1) J16_ON; else J16_OFF;}
else
if((EE_Parameter.J16Timing > 247) && (Parameter_J16Timing > 220)) {if(J16Bitmask & 128) J16_ON; else J16_OFF;}
else
if((EE_Parameter.J16Timing > 247) && (Parameter_J16Timing == 5)) {if(J16Bitmask & 128) J16_OFF; else J16_ON;}
else
if(!J16Blinkcount--)
{
J16Blinkcount = Parameter_J16Timing / 2;
if(J16Mask == 1) J16Mask = 128; else J16Mask /= 2;
if(J16Mask & J16Bitmask) J16_ON; else J16_OFF;
}
}
else
if(!J16Blinkcount--)
{
J16Blinkcount = 10-1;
if(J16Mask == 1) J16Mask = 128; else J16Mask /= 2;
if(J16Mask & EE_Parameter.WARN_J16_Bitmask) J16_ON; else J16_OFF;
}
 
if(!J17Warn)
{
if((EE_Parameter.BitConfig & CFG_MOTOR_BLINK2) && !MotorenEin) {if(EE_Parameter.BitConfig & CFG_MOTOR_OFF_LED2) J17_ON; else J17_OFF;}
else
if((EE_Parameter.J17Timing > 247) && (Parameter_J17Timing > 220)) {if(J17Bitmask & 128) J17_ON; else J17_OFF;}
else
if((EE_Parameter.J17Timing > 247) && (Parameter_J17Timing == 5)) {if(J17Bitmask & 128) J17_OFF; else J17_ON;}
else
if(!J17Blinkcount--)
{
J17Blinkcount = Parameter_J17Timing / 2;
if(J17Mask == 1) J17Mask = 128; else J17Mask /= 2;
if(J17Mask & J17Bitmask) J17_ON; else J17_OFF;
}
}
else
if(!J17Blinkcount--)
{
J17Blinkcount = 10-1;
if(J17Mask == 1) J17Mask = 128; else J17Mask /= 2;
if(J17Mask & EE_Parameter.WARN_J17_Bitmask) J17_ON; else J17_OFF;
}
}
}
 
/branches/V0.86d_MartinW_Jeti+V0.20/main.c
0,0 → 1,478
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) Holger Buss, Ingo Busker
// + Nur für den privaten Gebrauch / NON-COMMERCIAL USE ONLY
// + www.MikroKopter.com
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Es gilt für das gesamte Projekt (Hardware, Software, Binärfiles, Sourcecode und Dokumentation),
// + dass eine Nutzung (auch auszugsweise) nur für den privaten und nicht-kommerziellen Gebrauch zulässig ist.
// + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt
// + bzgl. der Nutzungsbedingungen aufzunehmen.
// + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen,
// + Verkauf von Luftbildaufnahmen, usw.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht,
// + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts
// + auf anderen Webseiten oder Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de"
// + eindeutig als Ursprung verlinkt und genannt werden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion
// + Benutzung auf eigene Gefahr
// + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Portierung oder Nutzung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur
// + mit unserer Zustimmung zulässig
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Redistributions of source code (with or without modifications) must retain the above copyright notice,
// + this list of conditions and the following disclaimer.
// + * Neither the name of the copyright holders nor the names of contributors may be used to endorse or promote products derived
// + from this software without specific prior written permission.
// + * The use of this project (hardware, software, binary files, sources and documentation) is only permittet
// + for non-commercial use (directly or indirectly)
// + Commercial use (for excample: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted
// + with our written permission
// + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be
// + clearly linked as origin
// + * porting the sources to other systems or using the software on other systems (except hardware from www.mikrokopter.de) is not allowed
// + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
// + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// + POSSIBILITY OF SUCH DAMAGE.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
#include "main.h"
unsigned char DisableRcOffBeeping = 0;
unsigned char PlatinenVersion = 10;
unsigned char SendVersionToNavi = 1;
unsigned char BattLowVoltageWarning = 94;
unsigned int FlugMinuten = 0,FlugMinutenGesamt = 0;
unsigned int FlugSekunden = 0;
pVoidFnct_pVoidFnctChar_const_fmt _printf_P;
unsigned char FoundMotors = 0;
unsigned char JetiBeep = 0; // to allow any Morse-Beeping of the Jeti-Box
 
static char panodelay = 0; ///martinw
//static char panoleddelay = 0; ///martinw
 
void CalMk3Mag(void)
{
static unsigned char stick = 1;
if(PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] > -20) stick = 0;
if((PPM_in[EE_Parameter.Kanalbelegung[K_NICK]] < -70) && !stick)
{
stick = 1;
WinkelOut.CalcState++;
if(WinkelOut.CalcState > 4)
{
// WinkelOut.CalcState = 0; // in Uart.c
beeptime = 1000;
}
else Piep(WinkelOut.CalcState,150);
}
DebugOut.Analog[19] = WinkelOut.CalcState;
}
 
 
void LipoDetection(unsigned char print)
{
#define MAX_CELL_VOLTAGE 43 // max cell volatage for LiPO
unsigned int timer, cells;
if(print) printf("\n\rBatt:");
if(EE_Parameter.UnterspannungsWarnung < 50) // automatische Zellenerkennung
{
timer = SetDelay(500);
if(print) while (!CheckDelay(timer));
// up to 6s LiPo, less than 2s is technical impossible
for(cells = 2; cells < 7; cells++)
{
if(UBat < cells * MAX_CELL_VOLTAGE) break;
}
 
BattLowVoltageWarning = cells * EE_Parameter.UnterspannungsWarnung;
if(print)
{
Piep(cells, 200);
printf(" %d Cells ", cells);
}
}
else BattLowVoltageWarning = EE_Parameter.UnterspannungsWarnung;
//if(print) printf(" Low warning level: %d.%d",BattLowVoltageWarning/10,BattLowVoltageWarning%10);
if(print) printf("Low Batt level: %d.%d",BattLowVoltageWarning/10,BattLowVoltageWarning%10); /// Martinw; removed memorysaving
 
}
 
//############################################################################
//Hauptprogramm
int main (void)
//############################################################################
{
unsigned int timer,i,timer2 = 0, timerPolling;
 
DDRB = 0x00;
PORTB = 0x00;
for(timer = 0; timer < 1000; timer++); // verzögern
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
PlatinenVersion = 21;
#else
if(PINB & 0x01)
{
if(PINB & 0x02) PlatinenVersion = 13;
else PlatinenVersion = 11;
}
else
{
if(PINB & 0x02) PlatinenVersion = 20;
else PlatinenVersion = 10;
}
#endif
DDRC = 0x81; // SCL
DDRC |=0x40; // HEF4017 Reset
PORTC = 0xff; // Pullup SDA
DDRB = 0x1B; // LEDs und Druckoffset
PORTB = 0x01; // LED_Rot
DDRD = 0x3E; // Speaker & TXD & J3 J4 J5
PORTD = 0x47; // LED
HEF4017R_ON;
MCUSR &=~(1<<WDRF);
WDTCSR |= (1<<WDCE)|(1<<WDE);
WDTCSR = 0;
 
beeptime = 2500;
StickGier = 0; PPM_in[K_GAS] = 0; StickRoll = 0; StickNick = 0;
if(PlatinenVersion >= 20) GIER_GRAD_FAKTOR = 1220; else GIER_GRAD_FAKTOR = 1291; // unterschiedlich für ME und ENC
ROT_OFF;
 
Timer_Init();
TIMER2_Init();
UART_Init();
rc_sum_init();
ADC_Init();
I2C_Init(1);
SPI_MasterInit();
LIBFC_Init();
GRN_ON;
sei();
ParamSet_Init();
Capacity_Init(); //Moved by metro
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Check connected BL-Ctrls
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Check connected BL-Ctrls
BLFlags |= BLFLAG_READ_VERSION;
motor_read = 0; // read the first I2C-Data
SendMotorData();
timer = SetDelay(500);
while(!(BLFlags & BLFLAG_TX_COMPLETE) && !CheckDelay(timer)); //wait for complete transfer
 
printf("\n\rFound BL-Ctrl: ");
timer = SetDelay(4000);
for(i=0; i < MAX_MOTORS; i++)
{
SendMotorData();
while(!(BLFlags & BLFLAG_TX_COMPLETE) && !CheckDelay(timer)); //wait for complete transfer
if(Mixer.Motor[i][0] > 0) // wait max 4 sec for the BL-Ctrls to wake up
{
while(!CheckDelay(timer) && !(Motor[i].State & MOTOR_STATE_PRESENT_MASK) )
{
SendMotorData();
while(!(BLFlags & BLFLAG_TX_COMPLETE) && !CheckDelay(timer)); //wait for complete transfer
}
}
if(Motor[i].State & MOTOR_STATE_PRESENT_MASK)
{
printf("%d",i+1);
FoundMotors++;
// if(Motor[i].Version & MOTOR_STATE_NEW_PROTOCOL_MASK) printf("(new) ");
}
}
for(i=0; i < MAX_MOTORS; i++)
{
if(!(Motor[i].State & MOTOR_STATE_PRESENT_MASK) && Mixer.Motor[i][0] > 0)
{
//printf("\n\r\n\r!! MISSING BL-CTRL: %d !!",i+1);
printf("\n\r\n\r!!MISSING BL-CTRL: %d!!",i+1);/// Martinw; removed memorysaving
ServoActive = 2; // just in case the FC would be used as camera-stabilizer
}
Motor[i].State &= ~MOTOR_STATE_ERROR_MASK; // clear error counter
}
//printf("\n\r===================================");/// Martinw; removed memorysaving
printf("\n\r=");/// Martinw; removed memorysaving
 
 
if(RequiredMotors < FoundMotors) VersionInfo.HardwareError[1] |= FC_ERROR1_MIXER;
 
//if(EE_Parameter.GlobalConfig & CFG_HOEHENREGELUNG)
{
//printf("\n\rCalibrating pressure sensor..");
printf("\n\rCal. pressure sensor");/// Martinw; removed memorysaving
timer = SetDelay(1000);
SucheLuftruckOffset();
while (!CheckDelay(timer));
printf("OK\n\r");
}
 
SetNeutral(0);
 
ROT_OFF;
 
beeptime = 2000;
ExternControl.Digital[0] = 0x55;
 
 
FlugMinuten = (unsigned int)GetParamByte(PID_FLIGHT_MINUTES) * 256 + (unsigned int)GetParamByte(PID_FLIGHT_MINUTES + 1);
FlugMinutenGesamt = (unsigned int)GetParamByte(PID_FLIGHT_MINUTES_TOTAL) * 256 + (unsigned int)GetParamByte(PID_FLIGHT_MINUTES_TOTAL + 1);
 
if((FlugMinutenGesamt == 0xFFFF) || (FlugMinuten == 0xFFFF))
{
FlugMinuten = 0;
FlugMinutenGesamt = 0;
}
printf("\n\rFlight-time %u min Total:%u min", FlugMinuten, FlugMinutenGesamt);
 
printf("\n\rControl: ");
if (EE_Parameter.GlobalConfig & CFG_HEADING_HOLD) printf("HeadingHold");
else printf("Normal (ACC-Mode)");
#ifdef WITH_MKTOOL_Display // MartinW; for no MKT Display main.h
#warning : "### with MKTool Display ###"
LcdClear();
#endif
 
I2CTimeout = 5000;
WinkelOut.Orientation = 1;
LipoDetection(1);
 
LIBFC_ReceiverInit(EE_Parameter.Receiver);
 
//printf("\n\r===================================\n\r");
printf("\n\r=\n\r"); /// Martinw; removed memorysaving
//SpektrumBinding();
timer = SetDelay(2000);
timerPolling = SetDelay(250);
 
Debug(ANSI_CLEAR "FC-Start!\n\rFlugzeit: %d min", FlugMinutenGesamt); // Note: this won't waste flash memory, if #DEBUG is not active
DebugOut.Status[0] = 0x01 | 0x02;
JetiBeep = 0;
if(EE_Parameter.ExtraConfig & CFG_NO_RCOFF_BEEPING) DisableRcOffBeeping = 1;
 
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__)) ///MartinW; only for 1284er
//#warning : "### with Sponsored Message ###"
printf("\n\rJETI+ Version sponsored by Flyinghigh.ch, progammed by MartinW\n\r");
#else
#endif
 
 
while (1)
{
if(ReceiverUpdateModeActive) while (1) PORTC &= ~(1<<7); // Beeper off
//}
if(UpdateMotor && AdReady) // ReglerIntervall
{
//GRN_OFF;
UpdateMotor=0;
if(WinkelOut.CalcState) CalMk3Mag();
else MotorRegler();
SendMotorData();
ROT_OFF;
if(SenderOkay) { SenderOkay--; /*VersionInfo.HardwareError[1] &= ~FC_ERROR1_PPM;*/ }
else
{
TIMSK1 |= _BV(ICIE1); // enable PPM-Input
PPM_in[0] = 0; // set RSSI to zero on data timeout
VersionInfo.HardwareError[1] |= FC_ERROR1_PPM;
}
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//if(HoehenReglerAktiv && NaviDataOkay && SenderOkay < 160 && SenderOkay > 10 && FromNaviCtrl_Value.SerialDataOkay > 220) SenderOkay = 160;
//if(HoehenReglerAktiv && NaviDataOkay && SenderOkay < 101 && SenderOkay > 10 && FromNaviCtrl_Value.SerialDataOkay > 1) SenderOkay = 101;
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(!--I2CTimeout || MissingMotor)
{
if(!I2CTimeout)
{
I2C_Reset();
I2CTimeout = 5;
DebugOut.Analog[28]++; // I2C-Error
VersionInfo.HardwareError[1] |= FC_ERROR1_I2C;
DebugOut.Status[1] |= 0x02; // BL-Error-Status
}
if((BeepMuster == 0xffff) && MotorenEin)
{
beeptime = 25000;
BeepMuster = 0x0080;
}
}
else
{
ROT_OFF;
}
LIBFC_Polling();
 
if(!UpdateMotor)
{
if(CalculateServoSignals) CalculateServo();
DatenUebertragung();
BearbeiteRxDaten();
if(CheckDelay(timer))
{
static unsigned char second;
timer += 20; // 20 ms interval
#if ((defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__)) && defined(WITH_HOTTMENU))
#warning : "### with Hottmenu ###"
if(EE_Parameter.Receiver == RECEIVER_HOTT) HoTT_Menu();
#endif
if(MissingMotor)
{
VersionInfo.HardwareError[1] |= FC_ERROR1_BL_MISSING;
DebugOut.Status[1] |= 0x02; // BL-Error-Status
}
else
{
if(!beeptime)
{
if(I2CTimeout > 6) DebugOut.Status[1] &= ~0x02; // BL-Error-Status
}
}
if(SenderOkay && DisableRcOffBeeping) { DisableRcOffBeeping = 0; beeptime = 5000;};
if(PcZugriff) PcZugriff--;
else
{
ExternControl.Config = 0;
ExternStickNick = 0;
ExternStickRoll = 0;
ExternStickGier = 0;
if(!SenderOkay)
{
if(BeepMuster == 0xffff && DisableRcOffBeeping != 2)
{
beeptime = 15000;
BeepMuster = 0x0c00;
if(DisableRcOffBeeping) DisableRcOffBeeping = 2;
}
}
}
if(NaviDataOkay > 200)
{
NaviDataOkay--;
VersionInfo.HardwareError[1] &= ~FC_ERROR1_SPI_RX;
}
else
{
if(NC_Version.Compatible)
{
VersionInfo.HardwareError[1] |= FC_ERROR1_SPI_RX;
NC_ErrorCode = 9; // "ERR: no NC communication"
if(BeepMuster == 0xffff && MotorenEin)
{
beeptime = 15000;
BeepMuster = 0xA800;
}
}
GPS_Nick = 0;
GPS_Roll = 0;
GPS_Aid_StickMultiplikator = 0;
GPSInfo.Flags = 0;
FromNaviCtrl.AccErrorN = 0;
FromNaviCtrl.AccErrorR = 0;
FromNaviCtrl.CompassValue = -1;
NaviDataOkay = 0;
}
if(UBat < BattLowVoltageWarning)
{
FC_StatusFlags |= FC_STATUS_LOWBAT;
if(BeepMuster == 0xffff)
{
beeptime = 6000;
BeepMuster = 0x0300;
}
}
else if(!beeptime) FC_StatusFlags &= ~FC_STATUS_LOWBAT;
 
SPI_StartTransmitPacket();
SendSPI = 4;
if(!(FC_StatusFlags & FC_STATUS_FLY)) timer2 = 1450; // 0,5 Minuten aufrunden
else
if(++second == 49)
{
second = 0;
FlugSekunden++;
}
if(++timer2 == 2930) // eine Minute
{
timer2 = 0;
FlugMinuten++;
FlugMinutenGesamt++;
SetParamByte(PID_FLIGHT_MINUTES,FlugMinuten / 256);
SetParamByte(PID_FLIGHT_MINUTES+1,FlugMinuten % 256);
SetParamByte(PID_FLIGHT_MINUTES_TOTAL,FlugMinutenGesamt / 256);
SetParamByte(PID_FLIGHT_MINUTES_TOTAL+1,FlugMinutenGesamt % 256);
timer = SetDelay(20); // falls "timer += 20;" mal nicht geht
}
}
#ifdef WITH_PANOTRIGGER /// MartinW main.h means no memsave
#warning : "### with Panorama Trigger Function ###"
//// Pano Trigger
if(Parameter_UserParam8 >= 200) //enable/disable Pano Trigger Function
{
if(Parameter_UserParam4 <=9) { Parameter_UserParam4 = 10; }
degreedivold = degreediv;
degreediv = (ErsatzKompass / GIER_GRAD_FAKTOR) / Parameter_UserParam4;//Division
if((degreediv-degreedivold)==2||(degreediv-degreedivold)==1||(degreediv-degreedivold)== -2||(degreediv-degreedivold)== -1)
{
if(panodelay == 0)
{
panotrigger= 1; // muss wieder geleert werden
ROT_ON;
J16_ON;
panodelay = Parameter_UserParam5;
}
}
else
{
if(panodelay <= Parameter_UserParam6) //ms Intervall
{
//panoleddelay = Parameter_UserParam6;
J16_OFF;
ROT_OFF;
}
if(panodelay > 0)
{
panodelay--;
}
}
}// END if(Parameter_UserParam4 >= 1)
//// Pano Trigger
 
#else
#warning : "### without Panorama Trigger Function ###"
 
#endif
LED_Update();
Capacity_Update();
} //else DebugOut.Analog[26]++;
}
if(!SendSPI) { SPI_TransmitByte(); }
}
return (1);
}
 
 
/branches/V0.86d_MartinW_Jeti+V0.20/makefile
0,0 → 1,482
#--------------------------------------------------------------------
# MCU name
#MCU = atmega1284p
MCU = atmega644p
F_CPU = 20000000
#-------------------------------------------------------------------
VERSION_MAJOR = 0
VERSION_MINOR = 86
VERSION_PATCH = 3
VERSION_SERIAL_MAJOR = 11 # Serial Protocol
VERSION_SERIAL_MINOR = 0 # Serial Protocol
NC_SPI_COMPATIBLE = 27 # Navi-Kompatibilität
MOD = JETI+V0.20
#-------------------------------------------------------------------
 
# get SVN revision
REV := $(shell sh -c "cat .svn/entries | sed -n '4p'")
 
ifeq ($(MCU), atmega1284p)
FUSE_SETTINGS = -u -U lfuse:w:0xff:m -U hfuse:w:0xdf:m
HEX_NAME = MEGA1284P
LIBFC_EXT = 1284
endif
 
ifeq ($(MCU), atmega644p)
FUSE_SETTINGS = -u -U lfuse:w:0xff:m -U hfuse:w:0xdf:m
HEX_NAME = MEGA644
LIBFC_EXT = 644
endif
 
ifeq ($(F_CPU), 16000000)
QUARZ = 16MHZ
endif
 
ifeq ($(F_CPU), 20000000)
QUARZ = 20MHZ
endif
 
 
# Output format. (can be srec, ihex, binary)
FORMAT = ihex
 
# Target file name (without extension).
 
ifeq ($(VERSION_PATCH), 0)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)a_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 1)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)b_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 2)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)c_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 3)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)d_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 4)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)e_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 5)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)f_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 6)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)g_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 7)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)h_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 8)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)i_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 9)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)j_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 10)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)k_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 11)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)L_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 12)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)m_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 13)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)n_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 14)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)o_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 15)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)p_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 16)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)q_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 17)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)r_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 18)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)s_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 19)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)t_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 20)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)u_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 21)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)v_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 22)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)w_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 23)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)x_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 24)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)y_SVN$(REV)_$(MOD)
endif
ifeq ($(VERSION_PATCH), 25)
TARGET = Flight-Ctrl_$(HEX_NAME)_V$(VERSION_MAJOR)_$(VERSION_MINOR)z_SVN$(REV)_$(MOD)
endif
 
 
# Optimization level, can be [0, 1, 2, 3, s]. 0 turns off optimization.
# (Note: 3 is not always the best optimization level. See avr-libc FAQ.)
OPT = s
#OPT = 2
 
##########################################################################################################
# List C source files here. (C dependencies are automatically generated.)
SRC = main.c uart.c timer0.c analog.c menu.c eeprom.c
SRC += twimaster.c rc.c fc.c GPS.c spi.c led.c Spektrum.c
SRC += mymath.c jetimenu.c capacity.c debug.c
SRC += hottmenu.c
 
##########################################################################################################
 
 
# List Assembler source files here.
# Make them always end in a capital .S. Files ending in a lowercase .s
# will not be considered source files but generated files (assembler
# output from the compiler), and will be deleted upon "make clean"!
# Even though the DOS/Win* filesystem matches both .s and .S the same,
# it will preserve the spelling of the filenames, and gcc itself does
# care about how the name is spelled on its command-line.
ASRC = isqrt.S
 
 
 
# List any extra directories to look for include files here.
# Each directory must be seperated by a space.
EXTRAINCDIRS =
 
 
# Optional compiler flags.
# -g: generate debugging information (for GDB, or for COFF conversion)
# -O*: optimization level
# -f...: tuning, see gcc manual and avr-libc documentation
# -Wall...: warning level
# -Wa,...: tell GCC to pass this to the assembler.
# -ahlms: create assembler listing
CFLAGS = -O$(OPT) -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums -Wall -Wstrict-prototypes -Wa,-adhlns=$(<:%.c=%.lst) $(patsubst %,-I%,$(EXTRAINCDIRS))
 
 
# Set a "language standard" compiler flag.
# Unremark just one line below to set the language standard to use.
# gnu99 = C99 + GNU extensions. See GCC manual for more information.
#CFLAGS += -std=c89
#CFLAGS += -std=gnu89
#CFLAGS += -std=c99
CFLAGS += -std=gnu99
 
# shrink code size
CFLAGS += -mtiny-stack
#CFLAGS += -fno-inline-functions
CFLAGS += -mcall-prologues
 
CFLAGS += -DF_CPU=$(F_CPU) -DVERSION_MAJOR=$(VERSION_MAJOR) -DVERSION_MINOR=$(VERSION_MINOR) -DVERSION_PATCH=$(VERSION_PATCH) -DVERSION_SERIAL_MAJOR=$(VERSION_SERIAL_MAJOR) -DVERSION_SERIAL_MINOR=$(VERSION_SERIAL_MINOR) -DNC_SPI_COMPATIBLE=$(NC_SPI_COMPATIBLE)
 
 
# Optional assembler flags.
# -Wa,...: tell GCC to pass this to the assembler.
# -ahlms: create listing
# -gstabs: have the assembler create line number information; note that
# for use in COFF files, additional information about filenames
# and function names needs to be present in the assembler source
# files -- see avr-libc docs [FIXME: not yet described there]
ASFLAGS = -Wa,-adhlns=$(<:.S=.lst),-gstabs
 
 
 
# Optional linker flags.
# -Wl,...: tell GCC to pass this to linker.
# -Map: create map file
# --cref: add cross reference to map file
LDFLAGS = -Wl,-Map=$(TARGET).map,--cref
 
# Additional libraries
 
# Minimalistic printf version
#LDFLAGS += -Wl,-u,vfprintf -lprintf_min
 
# Floating point printf version (requires -lm below)
#LDFLAGS += -Wl,-u,vfprintf -lprintf_flt
 
# -lm = math library
LDFLAGS += -lm
 
LDFLAGS += libfc$(LIBFC_EXT).a
 
##LDFLAGS += -T./linkerfile/avr5.x
 
 
 
# Programming support using avrdude. Settings and variables.
 
# Programming hardware: alf avr910 avrisp bascom bsd
# dt006 pavr picoweb pony-stk200 sp12 stk200 stk500
#
# Type: avrdude -c ?
# to get a full listing.
#
#AVRDUDE_PROGRAMMER = dt006
#AVRDUDE_PROGRAMMER = stk200
#AVRDUDE_PROGRAMMER = ponyser
AVRDUDE_PROGRAMMER = avrispv2
#falls Ponyser ausgewählt wird, muss sich unsere avrdude-Configdatei im Bin-Verzeichnis des Compilers befinden
 
#AVRDUDE_PORT = com1 # programmer connected to serial device
#AVRDUDE_PORT = lpt1 # programmer connected to parallel port
AVRDUDE_PORT = usb # programmer connected to USB
 
#AVRDUDE_WRITE_FLASH = -U flash:w:$(TARGET).hex
AVRDUDE_WRITE_FLASH = -U flash:w:$(TARGET).hex $(FUSE_SETTINGS)
#AVRDUDE_WRITE_EEPROM = -U eeprom:w:$(TARGET).eep
 
#avrdude -c avrispv2 -P usb -p m32 -U flash:w:blink.hex
AVRDUDE_FLAGS = -p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER)
 
# Uncomment the following if you want avrdude's erase cycle counter.
# Note that this counter needs to be initialized first using -Yn,
# see avrdude manual.
#AVRDUDE_ERASE += -y
 
# Uncomment the following if you do /not/ wish a verification to be
# performed after programming the device.
AVRDUDE_FLAGS += -V
 
# Increase verbosity level. Please use this when submitting bug
# reports about avrdude. See <http://savannah.nongnu.org/projects/avrdude>
# to submit bug reports.
#AVRDUDE_FLAGS += -v -v
 
# ---------------------------------------------------------------------------
# Define directories, if needed.
DIRAVR = c:/winavr
DIRAVRBIN = $(DIRAVR)/bin
DIRAVRUTILS = $(DIRAVR)/utils/bin
DIRINC = .
DIRLIB = $(DIRAVR)/avr/lib
 
 
# Define programs and commands.
SHELL = sh
 
CC = avr-gcc
 
OBJCOPY = avr-objcopy
OBJDUMP = avr-objdump
SIZE = avr-size
 
# Programming support using avrdude.
AVRDUDE = avrdude
 
REMOVE = rm -f
COPY = cp
 
HEXSIZE = $(SIZE) --target=$(FORMAT) $(TARGET).hex
ELFSIZE = $(SIZE) -x -A $(TARGET).elf
LIMITS = $(SIZE) --mcu=$(MCU) -C $(TARGET).elf
 
 
# Define Messages
# English
MSG_ERRORS_NONE = Errors: none
MSG_BEGIN = -------- begin --------
MSG_END = -------- end --------
MSG_SIZE_BEFORE = Size before:
MSG_SIZE_AFTER = Size after:
MSG_COFF = Converting to AVR COFF:
MSG_EXTENDED_COFF = Converting to AVR Extended COFF:
MSG_FLASH = Creating load file for Flash:
MSG_EEPROM = Creating load file for EEPROM:
MSG_EXTENDED_LISTING = Creating Extended Listing:
MSG_SYMBOL_TABLE = Creating Symbol Table:
MSG_LINKING = Linking:
MSG_COMPILING = Compiling:
MSG_ASSEMBLING = Assembling:
MSG_CLEANING = Cleaning project:
 
 
# Define all object files.
OBJ = $(SRC:.c=.o) $(ASRC:.S=.o)
 
# Define all listing files.
LST = $(ASRC:.S=.lst) $(SRC:.c=.lst)
 
# Combine all necessary flags and optional flags.
# Add target processor to flags.
#ALL_CFLAGS = -mmcu=$(MCU) -DF_CPU=$(F_CPU) -I. $(CFLAGS)
ALL_CFLAGS = -mmcu=$(MCU) -I. $(CFLAGS)
ALL_ASFLAGS = -mmcu=$(MCU) -I. -x assembler-with-cpp $(ASFLAGS)
 
 
# Default target.
all: begin gccversion sizebefore $(TARGET).elf $(TARGET).hex sizeafter finished end
 
 
# Eye candy.
# AVR Studio 3.x does not check make's exit code but relies on
# the following magic strings to be generated by the compile job.
begin:
@echo
@echo $(MSG_BEGIN)
 
finished:
@echo $(MSG_ERRORS_NONE)
 
end:
@echo MaxSize Flashsize is 63488 bytes on Atmega644
@echo $(MSG_END)
@echo
 
 
# Display size of file.
sizebefore:
@if [ -f $(TARGET).elf ]; then echo Size before:; $(ELFSIZE); $(HEXSIZE); $(LIMITS); echo; fi
sizeafter:
@if [ -f $(TARGET).elf ]; then echo Size after:; $(ELFSIZE); $(HEXSIZE); $(LIMITS); echo; fi
 
 
# Display compiler version information.
gccversion :
@$(CC) --version
 
 
# Convert ELF to COFF for use in debugging / simulating in
# AVR Studio or VMLAB.
COFFCONVERT=$(OBJCOPY) --debugging \
--change-section-address .data-0x800000 \
--change-section-address .bss-0x800000 \
--change-section-address .noinit-0x800000 \
--change-section-address .eeprom-0x810000
 
 
coff: $(TARGET).elf
@echo
@echo $(MSG_COFF) $(TARGET).cof
$(COFFCONVERT) -O coff-avr $< $(TARGET).cof
 
 
extcoff: $(TARGET).elf
@echo
@echo $(MSG_EXTENDED_COFF) $(TARGET).cof
$(COFFCONVERT) -O coff-ext-avr $< $(TARGET).cof
 
 
 
 
# Program the device.
program: $(TARGET).hex $(TARGET).eep
$(AVRDUDE) $(AVRDUDE_FLAGS) $(AVRDUDE_WRITE_FLASH) $(AVRDUDE_WRITE_EEPROM)
 
 
 
 
# Create final output files (.hex, .eep) from ELF output file.
%.hex: %.elf
@echo
@echo $(MSG_FLASH) $@
$(OBJCOPY) -O $(FORMAT) -R .eeprom $< $@
 
%.eep: %.elf
@echo
@echo $(MSG_EEPROM) $@
-$(OBJCOPY) -j .eeprom --set-section-flags=.eeprom="alloc,load" \
--change-section-lma .eeprom=0 -O $(FORMAT) $< $@
 
# Create extended listing file from ELF output file.
%.lss: %.elf
@echo
@echo $(MSG_EXTENDED_LISTING) $@
$(OBJDUMP) -h -S $< > $@
 
# Create a symbol table from ELF output file.
%.sym: %.elf
@echo
@echo $(MSG_SYMBOL_TABLE) $@
avr-nm -n $< > $@
 
 
 
# Link: create ELF output file from object files.
.SECONDARY : $(TARGET).elf
.PRECIOUS : $(OBJ)
%.elf: $(OBJ)
@echo
@echo $(MSG_LINKING) $@
$(CC) $(ALL_CFLAGS) $(OBJ) --output $@ $(LDFLAGS)
 
 
# Compile: create object files from C source files.
%.o : %.c
@echo
@echo $(MSG_COMPILING) $<
$(CC) -c $(ALL_CFLAGS) $< -o $@
 
 
# Compile: create assembler files from C source files.
%.s : %.c
$(CC) -S $(ALL_CFLAGS) $< -o $@
 
 
# Assemble: create object files from assembler source files.
%.o : %.S
@echo
@echo $(MSG_ASSEMBLING) $<
$(CC) -c $(ALL_ASFLAGS) $< -o $@
 
 
 
 
 
 
# Target: clean project.
clean: begin clean_list finished end
 
clean_list :
@echo
@echo $(MSG_CLEANING)
$(REMOVE) Flight-Ctrl_*.hex
$(REMOVE) Flight-Ctrl_*.eep
$(REMOVE) $(TARGET).obj
$(REMOVE) $(TARGET).cof
$(REMOVE) Flight-Ctrl_*.elf
$(REMOVE) Flight-Ctrl_*.map
$(REMOVE) $(TARGET).obj
$(REMOVE) $(TARGET).a90
$(REMOVE) Flight-Ctrl_*.sym
$(REMOVE) $(TARGET).lnk
$(REMOVE) $(TARGET).lss
$(REMOVE) $(OBJ)
$(REMOVE) $(LST)
$(REMOVE) $(SRC:.c=.s)
$(REMOVE) $(SRC:.c=.d)
$(REMOVE) $(SRC:.c=.o)
 
 
# Automatically generate C source code dependencies.
# (Code originally taken from the GNU make user manual and modified
# (See README.txt Credits).)
#
# Note that this will work with sh (bash) and sed that is shipped with WinAVR
# (see the SHELL variable defined above).
# This may not work with other shells or other seds.
#
%.d: %.c
set -e; $(CC) -MM $(ALL_CFLAGS) $< \
| sed 's,\(.*\)\.o[ :]*,\1.o \1.d : ,g' > $@; \
[ -s $@ ] || rm -f $@
 
 
# Remove the '-' if you want to see the dependency files generated.
-include $(SRC:%.c=%.d)
 
 
 
# Listing of phony targets.
.PHONY : all begin finish end sizebefore sizeafter gccversion coff extcoff \
clean clean_list program
 
/branches/V0.86d_MartinW_Jeti+V0.20/menu.c
0,0 → 1,223
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) Holger Buss, Ingo Busker
// + only for non-profit use
// + www.MikroKopter.com
// + porting the sources to other systems or using the software on other systems (except hardware from www.mikrokopter.de) is not allowed
// + see the File "License.txt" for further Informations
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
#include "main.h"
#include "eeprom.h"
 
#ifdef WITH_MKTOOL_Display // only include functions if DEBUG is defined in main.h
 
#warning : "### with MKTool Display ###"
 
char DisplayBuff[80];
unsigned char DispPtr = 0;
 
unsigned char MaxMenue = 16;
unsigned char MenuePunkt = 0;
unsigned char RemoteKeys = 0;
 
#define KEY1 0x01
#define KEY2 0x02
#define KEY3 0x04
#define KEY4 0x08
#define KEY5 0x10
 
void LcdClear(void)
{
unsigned char i;
for(i=0;i<80;i++) DisplayBuff[i] = ' ';
}
 
void Menu_Putchar(char c)
{
if(DispPtr < 80) DisplayBuff[DispPtr++] = c;
}
 
void Menu(void)
{
unsigned char i;
if(RemoteKeys & KEY1) { if(MenuePunkt) MenuePunkt--; else MenuePunkt = MaxMenue;}
if(RemoteKeys & KEY2) { if(MenuePunkt == MaxMenue) MenuePunkt = 0; else MenuePunkt++;}
if((RemoteKeys & KEY1) && (RemoteKeys & KEY2)) MenuePunkt = 0;
LcdClear();
if(MenuePunkt < 10) {LCD_printfxy(17,0,"[%i]",MenuePunkt);}
else {LCD_printfxy(16,0,"[%i]",MenuePunkt);};
 
switch(MenuePunkt)
{
case 0:
LCD_printfxy(0,0,"--Jeti+ 0.20---");
LCD_printfxy(0,1,"HW:V%d.%d SW:%d.%d%c",PlatinenVersion/10,PlatinenVersion%10, VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH +'a');
LCD_printfxy(0,2,"Setting:%d %s", GetActiveParamSet(),Mixer.Name);
 
if(VersionInfo.HardwareError[1] & FC_ERROR1_MIXER) LCD_printfxy(0,3,"Mixer Error!")
else
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
if(NC_ErrorCode)
{
LCD_printfxy(0,3,"ERR%2d:",NC_ErrorCode);
_printf_P(&Menu_Putchar, NC_ERROR_TEXT[NC_ErrorCode] , 0);
}
else
#endif
if(VersionInfo.HardwareError[0]) LCD_printfxy(0,3,"Hardware Error 1:%d !!",VersionInfo.HardwareError[0])
else
if(MissingMotor) LCD_printfxy(0,3,"Missing BL-Ctrl:%d!!",MissingMotor)
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
#else
else
if(NC_ErrorCode)
{
LCD_printfxy(0,3,"! NC-ERR: %2d ! ",NC_ErrorCode);
}
#endif
// if(VersionInfo.HardwareError[1]) LCD_printfxy(0,3,"Error 2:%d !!",VersionInfo.HardwareError[1])
else
if(I2CTimeout < 6) LCD_printfxy(0,3,"I2C ERROR!!!")
break;
case 1:
if(Parameter_GlobalConfig & CFG_HOEHENREGELUNG)
{
LCD_printfxy(0,0,"Height: %5i",(int)(HoehenWert/5));
LCD_printfxy(0,1,"Setpoint:%5i",(int)(SollHoehe/5));
LCD_printfxy(0,2,"Pressure:%5i",MessLuftdruck);
LCD_printfxy(0,3,"Offset: %5i",OCR0A);
}
else
{
LCD_printfxy(0,0,"Height control");
LCD_printfxy(0,1,"DISABLED");
//LCD_printfxy(0,2,"Height control");
//LCD_printfxy(0,3,"DISABLED");
}
 
break;
case 2:
LCD_printfxy(0,0,"act. bearing");
LCD_printfxy(0,1,"Nick: %5i",IntegralNick/1024);
LCD_printfxy(0,2,"Roll: %5i",IntegralRoll/1024);
LCD_printfxy(0,3,"Compass: %5i",ErsatzKompassInGrad);
break;
case 3:
for(i=1;i<9;i+=2) LCD_printfxy(0,i/2,"K%i:%4i K%i:%4i ",i,PPM_in[i],i+1,PPM_in[i+1]);
break;
case 4:
LCD_printfxy(0,0,"Ni:%4i Ro:%4i ",PPM_in[EE_Parameter.Kanalbelegung[K_NICK]],PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]]);
LCD_printfxy(0,1,"Gs:%4i Gi:%4i ",PPM_in[EE_Parameter.Kanalbelegung[K_GAS]]+127,PPM_in[EE_Parameter.Kanalbelegung[K_GIER]]);
LCD_printfxy(0,2,"P1:%4i P2:%4i ",PPM_in[EE_Parameter.Kanalbelegung[K_POTI1]]+127,PPM_in[EE_Parameter.Kanalbelegung[K_POTI2]]+127);
LCD_printfxy(0,3,"P3:%4i P4:%4i ",PPM_in[EE_Parameter.Kanalbelegung[K_POTI3]]+127,PPM_in[EE_Parameter.Kanalbelegung[K_POTI4]]+127);
break;
case 5:
LCD_printfxy(0,0,"Gyro - Sensor");
if(PlatinenVersion == 10)
{
LCD_printfxy(0,1,"Nick%4i (%3i.%i)",AdWertNick - AdNeutralNick/8, AdNeutralNick/8, AdNeutralNick%8);
LCD_printfxy(0,2,"Roll%4i (%3i.%i)",AdWertRoll - AdNeutralRoll/8, AdNeutralRoll/8, AdNeutralRoll%8);
LCD_printfxy(0,3,"Gier%4i (%3i)",AdNeutralGier - AdWertGier, AdNeutralGier);
}
else
if((PlatinenVersion == 11) || (PlatinenVersion >= 20))
{
LCD_printfxy(0,1,"Nick %4i (%3i.%x)",AdWertNick - AdNeutralNick/8, AdNeutralNick/16, (AdNeutralNick%16)/2);
LCD_printfxy(0,2,"Roll %4i (%3i.%x)",AdWertRoll - AdNeutralRoll/8, AdNeutralRoll/16, (AdNeutralRoll%16)/2);
LCD_printfxy(0,3,"Yaw %4i (%3i)",AdNeutralGier - AdWertGier, AdNeutralGier/2);
}
else
if(PlatinenVersion == 13)
{
LCD_printfxy(0,1,"Nick %4i (%3i)(%3i)",AdWertNick - AdNeutralNick/8, AdNeutralNick/16,AnalogOffsetNick);
LCD_printfxy(0,2,"Roll %4i (%3i)(%3i)",AdWertRoll - AdNeutralRoll/8, AdNeutralRoll/16,AnalogOffsetRoll);
LCD_printfxy(0,3,"Yaw %4i (%3i)(%3i)",AdNeutralGier - AdWertGier, AdNeutralGier/2,AnalogOffsetGier);
}
break;
case 6:
LCD_printfxy(0,0,"ACC - Sensor");
LCD_printfxy(0,1,"Nick %4i (%3i)",AdWertAccNick,NeutralAccX);
LCD_printfxy(0,2,"Roll %4i (%3i)",AdWertAccRoll,NeutralAccY);
LCD_printfxy(0,3,"Z %4i (%3i)",AdWertAccHoch,(int)NeutralAccZ);
break;
case 7:
LCD_printfxy(0,0,"Voltage: %3i.%1iV",UBat/10, UBat%10);
LCD_printfxy(0,1,"Current: %3i.%1iA",Capacity.ActualCurrent/10, Capacity.ActualCurrent%10);
LCD_printfxy(0,2,"Power: %4iW",Capacity.ActualPower);
LCD_printfxy(0,3,"Discharge: %5imAh", Capacity.UsedCapacity);
break;
case 8:
LCD_printfxy(0,0,"Receiver");
LCD_printfxy(0,1,"RC-RSSI: %4i", PPM_in[0]);
LCD_printfxy(0,2,"RC-Quality: %4i", SenderOkay);
LCD_printfxy(0,3,"RC-Channels:%4i", Channels-1);
break;
case 9:
LCD_printfxy(0,0,"Compass");
LCD_printfxy(0,1,"Magnet: %5i",KompassValue);
LCD_printfxy(0,2,"Gyro: %5i",ErsatzKompassInGrad);
LCD_printfxy(0,3,"Setpoint: %5i",KompassSollWert);
break;
case 10:
for(i=0;i<4;i++) LCD_printfxy(0,i,"Poti%i: %3i",i+1,Poti[i]);
break;
case 11:
for(i=0;i<4;i++) LCD_printfxy(0,i,"Poti%i: %3i",i+5,Poti[i+4]);
break;
case 12:
LCD_printfxy(0,0,"Servo " );
LCD_printfxy(0,1,"Setpoint %3i",Parameter_ServoNickControl);
LCD_printfxy(0,2,"Position: %3i",ServoNickValue/4);
LCD_printfxy(0,3,"Range:%3i-%3i",EE_Parameter.ServoNickMin,EE_Parameter.ServoNickMax);
break;
/* case 13:
LCD_printfxy(0,0,"ExternControl " );
LCD_printfxy(0,1,"Ni:%4i Ro:%4i ",ExternControl.Nick,ExternControl.Roll);
LCD_printfxy(0,2,"Gs:%4i Gi:%4i ",ExternControl.Gas,ExternControl.Gier);
LCD_printfxy(0,3,"Hi:%4i Cf:%4i ",ExternControl.Hight,ExternControl.Config);
break;
*/
case 13:
LCD_printfxy(0,0,"BL-Ctrl Errors " );
for(i=0;i<3;i++)
{
LCD_printfxy(0,i+1,"%3d %3d %3d %3d ",Motor[i*4].State & MOTOR_STATE_ERROR_MASK,Motor[i*4+1].State & MOTOR_STATE_ERROR_MASK,Motor[i*4+2].State & MOTOR_STATE_ERROR_MASK,Motor[i*4+3].State & MOTOR_STATE_ERROR_MASK);
// if(i*4 >= RequiredMotors) break;
}
break;
case 14:
LCD_printfxy(0,0,"BL Temperature" );
for(i=0;i<3;i++)
{
LCD_printfxy(0,i+1,"%3d %3d %3d %3d ",Motor[i*4].Temperature,Motor[i*4+1].Temperature,Motor[i*4+2].Temperature,Motor[i*4+3].Temperature);
// if(4 + i * 4 >= RequiredMotors) break;
}
break;
case 15:
LCD_printfxy(0,0,"BL-Ctrl found " );
LCD_printfxy(0,1," %c %c %c %c ",'-' + 4 * (Motor[0].State>>7),'-' + 5 * (Motor[1].State>>7),'-' + 6 * (Motor[2].State>>7),'-' + 7 * (Motor[3].State>>7));
LCD_printfxy(0,2," %c %c %c %c ",'-' + 8 * (Motor[4].State>>7),'-' + 9 * (Motor[5].State>>7),'-' + 10 * (Motor[6].State>>7),'-' + 11 * (Motor[7].State>>7));
LCD_printfxy(0,3," %c - - - ",'-' + 12 * (Motor[8].State>>7));
if(Motor[9].State>>7) LCD_printfxy(4,3,"10");
if(Motor[10].State>>7) LCD_printfxy(8,3,"11");
if(Motor[11].State>>7) LCD_printfxy(12,3,"12");
break;
case 16:
LCD_printfxy(0,0,"Flight-Time " );
LCD_printfxy(0,1,"Total:%5umin",FlugMinutenGesamt);
LCD_printfxy(0,2,"Act: %5umin",FlugMinuten);
LCD_printfxy(13,3,"(reset)");
if(RemoteKeys & KEY4)
{
FlugMinuten = 0;
SetParamWord(PID_FLIGHT_MINUTES, FlugMinuten);
}
break;
default:
if(MenuePunkt == MaxMenue) MaxMenue--;
MenuePunkt = 0;
break;
}
RemoteKeys = 0;
}
#endif
/branches/V0.86d_MartinW_Jeti+V0.20/mymath.c
0,0 → 1,41
#include <stdlib.h>
#include <avr/pgmspace.h>
#include "mymath.h"
 
// discrete mathematics
 
// Sinus with argument in degree at an angular resolution of 1 degree and a discretisation of 13 bit.
const uint16_t pgm_sinlookup[91] PROGMEM = {0, 143, 286, 429, 571, 714, 856, 998, 1140, 1282, 1423, 1563, 1703, 1843, 1982, 2120, 2258, 2395, 2531, 2667, 2802, 2936, 3069, 3201, 3332, 3462, 3591, 3719, 3846, 3972, 4096, 4219, 4341, 4462, 4581, 4699, 4815, 4930, 5043, 5155, 5266, 5374, 5482, 5587, 5691, 5793, 5893, 5991, 6088, 6183, 6275, 6366, 6455, 6542, 6627, 6710, 6791, 6870, 6947, 7022, 7094, 7165, 7233, 7299, 7363, 7424, 7484, 7541, 7595, 7648, 7698, 7746, 7791, 7834, 7875, 7913, 7949, 7982, 8013, 8041, 8068, 8091, 8112, 8131, 8147, 8161, 8172, 8181, 8187, 8191, 8192};
 
int16_t c_sin_8192(int16_t angle)
{
int8_t m,n;
int16_t sinus;
 
// avoid negative angles
if (angle < 0)
{
m = -1;
angle = abs(angle);
}
else m = +1;
 
// fold angle to intervall 0 to 359
angle %= 360;
 
// check quadrant
if (angle <= 90) n=1; // first quadrant
else if ((angle > 90) && (angle <= 180)) {angle = 180 - angle; n = 1;} // second quadrant
else if ((angle > 180) && (angle <= 270)) {angle = angle - 180; n = -1;} // third quadrant
else {angle = 360 - angle; n = -1;} //fourth quadrant
// get lookup value
sinus = pgm_read_word(&pgm_sinlookup[angle]);
// calculate sinus value
return (sinus * m * n);
}
 
// Cosinus with argument in degree at an angular resolution of 1 degree and a discretisation of 13 bit.
int16_t c_cos_8192(int16_t angle)
{
return (c_sin_8192(90 - angle));
}
/branches/V0.86d_MartinW_Jeti+V0.20/rc.c
0,0 → 1,218
/*#######################################################################################
Decodieren eines RC Summen Signals
#######################################################################################*/
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) Holger Buss, Ingo Busker
// + only for non-profit use
// + www.MikroKopter.com
// + porting the sources to other systems or using the software on other systems (except hardware from www.mikrokopter.de) is not allowed
// + see the File "License.txt" for further Informations
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
#include "rc.h"
#include "main.h"
// Achtung: ACT_S3D_SUMMENSIGNAL wird in der Main.h gesetzt
 
volatile int PPM_in[26];
volatile int PPM_diff[26]; // das diffenzierte Stick-Signal
volatile char Channels,tmpChannels = 0;
volatile unsigned char NewPpmData = 1;
unsigned int PPM_Neutral = 466;
 
//############################################################################
//zum decodieren des PPM-Signals wird Timer1 mit seiner Input
//Capture Funktion benutzt:
void rc_sum_init (void)
//############################################################################
{
unsigned char i;
for(i=0;i<26;i++)
{
if(i < 5) PPM_in[i] = 0; else PPM_in[i] = -126;
PPM_diff[i] = 0;
}
 
AdNeutralGier = 0;
AdNeutralRoll = 0;
AdNeutralNick = 0;
return;
}
 
#ifndef ACT_S3D_SUMMENSIGNAL
//############################################################################
//Diese Routine startet und inizialisiert den Timer für RC
ISR(TIMER1_CAPT_vect)
//############################################################################
{
if(!(EE_Parameter.ExtraConfig & CFG_SENSITIVE_RC))
{
static unsigned int AltICR=0;
signed int signal = 0,tmp;
static int index;
 
signal = (unsigned int) ICR1 - AltICR;
AltICR = ICR1;
//Syncronisationspause? (3.52 ms < signal < 25.6 ms)
if((signal > 1100) && (signal < 8000))
{
Channels = index;
if(index >= 4) NewPpmData = 0; // Null bedeutet: Neue Daten
index = 1;
}
else
{
if(index < 13)
{
if((signal > 250) && (signal < 687))
{
signal -= PPM_Neutral;
// Stabiles Signal
if(abs(signal - PPM_in[index]) < 6) { if(SenderOkay < 200) SenderOkay += 10; else SenderOkay = 200;}
tmp = (3 * (PPM_in[index]) + signal) / 4;
if(tmp > signal+1) tmp--; else
if(tmp < signal-1) tmp++;
if(SenderOkay >= 195) PPM_diff[index] = ((tmp - PPM_in[index]) / 3) * 3;
else PPM_diff[index] = 0;
PPM_in[index] = tmp;
}
index++;
if(PlatinenVersion < 20)
{
if(index == 5) J3High; else J3Low; // Servosignal an J3 anlegen
if(index == 6) J4High; else J4Low; // Servosignal an J4 anlegen
if(index == 7) J5High; else J5Low; // Servosignal an J5 anlegen
}
}
}
}
else
{
static unsigned int AltICR=0;
static int ppm_in[13];
static int ppm_diff[13];
static int old_ppm_in[13];
static int old_ppm_diff[13];
signed int signal = 0,tmp;
static unsigned char index, okay_cnt = 0;
signal = (unsigned int) ICR1 - AltICR;
AltICR = ICR1;
//Syncronisationspause? (3.52 ms < signal < 25.6 ms)
if((signal > 1100) && (signal < 8000))
{
tmpChannels = index;
if(tmpChannels >= 4 && Channels == tmpChannels)
{
if(okay_cnt > 10)
{
NewPpmData = 0; // Null bedeutet: Neue Daten
for(index = 0; index < 13; index++)
{
if(okay_cnt > 30)
{
old_ppm_in[index] = PPM_in[index];
old_ppm_diff[index] = PPM_diff[index];
}
PPM_in[index] = ppm_in[index];
PPM_diff[index] = ppm_diff[index];
}
}
if(okay_cnt < 255) okay_cnt++;
}
else
{
if(okay_cnt > 100) okay_cnt = 10; else okay_cnt = 0;
ROT_ON;
}
index = 1;
if(!MotorenEin) Channels = tmpChannels;
}
else
{
if(index < 13)
{
if((signal > 250) && (signal < 687))
{
signal -= PPM_Neutral;
// Stabiles Signal
if((abs(signal - ppm_in[index]) < 6))
{
if(okay_cnt > 25) SenderOkay += 10;
else
if(okay_cnt > 10) SenderOkay += 2;
if(SenderOkay > 200) SenderOkay = 200;
}
tmp = (3 * (ppm_in[index]) + signal) / 4;
if(tmp > signal+1) tmp--; else
if(tmp < signal-1) tmp++;
if(SenderOkay >= 190) ppm_diff[index] = ((tmp - ppm_in[index]) / 3) * 3;
else ppm_diff[index] = 0;
ppm_in[index] = tmp;
}
else ROT_ON;
if(PlatinenVersion < 20)
{
if(index == 5) J3High; else J3Low; // Servosignal an J3 anlegen
if(index == 6) J4High; else J4Low; // Servosignal an J4 anlegen
if(index == 7) J5High; else J5Low; // Servosignal an J5 anlegen
}
}
if(index < 20) index++;
else
if(index == 20)
{
unsigned char i;
ROT_ON;
index = 30;
for(i=0;i<13;i++) // restore from older data
{
PPM_in[i] = old_ppm_in[i];
PPM_diff[i] = 0;
// okay_cnt /= 2;
}
}
}
}
}
 
#else
//############################################################################
//Diese Routine startet und inizialisiert den Timer für RC
ISR(TIMER1_CAPT_vect)
//############################################################################
 
{
static unsigned int AltICR=0;
signed int signal = 0,tmp;
static int index;
 
signal = (unsigned int) ICR1 - AltICR;
signal /= 2;
AltICR = ICR1;
//Syncronisationspause?
if((signal > 1100*2) && (signal < 8000*2))
{
if(index >= 4) NewPpmData = 0; // Null bedeutet: Neue Daten
index = 1;
}
else
{
if(index < 13)
{
if((signal > 250) && (signal < 687*2))
{
signal -= 962;
// Stabiles Signal
if(abs(signal - PPM_in[index]) < 6) { if(SenderOkay < 200) SenderOkay += 10;}
tmp = (3 * (PPM_in[index]) + signal) / 4;
if(tmp > signal+1) tmp--; else
if(tmp < signal-1) tmp++;
if(SenderOkay >= 195) PPM_diff[index] = ((tmp - PPM_in[index]) / 3) * 3;
else PPM_diff[index] = 0;
PPM_in[index] = tmp;
}
index++;
}
}
}
#endif
 
/branches/V0.86d_MartinW_Jeti+V0.20/spi.c
0,0 → 1,390
// ######################## SPI - FlightCtrl ###################
#include "main.h"
#include "eeprom.h"
 
//struct str_ToNaviCtrl_Version ToNaviCtrl_Version;
//struct str_FromNaviCtrl_Version FromNaviCtrl_Version;
struct str_ToNaviCtrl ToNaviCtrl;
struct str_FromNaviCtrl FromNaviCtrl;
struct str_FromNaviCtrl_Value FromNaviCtrl_Value;
struct str_SPI_VersionInfo NC_Version;
struct str_GPSInfo GPSInfo;
 
unsigned char SPI_BufferIndex;
unsigned char SPI_RxBufferIndex;
signed char FromNC_Rotate_C = 32, FromNC_Rotate_S = 0;
 
volatile unsigned char SPI_Buffer[sizeof(FromNaviCtrl)];
unsigned char *SPI_TX_Buffer;
 
unsigned char SPITransferCompleted, SPI_ChkSum;
unsigned char SPI_RxDataValid,NaviDataOkay = 250;
 
unsigned char SPI_CommandSequence[] = {SPI_FCCMD_STICK, SPI_FCCMD_USER, SPI_FCCMD_PARAMETER1, SPI_FCCMD_STICK, SPI_FCCMD_MISC, SPI_FCCMD_VERSION, SPI_FCCMD_STICK, SPI_FCCMD_SERVOS, SPI_FCCMD_ACCU};
unsigned char SPI_CommandCounter = 0;
unsigned char NC_ErrorCode = 0;
unsigned char NC_GPS_ModeCharacter = ' ';
unsigned char EarthMagneticField = 0;
unsigned char EarthMagneticInclination = 0, EarthMagneticInclinationTheoretic = 0;
signed int POI_KameraNick = 0; // in 0,1°
vector16_t MagVec = {0,0,0};
 
#ifdef USE_SPI_COMMUNICATION
 
//------------------------------------------------------
void SPI_MasterInit(void)
{
DDR_SPI |= (1<<DD_MOSI)|(1<<DD_SCK); // Set MOSI and SCK output, all others input
SLAVE_SELECT_DDR_PORT |= (1 << SPI_SLAVE_SELECT);
 
SPCR = (1<<SPE)|(1<<MSTR)|(1<<SPR1)|(0<<SPR0)|(0<<SPIE); // Enable SPI, Master, set clock rate fck/64
SPSR = 0;//(1<<SPI2X);
 
SLAVE_SELECT_PORT |= (1 << SPI_SLAVE_SELECT);
SPITransferCompleted = 1;
 
//SPDR = 0x00; // dummy write
 
ToNaviCtrl.Sync1 = 0xAA;
ToNaviCtrl.Sync2 = 0x83;
 
ToNaviCtrl.Command = SPI_FCCMD_USER;
ToNaviCtrl.IntegralNick = 0;
ToNaviCtrl.IntegralRoll = 0;
FromNaviCtrl_Value.SerialDataOkay = 0;
SPI_RxDataValid = 0;
 
}
 
//------------------------------------------------------
void SPI_StartTransmitPacket(void)
{
//if ((SLAVE_SELECT_PORT & (1 << SPI_SLAVE_SELECT)) == 0) return; // transfer of prev. packet not completed
if (!SPITransferCompleted) return;
// _delay_us(30);
 
SLAVE_SELECT_PORT &= ~(1 << SPI_SLAVE_SELECT); // SelectSlave
SPI_TX_Buffer = (unsigned char *) &ToNaviCtrl;
 
ToNaviCtrl.Command = SPI_CommandSequence[SPI_CommandCounter++];
if (SPI_CommandCounter >= sizeof(SPI_CommandSequence)) SPI_CommandCounter = 0;
 
SPITransferCompleted = 0;
UpdateSPI_Buffer(); // update buffer
 
SPI_BufferIndex = 1;
//ebugOut.Analog[16]++;
// -- Debug-Output ---
//----
asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop");
asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop");
asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop");
ToNaviCtrl.Chksum = ToNaviCtrl.Sync1;
SPDR = ToNaviCtrl.Sync1; // Start transmission
// SLAVE_SELECT_PORT |= (1 << SPI_SLAVE_SELECT); // DeselectSlave
 
}
 
//------------------------------------------------------
//SIGNAL(SIG_SPI)
void SPI_TransmitByte(void)
{
static unsigned char SPI_RXState = 0;
unsigned char rxdata;
static unsigned char rxchksum;
 
if (SPITransferCompleted) return;
if (!(SPSR & (1 << SPIF))) return;
SendSPI = 4;
 
// _delay_us(30);
SLAVE_SELECT_PORT |= (1 << SPI_SLAVE_SELECT); // DeselectSlave
 
rxdata = SPDR;
switch ( SPI_RXState)
{
case 0:
 
SPI_RxBufferIndex = 0;
rxchksum = rxdata;
if (rxdata == 0x81 ) { SPI_RXState = 1; } // 1. Syncbyte ok
 
break;
 
case 1:
if (rxdata == 0x55) { rxchksum += rxdata; SPI_RXState = 2; } // 2. Syncbyte ok
else SPI_RXState = 0;
break;
 
case 2:
SPI_Buffer[SPI_RxBufferIndex++]= rxdata; // get data
//DebugOut.Analog[19]++;
if (SPI_RxBufferIndex >= sizeof(FromNaviCtrl))
{
 
if (rxdata == rxchksum)
{
unsigned char *ptr = (unsigned char *)&FromNaviCtrl;
memcpy(ptr, (unsigned char *) SPI_Buffer, sizeof(SPI_Buffer));
SPI_RxDataValid = 1;
}
else
{
SPI_RxDataValid = 0;
}
 
 
SPI_RXState = 0;
}
else rxchksum += rxdata;
break;
 
}
 
if (SPI_BufferIndex < sizeof(ToNaviCtrl))
{
SLAVE_SELECT_PORT &= ~(1 << SPI_SLAVE_SELECT); // SelectSlave
asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop");
asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop");
asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop"); asm volatile ("nop");
 
SPDR = SPI_TX_Buffer[SPI_BufferIndex];
ToNaviCtrl.Chksum += SPI_TX_Buffer[SPI_BufferIndex];
// SLAVE_SELECT_PORT |= (1 << SPI_SLAVE_SELECT); // DeselectSlave
 
}
else SPITransferCompleted = 1;
 
SPI_BufferIndex++;
}
 
 
//------------------------------------------------------
void UpdateSPI_Buffer(void)
{
signed int tmp;
static unsigned char motorindex;
ToNaviCtrl.IntegralNick = (int) (IntegralNick / (long)(EE_Parameter.GyroAccFaktor * 4));
ToNaviCtrl.IntegralRoll = (int) (IntegralRoll / (long)(EE_Parameter.GyroAccFaktor * 4));
ToNaviCtrl.GyroCompass = (10 * ErsatzKompass) / GIER_GRAD_FAKTOR;
ToNaviCtrl.GyroGier = (signed int) AdNeutralGier - AdWertGier;
ToNaviCtrl.AccNick = ((int) ACC_AMPLIFY * (NaviAccNick / NaviCntAcc))/4;
ToNaviCtrl.AccRoll = ((int) ACC_AMPLIFY * (NaviAccRoll / NaviCntAcc))/4;
NaviCntAcc = 0; NaviAccNick = 0; NaviAccRoll = 0;
// ToNaviCtrl.User8 = Parameter_UserParam8;
// ToNaviCtrl.CalState = WinkelOut.CalcState;
switch(ToNaviCtrl.Command) //
{
case SPI_FCCMD_USER:
ToNaviCtrl.Param.Byte[0] = Parameter_UserParam1;
ToNaviCtrl.Param.Byte[1] = Parameter_UserParam2;
ToNaviCtrl.Param.Byte[2] = Parameter_UserParam3;
ToNaviCtrl.Param.Byte[3] = Parameter_UserParam4;
ToNaviCtrl.Param.Byte[4] = Parameter_UserParam5;
ToNaviCtrl.Param.Byte[5] = Parameter_UserParam6;
ToNaviCtrl.Param.Byte[6] = Parameter_UserParam7;
ToNaviCtrl.Param.Byte[7] = Parameter_UserParam8;
ToNaviCtrl.Param.Byte[8] = FC_StatusFlags;
FC_StatusFlags &= ~(FC_STATUS_CALIBRATE | FC_STATUS_START);
ToNaviCtrl.Param.Byte[9] = GetActiveParamSet();
ToNaviCtrl.Param.Byte[10] = EE_Parameter.ComingHomeAltitude;
ToNaviCtrl.Param.Byte[11] = FC_StatusFlags2;
break;
 
case SPI_FCCMD_ACCU:
ToNaviCtrl.Param.Int[0] = Capacity.ActualCurrent; // 0.1A
ToNaviCtrl.Param.Int[1] = Capacity.UsedCapacity; // mAh
ToNaviCtrl.Param.Byte[4] = (unsigned char) UBat; // 0.1V
ToNaviCtrl.Param.Byte[5] = (unsigned char) BattLowVoltageWarning; //0.1V
ToNaviCtrl.Param.Byte[6] = VarioCharacter;
ToNaviCtrl.Param.Byte[7] = Parameter_GlobalConfig;
ToNaviCtrl.Param.Byte[8] = Parameter_ExtraConfig;
ToNaviCtrl.Param.Byte[9] = motorindex;
ToNaviCtrl.Param.Byte[10] = Motor[motorindex].Temperature;
ToNaviCtrl.Param.Byte[11] = Motor[motorindex++].Current;
motorindex %= 12;
break;
case SPI_FCCMD_PARAMETER1:
ToNaviCtrl.Param.Byte[0] = EE_Parameter.NaviGpsModeControl; // Parameters for the Naviboard
ToNaviCtrl.Param.Byte[1] = EE_Parameter.NaviGpsGain;
ToNaviCtrl.Param.Byte[2] = EE_Parameter.NaviGpsP;
ToNaviCtrl.Param.Byte[3] = EE_Parameter.NaviGpsI;
ToNaviCtrl.Param.Byte[4] = EE_Parameter.NaviGpsD;
ToNaviCtrl.Param.Byte[5] = EE_Parameter.NaviGpsACC;
ToNaviCtrl.Param.Byte[6] = EE_Parameter.NaviGpsMinSat;
ToNaviCtrl.Param.Byte[7] = EE_Parameter.NaviStickThreshold;
ToNaviCtrl.Param.Byte[8] = EE_Parameter.NaviOperatingRadius;
ToNaviCtrl.Param.Byte[9] = EE_Parameter.NaviWindCorrection;
ToNaviCtrl.Param.Byte[10] = EE_Parameter.NaviAccCompensation;
ToNaviCtrl.Param.Byte[11] = EE_Parameter.NaviAngleLimitation;
break;
 
case SPI_FCCMD_STICK:
cli();
tmp = PPM_in[EE_Parameter.Kanalbelegung[K_GAS]]; if(tmp > 127) tmp = 127; else if(tmp < -127) tmp = -127;
ToNaviCtrl.Param.Byte[0] = (char) tmp;
tmp = PPM_in[EE_Parameter.Kanalbelegung[K_GIER]]; if(tmp > 127) tmp = 127; else if(tmp < -127) tmp = -127;
ToNaviCtrl.Param.Byte[1] = (char) tmp;
tmp = PPM_in[EE_Parameter.Kanalbelegung[K_ROLL]]; if(tmp > 127) tmp = 127; else if(tmp < -127) tmp = -127;
ToNaviCtrl.Param.Byte[2] = (char) tmp;
tmp = PPM_in[EE_Parameter.Kanalbelegung[K_NICK]]; if(tmp > 127) tmp = 127; else if(tmp < -127) tmp = -127;
sei();
ToNaviCtrl.Param.Byte[3] = (char) tmp;
ToNaviCtrl.Param.Byte[4] = (unsigned char) Poti[0];
ToNaviCtrl.Param.Byte[5] = (unsigned char) Poti[1];
ToNaviCtrl.Param.Byte[6] = (unsigned char) Poti[2];
ToNaviCtrl.Param.Byte[7] = (unsigned char) Poti[3];
ToNaviCtrl.Param.Byte[8] = (unsigned char) Poti[4];
ToNaviCtrl.Param.Byte[9] = (unsigned char) Poti[5];
ToNaviCtrl.Param.Byte[10] = (unsigned char) Poti[6];
ToNaviCtrl.Param.Byte[11] = (unsigned char) Poti[7];
break;
case SPI_FCCMD_MISC:
if(WinkelOut.CalcState > 5)
{
WinkelOut.CalcState = 0;
ToNaviCtrl.Param.Byte[0] = 5;
}
else ToNaviCtrl.Param.Byte[0] = WinkelOut.CalcState;
ToNaviCtrl.Param.Byte[1] = EE_Parameter.NaviPH_LoginTime;
ToNaviCtrl.Param.Int[1] = (int)(HoehenWert/5);
ToNaviCtrl.Param.Int[2] = (int)(SollHoehe/5);
ToNaviCtrl.Param.Byte[6] = EE_Parameter.NaviGpsPLimit;
ToNaviCtrl.Param.Byte[7] = EE_Parameter.NaviGpsILimit;
ToNaviCtrl.Param.Byte[8] = EE_Parameter.NaviGpsDLimit;
ToNaviCtrl.Param.Byte[9] = (unsigned char) SenderOkay;
ToNaviCtrl.Param.Byte[10] = (unsigned char) PPM_in[0];
ToNaviCtrl.Param.Byte[11] = DebugOut.Analog[7] / 4; //GasMischanteil
break;
case SPI_FCCMD_VERSION:
ToNaviCtrl.Param.Byte[0] = VERSION_MAJOR;
ToNaviCtrl.Param.Byte[1] = VERSION_MINOR;
ToNaviCtrl.Param.Byte[2] = VERSION_PATCH;
ToNaviCtrl.Param.Byte[3] = NC_SPI_COMPATIBLE;
ToNaviCtrl.Param.Byte[4] = PlatinenVersion;
ToNaviCtrl.Param.Byte[5] = VersionInfo.HardwareError[0];
ToNaviCtrl.Param.Byte[6] = VersionInfo.HardwareError[1];
VersionInfo.HardwareError[0] = 0;
VersionInfo.HardwareError[1] &= FC_ERROR1_MIXER;
ToNaviCtrl.Param.Byte[7] = VersionInfo.HardwareError[2];
ToNaviCtrl.Param.Byte[8] = VersionInfo.HardwareError[3];
ToNaviCtrl.Param.Byte[9] = VersionInfo.HardwareError[4];
ToNaviCtrl.Param.Byte[10] = EE_Parameter.OrientationAngle;
break;
case SPI_FCCMD_SERVOS:
ToNaviCtrl.Param.Byte[0] = EE_Parameter.ServoNickRefresh; // Parameters for the Servo Control
ToNaviCtrl.Param.Byte[1] = EE_Parameter.ServoCompInvert;
ToNaviCtrl.Param.Byte[2] = Parameter_ServoNickControl;
ToNaviCtrl.Param.Byte[3] = EE_Parameter.ServoNickComp;
ToNaviCtrl.Param.Byte[4] = EE_Parameter.ServoNickMin;
ToNaviCtrl.Param.Byte[5] = EE_Parameter.ServoNickMax;
ToNaviCtrl.Param.Byte[6] = Parameter_ServoRollControl;
ToNaviCtrl.Param.Byte[7] = EE_Parameter.ServoRollComp;
ToNaviCtrl.Param.Byte[8] = EE_Parameter.ServoRollMin;
ToNaviCtrl.Param.Byte[9] = EE_Parameter.ServoRollMax;
ToNaviCtrl.Param.Byte[10] = Capacity.MinOfMaxPWM;
ToNaviCtrl.Param.Byte[11] = DebugOut.Analog[28]; // I2C-Error counter
break;
}
 
if(SPI_RxDataValid)
{
NaviDataOkay = 250;
CalculateCompassTimer = 1;
if(abs(FromNaviCtrl.GPS_Nick) < 512 && abs(FromNaviCtrl.GPS_Roll) < 512 && (EE_Parameter.GlobalConfig & CFG_GPS_AKTIV))
{
GPS_Nick = FromNaviCtrl.GPS_Nick;
GPS_Roll = FromNaviCtrl.GPS_Roll;
}
 
// update compass readings
// MagVec.x = FromNaviCtrl.MagVecX;
// MagVec.y = FromNaviCtrl.MagVecY;
// MagVec.z = FromNaviCtrl.MagVecZ;
 
if(FromNaviCtrl.CompassValue <= 360) KompassValue = FromNaviCtrl.CompassValue;
// KompassRichtung = ((540 + KompassValue - KompassSollWert) % 360) - 180;
 
if(FromNaviCtrl.BeepTime > beeptime /*&& !WinkelOut.CalcState*/) beeptime = FromNaviCtrl.BeepTime;
switch (FromNaviCtrl.Command)
{
case SPI_NCCMD_KALMAN:
FromNaviCtrl_Value.Kalman_K = FromNaviCtrl.Param.sByte[0];
FromNaviCtrl_Value.Kalman_MaxFusion = FromNaviCtrl.Param.sByte[1];
FromNaviCtrl_Value.Kalman_MaxDrift = FromNaviCtrl.Param.sByte[2];
KompassFusion = FromNaviCtrl.Param.sByte[3];
FromNaviCtrl_Value.GpsZ = FromNaviCtrl.Param.Byte[4];
FromNC_Rotate_C = FromNaviCtrl.Param.Byte[5];
FromNC_Rotate_S = FromNaviCtrl.Param.Byte[6];
GPS_Aid_StickMultiplikator = FromNaviCtrl.Param.Byte[7];
if(CareFree && FromNaviCtrl.Param.sInt[4] >= 0)
{
KompassSollWert = FromNaviCtrl.Param.sInt[4]; // bei Carefree kann NC den Kompass-Sollwinkel vorgeben
if(EE_Parameter.CamOrientation) // Kamera angle is not front
{
KompassSollWert += 360 - ((unsigned int) EE_Parameter.CamOrientation * 15);
KompassSollWert %= 360;
}
}
POI_KameraNick = (POI_KameraNick + FromNaviCtrl.Param.sInt[5]) / 2; // FromNaviCtrl.Param.sInt[5]; // Nickwinkel
break;
case SPI_NCCMD_VERSION:
NC_Version.Major = FromNaviCtrl.Param.Byte[0];
NC_Version.Minor = FromNaviCtrl.Param.Byte[1];
NC_Version.Patch = FromNaviCtrl.Param.Byte[2];
NC_Version.Compatible = FromNaviCtrl.Param.Byte[3];
NC_Version.Hardware = FromNaviCtrl.Param.Byte[4];
DebugOut.Status[0] |= FromNaviCtrl.Param.Byte[5];
DebugOut.Status[1] = (DebugOut.Status[1] & (0x01|0x02)) | (FromNaviCtrl.Param.Byte[6] & (0x04 | 0x08));
NC_ErrorCode = FromNaviCtrl.Param.Byte[7];
NC_GPS_ModeCharacter = FromNaviCtrl.Param.Byte[8];
FromNaviCtrl_Value.SerialDataOkay = FromNaviCtrl.Param.Byte[9];
// = FromNaviCtrl.Param.Byte[10];
// = FromNaviCtrl.Param.Byte[11];
break;
case SPI_NCCMD_GPSINFO:
GPSInfo.Flags = FromNaviCtrl.Param.Byte[0];
GPSInfo.NumOfSats = FromNaviCtrl.Param.Byte[1];
GPSInfo.SatFix = FromNaviCtrl.Param.Byte[2];
GPSInfo.Speed = FromNaviCtrl.Param.Byte[3];
GPSInfo.HomeDistance = FromNaviCtrl.Param.Int[2];
GPSInfo.HomeBearing = FromNaviCtrl.Param.sInt[3];
PPM_in[25] = (signed char) FromNaviCtrl.Param.Byte[8]; // WP_EVENT-Channel-Value
FromNC_AltitudeSpeed = FromNaviCtrl.Param.Byte[9];
FromNC_AltitudeSetpoint = (long) FromNaviCtrl.Param.sInt[5] * 10; // in cm
break;
case SPI_MISC:
EarthMagneticField = FromNaviCtrl.Param.Byte[0];
EarthMagneticInclination = FromNaviCtrl.Param.Byte[1];
EarthMagneticInclinationTheoretic = FromNaviCtrl.Param.Byte[2];
break;
 
#if ((defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__)) && defined(WITH_HOTTMENU))
#warning : "### with Hottmenu ###"
case SPI_NCCMD_HOTT_DATA:
if(EE_Parameter.Receiver == RECEIVER_HOTT) NC_Fills_HoTT_Telemety();
break;
#endif
 
// 0 = 0,1
// 1 = 2,3
// 2 = 4,5
// 3 = 6,7
// 4 = 8,9
// 5 = 10,11
default:
break;
}
}
else
{
// KompassValue = 0;
// KompassRichtung = 0;
GPS_Nick = 0;
GPS_Roll = 0;
}
}
 
#endif
 
 
/branches/V0.86d_MartinW_Jeti+V0.20/timer0.c
0,0 → 1,404
#include "main.h"
#define MULTIPLYER 4
 
volatile unsigned int CountMilliseconds = 0;
volatile static unsigned int tim_main;
volatile unsigned char UpdateMotor = 0;
volatile unsigned int cntKompass = 0;
volatile unsigned int beeptime = 0;
volatile unsigned char SendSPI = 0, ServoActive = 0, CalculateServoSignals = 1;
uint16_t RemainingPulse = 0;
volatile int16_t ServoNickOffset = (255 / 2) * MULTIPLYER * 16; // initial value near center positon
volatile int16_t ServoRollOffset = (255 / 2) * MULTIPLYER * 16; // initial value near center positon
 
unsigned int BeepMuster = 0xffff;
 
volatile int16_t ServoNickValue = 0;
volatile int16_t ServoRollValue = 0;
 
 
enum {
STOP = 0,
CK = 1,
CK8 = 2,
CK64 = 3,
CK256 = 4,
CK1024 = 5,
T0_FALLING_EDGE = 6,
T0_RISING_EDGE = 7
};
 
 
ISR(TIMER0_OVF_vect) // 9,7kHz
{
static unsigned char cnt_1ms = 1,cnt = 0, compass_active = 0;
unsigned char pieper_ein = 0;
if(SendSPI) SendSPI--;
if(SpektrumTimer) SpektrumTimer--;
if(!cnt--)
{
cnt = 9;
CountMilliseconds++;
cnt_1ms++;
cnt_1ms %= 2;
 
if(!cnt_1ms) UpdateMotor = 1;
if(!(PINC & 0x10)) compass_active = 1;
 
if(beeptime)
{
if(beeptime > 10) beeptime -= 10; else beeptime = 0;
if(beeptime & BeepMuster)
{
pieper_ein = 1;
}
else pieper_ein = 0;
}
else
{
pieper_ein = 0;
BeepMuster = 0xffff;
}
if(pieper_ein)
{
if(PlatinenVersion == 10) PORTD |= (1<<2); // Speaker an PORTD.2
else PORTC |= (1<<7); // Speaker an PORTC.7
}
else
{
if(PlatinenVersion == 10) PORTD &= ~(1<<2);
else PORTC &= ~(1<<7);
}
}
if(compass_active && !NaviDataOkay && Parameter_GlobalConfig & CFG_KOMPASS_AKTIV)
{
if(PINC & 0x10)
{
if(++cntKompass > 1000) compass_active = 0;
}
else
{
if((cntKompass) && (cntKompass < 362))
{
cntKompass += cntKompass / 41;
if(cntKompass > 10) KompassValue = cntKompass - 10; else KompassValue = 0;
// KompassRichtung = ((540 + KompassValue - KompassSollWert) % 360) - 180;
}
cntKompass = 0;
}
}
}
 
 
// -----------------------------------------------------------------------
unsigned int SetDelay (unsigned int t)
{
// TIMSK0 &= ~_BV(TOIE0);
return(CountMilliseconds + t + 1);
// TIMSK0 |= _BV(TOIE0);
}
 
// -----------------------------------------------------------------------
char CheckDelay(unsigned int t)
{
// TIMSK0 &= ~_BV(TOIE0);
return(((t - CountMilliseconds) & 0x8000) >> 9);
// TIMSK0 |= _BV(TOIE0);
}
 
// -----------------------------------------------------------------------
void Delay_ms(unsigned int w)
{
unsigned int akt;
akt = SetDelay(w);
while (!CheckDelay(akt));
}
 
void Delay_ms_Mess(unsigned int w)
{
unsigned int akt;
akt = SetDelay(w);
while (!CheckDelay(akt)) if(AdReady) {AdReady = 0; ANALOG_ON;}
}
 
/*****************************************************/
/* Initialize Timer 2 */
/*****************************************************/
// The timer 2 is used to generate the PWM at PD7 (J7)
// to control a camera servo for nick compensation.
void TIMER2_Init(void)
{
uint8_t sreg = SREG;
 
// disable all interrupts before reconfiguration
cli();
 
PORTD &= ~(1<<PORTD7); // set PD7 to low
 
DDRC |= (1<<DDC6); // set PC6 as output (Reset for HEF4017)
HEF4017R_ON;
// Timer/Counter 2 Control Register A
 
// Timer Mode is FastPWM with timer reload at OCR2A (Bits: WGM22 = 1, WGM21 = 1, WGM20 = 1)
// PD7: Normal port operation, OC2A disconnected, (Bits: COM2A1 = 0, COM2A0 = 0)
// PD6: Normal port operation, OC2B disconnected, (Bits: COM2B1 = 0, COM2B0 = 0)
TCCR2A &= ~((1<<COM2A1)|(1<<COM2A0)|(1<<COM2B1)|(1<<COM2B0));
TCCR2A |= (1<<WGM21)|(1<<WGM20);
 
// Timer/Counter 2 Control Register B
 
// Set clock divider for timer 2 to SYSKLOCK/32 = 20MHz / 32 = 625 kHz
// The timer increments from 0x00 to 0xFF with an update rate of 625 kHz or 1.6 us
// hence the timer overflow interrupt frequency is 625 kHz / 256 = 2.44 kHz or 0.4096 ms
 
// divider 32 (Bits: CS022 = 0, CS21 = 1, CS20 = 1)
TCCR2B &= ~((1<<FOC2A)|(1<<FOC2B)|(1<<CS22));
TCCR2B |= (1<<CS21)|(1<<CS20)|(1<<WGM22);
 
// Initialize the Timer/Counter 2 Register
TCNT2 = 0;
 
// Initialize the Output Compare Register A used for PWM generation on port PD7.
OCR2A = 255;
TCCR2A |= (1<<COM2A1); // set or clear at compare match depends on value of COM2A0
 
// Timer/Counter 2 Interrupt Mask Register
// Enable timer output compare match A Interrupt only
TIMSK2 &= ~((1<<OCIE2B)|(1<<TOIE2));
TIMSK2 |= (1<<OCIE2A);
 
SREG = sreg;
}
 
//----------------------------
void Timer_Init(void)
{
tim_main = SetDelay(10);
TCCR0B = CK8;
TCCR0A = (1<<COM0A1)|(1<<COM0B1)|3;//fast PWM
OCR0A = 0;
OCR0B = 180;
TCNT0 = (unsigned char)-TIMER_RELOAD_VALUE; // reload
//OCR1 = 0x00;
TIMSK0 |= _BV(TOIE0);
}
 
 
/*****************************************************/
/* Control Servo Position */
/*****************************************************/
 
 
void CalculateServo(void)
{
signed char cosinus, sinus;
signed long nick, roll;
 
cosinus = sintab[EE_Parameter.CamOrientation + 6];
sinus = sintab[EE_Parameter.CamOrientation];
 
if(CalculateServoSignals == 1)
{
nick = (cosinus * IntegralNick) / 128L - (sinus * IntegralRoll) / 128L;
nick -= POI_KameraNick * 7;
nick = ((long)EE_Parameter.ServoNickComp * nick) / 512L;
ServoNickOffset += ((int16_t)Parameter_ServoNickControl * (MULTIPLYER*16) - ServoNickOffset) / EE_Parameter.ServoManualControlSpeed;
ServoNickValue = ServoNickOffset / 16; // offset (Range from 0 to 255 * 3 = 765)
 
if(EE_Parameter.ServoCompInvert & 0x01)
{ // inverting movement of servo
ServoNickValue += nick;//(int16_t)( ( (int32_t)EE_Parameter.ServoNickComp * nick) / (256L) );
}
else
{ // non inverting movement of servo
ServoNickValue -= nick;
}
// limit servo value to its parameter range definition
if(ServoNickValue < ((int16_t)EE_Parameter.ServoNickMin * MULTIPLYER) )
{
ServoNickValue = (int16_t)EE_Parameter.ServoNickMin * MULTIPLYER;
}
else
if(ServoNickValue > ((int16_t)EE_Parameter.ServoNickMax * MULTIPLYER) )
{
ServoNickValue = (int16_t)EE_Parameter.ServoNickMax * MULTIPLYER;
}
if(PlatinenVersion < 20) CalculateServoSignals = 0; else CalculateServoSignals++;
}
else
{
roll = (cosinus * IntegralRoll) / 128L + (sinus * IntegralNick) / 128L;
roll = ((long)EE_Parameter.ServoRollComp * roll) / 512L;
ServoRollOffset += ((int16_t)Parameter_ServoRollControl * (MULTIPLYER*16) - ServoRollOffset) / EE_Parameter.ServoManualControlSpeed;
ServoRollValue = ServoRollOffset/16; // offset (Range from 0 to 255 * 3 = 765)
if(EE_Parameter.ServoCompInvert & 0x02)
{ // inverting movement of servo
ServoRollValue += roll;
}
else
{ // non inverting movement of servo
ServoRollValue -= roll;
}
// limit servo value to its parameter range definition
if(ServoRollValue < ((int16_t)EE_Parameter.ServoRollMin * MULTIPLYER) )
{
ServoRollValue = (int16_t)EE_Parameter.ServoRollMin * MULTIPLYER;
}
else
if(ServoRollValue > ((int16_t)EE_Parameter.ServoRollMax * MULTIPLYER) )
{
ServoRollValue = (int16_t)EE_Parameter.ServoRollMax * MULTIPLYER;
}
CalculateServoSignals = 0;
}
}
 
ISR(TIMER2_COMPA_vect)
{
// frame len 22.5 ms = 14063 * 1.6 us
// stop pulse: 0.3 ms = 188 * 1.6 us
// min servo pulse: 0.6 ms = 375 * 1.6 us
// max servo pulse: 2.4 ms = 1500 * 1.6 us
// resolution: 1500 - 375 = 1125 steps
 
#define IRS_RUNTIME 127
#define PPM_STOPPULSE 188
#define PPM_FRAMELEN (1757 * EE_Parameter.ServoNickRefresh)
#define MINSERVOPULSE 375
#define MAXSERVOPULSE 1500
#define SERVORANGE (MAXSERVOPULSE - MINSERVOPULSE)
 
static uint8_t PulseOutput = 0;
static uint16_t ServoFrameTime = 0;
static uint8_t ServoIndex = 0;
 
 
if(PlatinenVersion < 20)
{
//---------------------------
// Nick servo state machine
//---------------------------
if(!PulseOutput) // pulse output complete
{
if(TCCR2A & (1<<COM2A0)) // we had a low pulse
{
TCCR2A &= ~(1<<COM2A0);// make a high pulse
RemainingPulse = MINSERVOPULSE + SERVORANGE/2; // center position ~ 1.5ms
RemainingPulse += ServoNickValue - (256 / 2) * MULTIPLYER; // shift ServoNickValue to center position
// range servo pulse width
if(RemainingPulse > MAXSERVOPULSE ) RemainingPulse = MAXSERVOPULSE; // upper servo pulse limit
else if(RemainingPulse < MINSERVOPULSE ) RemainingPulse = MINSERVOPULSE; // lower servo pulse limit
// accumulate time for correct update rate
ServoFrameTime = RemainingPulse;
}
else // we had a high pulse
{
TCCR2A |= (1<<COM2A0); // make a low pulse
RemainingPulse = PPM_FRAMELEN - ServoFrameTime;
CalculateServoSignals = 1;
}
// set pulse output active
PulseOutput = 1;
}
} // EOF Nick servo state machine
else
{
//-----------------------------------------------------
// PPM state machine, onboard demultiplexed by HEF4017
//-----------------------------------------------------
if(!PulseOutput) // pulse output complete
{
if(TCCR2A & (1<<COM2A0)) // we had a low pulse
{
TCCR2A &= ~(1<<COM2A0);// make a high pulse
 
if(ServoIndex == 0) // if we are at the sync gap
{
RemainingPulse = PPM_FRAMELEN - ServoFrameTime; // generate sync gap by filling time to full frame time
ServoFrameTime = 0; // reset servo frame time
HEF4017R_ON; // enable HEF4017 reset
}
else // servo channels
{
RemainingPulse = MINSERVOPULSE + SERVORANGE/2; // center position ~ 1.5ms
switch(ServoIndex) // map servo channels
{
case 1: // Nick Compensation Servo
RemainingPulse += ServoNickValue - (256 / 2) * MULTIPLYER; // shift ServoNickValue to center position
break;
case 2: // Roll Compensation Servo
RemainingPulse += ServoRollValue - (256 / 2) * MULTIPLYER; // shift ServoNickValue to center position
break;
case 3:
RemainingPulse += ((int16_t)Parameter_Servo3 * MULTIPLYER) - (256 / 2) * MULTIPLYER;
break;
case 4:
RemainingPulse += ((int16_t)Parameter_Servo4 * MULTIPLYER) - (256 / 2) * MULTIPLYER;
break;
case 5:
RemainingPulse += ((int16_t)Parameter_Servo5 * MULTIPLYER) - (256 / 2) * MULTIPLYER;
break;
default: // other servo channels
RemainingPulse += 2 * PPM_in[ServoIndex]; // add channel value, factor of 2 because timer 1 increments 3.2µs
break;
}
// range servo pulse width
if(RemainingPulse > MAXSERVOPULSE ) RemainingPulse = MAXSERVOPULSE; // upper servo pulse limit
else if(RemainingPulse < MINSERVOPULSE ) RemainingPulse = MINSERVOPULSE; // lower servo pulse limit
// substract stop pulse width
RemainingPulse -= PPM_STOPPULSE;
// accumulate time for correct sync gap
ServoFrameTime += RemainingPulse;
}
}
else // we had a high pulse
{
TCCR2A |= (1<<COM2A0); // make a low pulse
// set pulsewidth to stop pulse width
RemainingPulse = PPM_STOPPULSE;
// accumulate time for correct sync gap
ServoFrameTime += RemainingPulse;
if((ServoActive && SenderOkay) || ServoActive == 2) HEF4017R_OFF; // disable HEF4017 reset
else HEF4017R_ON;
ServoIndex++; // change to next servo channel
if(ServoIndex > EE_Parameter.ServoNickRefresh)
{
CalculateServoSignals = 1;
ServoIndex = 0; // reset to the sync gap
}
}
// set pulse output active
PulseOutput = 1;
}
} // EOF PPM state machine
 
// General pulse output generator
if(RemainingPulse > (255 + IRS_RUNTIME))
{
OCR2A = 255;
RemainingPulse -= 255;
}
else
{
if(RemainingPulse > 255) // this is the 2nd last part
{
if((RemainingPulse - 255) < IRS_RUNTIME)
{
OCR2A = 255 - IRS_RUNTIME;
RemainingPulse -= 255 - IRS_RUNTIME;
 
}
else // last part > ISR_RUNTIME
{
OCR2A = 255;
RemainingPulse -= 255;
}
}
else // this is the last part
{
OCR2A = RemainingPulse;
RemainingPulse = 0;
PulseOutput = 0; // trigger to stop pulse
}
} // EOF general pulse output generator
}
/branches/V0.86d_MartinW_Jeti+V0.20/twimaster.c
0,0 → 1,468
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) Holger Buss, Ingo Busker
// + Nur für den privaten Gebrauch
// + www.MikroKopter.com
// + porting the sources to other systems or using the software on other systems (except hardware from www.mikrokopter.de) is not allowed
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Es gilt für das gesamte Projekt (Hardware, Software, Binärfiles, Sourcecode und Dokumentation),
// + dass eine Nutzung (auch auszugsweise) nur für den privaten (nicht-kommerziellen) Gebrauch zulässig ist.
// + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt
// + bzgl. der Nutzungsbedingungen aufzunehmen.
// + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen,
// + Verkauf von Luftbildaufnahmen, usw.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht,
// + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts
// + auf anderen Webseiten oder sonstigen Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de"
// + eindeutig als Ursprung verlinkt werden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion
// + Benutzung auf eigene Gefahr
// + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Portierung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur
// + mit unserer Zustimmung zulässig
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Redistributions of source code (with or without modifications) must retain the above copyright notice,
// + this list of conditions and the following disclaimer.
// + * Neither the name of the copyright holders nor the names of contributors may be used to endorse or promote products derived
// + from this software without specific prior written permission.
// + * The use of this project (hardware, software, binary files, sources and documentation) is only permittet
// + for non-commercial use (directly or indirectly)
// + Commercial use (for excample: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted
// + with our written permission
// + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be
// + clearly linked as origin
// + * porting to systems other than hardware from www.mikrokopter.de is not allowed
// + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
// + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN// + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// + POSSIBILITY OF SUCH DAMAGE.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
#include <avr/io.h>
#include <avr/interrupt.h>
#include <util/twi.h>
#include "eeprom.h"
#include "twimaster.h"
#include "fc.h"
#include "analog.h"
#include "uart.h"
#include "timer0.h"
 
volatile uint8_t twi_state = TWI_STATE_MOTOR_TX;
volatile uint8_t dac_channel = 0;
volatile uint8_t motor_write = 0;
volatile uint8_t motor_read = 0;
volatile uint8_t I2C_TransferActive = 0;
 
volatile uint16_t I2CTimeout = 100;
 
uint8_t MissingMotor = 0;
 
volatile uint8_t BLFlags = 0;
 
MotorData_t Motor[MAX_MOTORS];
 
// bit mask for witch BL the configuration should be sent
volatile uint16_t BLConfig_WriteMask = 0;
// bit mask for witch BL the configuration should be read
volatile uint16_t BLConfig_ReadMask = 0;
// buffer for BL Configuration
BLConfig_t BLConfig;
 
#define I2C_WriteByte(byte) {TWDR = byte; TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWIE);}
#define I2C_ReceiveByte() {TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWIE) | (1<<TWEA);}
#define I2C_ReceiveLastByte() {TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWIE);}
 
#define SCL_CLOCK 200000L
#define I2C_TIMEOUT 30000
#define TWI_BASE_ADDRESS 0x52
 
/**************************************************/
/* Initialize I2C (TWI) */
/**************************************************/
 
void I2C_Init(char clear)
{
uint8_t i;
uint8_t sreg = SREG;
cli();
 
// SDA is INPUT
DDRC &= ~(1<<DDC1);
// SCL is output
DDRC |= (1<<DDC0);
// pull up SDA
PORTC |= (1<<PORTC0)|(1<<PORTC1);
 
// TWI Status Register
// prescaler 1 (TWPS1 = 0, TWPS0 = 0)
TWSR &= ~((1<<TWPS1)|(1<<TWPS0));
 
// set TWI Bit Rate Register
TWBR = ((F_CPU/SCL_CLOCK)-16)/2;
 
twi_state = TWI_STATE_MOTOR_TX;
motor_write = 0;
motor_read = 0;
 
if(clear) for(i=0; i < MAX_MOTORS; i++)
{
Motor[i].Version = 0;
Motor[i].SetPoint = 0;
Motor[i].SetPointLowerBits = 0;
Motor[i].State = 0;
Motor[i].ReadMode = BL_READMODE_STATUS;
Motor[i].Current = 0;
Motor[i].MaxPWM = 0;
Motor[i].Temperature = 0;
}
sei();
SREG = sreg;
}
 
void I2C_Reset(void)
{
// stop i2c bus
I2C_Stop(TWI_STATE_MOTOR_TX);
TWCR = (1<<TWINT); // reset to original state incl. interrupt flag reset
TWAMR = 0;
TWAR = 0;
TWDR = 0;
TWSR = 0;
TWBR = 0;
I2C_TransferActive = 0;
I2C_Init(0);
I2C_WriteByte(0);
BLFlags |= BLFLAG_READ_VERSION;
}
 
/****************************************/
/* I2C ISR */
/****************************************/
ISR (TWI_vect)
{
static uint8_t missing_motor = 0, motor_read_temperature = 0;
static uint8_t *pBuff = 0;
static uint8_t BuffLen = 0;
 
switch (twi_state++)
{
// Master Transmit
case 0: // TWI_STATE_MOTOR_TX
I2C_TransferActive = 1;
// skip motor if not used in mixer
while((Mixer.Motor[motor_write][MIX_GAS] <= 0) && (motor_write < MAX_MOTORS)) motor_write++;
if(motor_write >= MAX_MOTORS) // writing finished, read now
{
BLConfig_WriteMask = 0; // reset configuration bitmask
motor_write = 0; // reset motor write counter for next cycle
twi_state = TWI_STATE_MOTOR_RX;
I2C_WriteByte(TWI_BASE_ADDRESS + TW_READ + (motor_read<<1) ); // select slave address in rx mode
}
else I2C_WriteByte(TWI_BASE_ADDRESS + TW_WRITE + (motor_write<<1) ); // select slave address in tx mode
break;
case 1: // Send Data to Slave
I2C_WriteByte(Motor[motor_write].SetPoint); // transmit setpoint
// if old version has been detected
if(!(Motor[motor_write].Version & MOTOR_STATE_NEW_PROTOCOL_MASK))
{
twi_state = 4; //jump over sending more data
}
// the new version has been detected
else if(!( (Motor[motor_write].SetPointLowerBits && (RequiredMotors < 7)) || BLConfig_WriteMask || BLConfig_ReadMask ) )
{ // or LowerBits are zero and no BlConfig should be sent (saves round trip time)
twi_state = 4; //jump over sending more data
}
break;
case 2: // lower bits of setpoint (higher resolution)
if ((0x0001<<motor_write) & BLConfig_ReadMask)
{
Motor[motor_write].ReadMode = BL_READMODE_CONFIG; // configuration request
}
else
{
Motor[motor_write].ReadMode = BL_READMODE_STATUS; // normal status request
}
// send read mode and the lower bits of setpoint
I2C_WriteByte((Motor[motor_write].ReadMode<<3)|(Motor[motor_write].SetPointLowerBits & 0x07));
// configuration tranmission request?
if((0x0001<<motor_write) & BLConfig_WriteMask)
{ // redirect tx pointer to configuration data
pBuff = (uint8_t*)&BLConfig; // select config for motor
BuffLen = sizeof(BLConfig_t);
}
else
{ // jump to end of transmission for that motor
twi_state = 4;
}
break;
case 3: // send configuration
I2C_WriteByte(*pBuff);
pBuff++;
if(--BuffLen > 0) twi_state = 3; // if there are some bytes left
break;
case 4: // repeat case 0-4 for all motors
if(TWSR == TW_MT_DATA_NACK) // Data transmitted, NACK received
{
if(!missing_motor) missing_motor = motor_write + 1;
if((Motor[motor_write].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[motor_write].State++; // increment error counter and handle overflow
}
I2C_Stop(TWI_STATE_MOTOR_TX);
I2CTimeout = 10;
motor_write++; // next motor
I2C_Start(TWI_STATE_MOTOR_TX); // Repeated start -> switch slave or switch Master Transmit -> Master Receive
break;
// Master Receive Data
case 5: // TWI_STATE_MOTOR_RX
if(TWSR != TW_MR_SLA_ACK) // SLA+R transmitted but no ACK received
{ // no response from the addressed slave received
Motor[motor_read].State &= ~MOTOR_STATE_PRESENT_MASK; // clear present bit
if(++motor_read >= MAX_MOTORS)
{ // all motors read
motor_read = 0; // restart from beginning
BLConfig_ReadMask = 0; // reset read configuration bitmask
if(++motor_read_temperature >= MAX_MOTORS)
{
motor_read_temperature = 0;
BLFlags &= ~BLFLAG_READ_VERSION;
}
}
BLFlags |= BLFLAG_TX_COMPLETE;
I2C_Stop(TWI_STATE_MOTOR_TX);
I2C_TransferActive = 0;
}
else
{ // motor successfully addressed
Motor[motor_read].State |= MOTOR_STATE_PRESENT_MASK; // set present bit
if(Motor[motor_read].Version & MOTOR_STATE_NEW_PROTOCOL_MASK)
{
// new BL found
switch(Motor[motor_read].ReadMode)
{
case BL_READMODE_CONFIG:
pBuff = (uint8_t*)&BLConfig;
BuffLen = sizeof(BLConfig_t);
break;
 
case BL_READMODE_STATUS:
pBuff = (uint8_t*)&(Motor[motor_read].Current);
if(motor_read == motor_read_temperature) BuffLen = 3; // read Current, MaxPwm & Temp
else BuffLen = 1;// read Current only
break;
}
}
else // old BL version
{
pBuff = (uint8_t*)&(Motor[motor_read].Current);
if((BLFlags & BLFLAG_READ_VERSION) || (motor_read == motor_read_temperature)) BuffLen = 2; // Current & MaxPwm
else BuffLen = 1; // read Current only
}
if(BuffLen == 1)
{
I2C_ReceiveLastByte(); // read last byte
}
else
{
I2C_ReceiveByte(); // read next byte
}
}
MissingMotor = missing_motor;
missing_motor = 0;
break;
case 6: // receive bytes
*pBuff = TWDR;
pBuff++;
BuffLen--;
if(BuffLen>1)
{
I2C_ReceiveByte(); // read next byte
}
else if (BuffLen == 1)
{
I2C_ReceiveLastByte(); // read last byte
}
else // nothing left
{
if(BLFlags & BLFLAG_READ_VERSION)
{
if(!(FC_StatusFlags & FC_STATUS_MOTOR_RUN) && (Motor[motor_read].MaxPWM == 250) ) Motor[motor_read].Version |= MOTOR_STATE_NEW_PROTOCOL_MASK;
else Motor[motor_read].Version = 0;
}
if(++motor_read >= MAX_MOTORS)
{
motor_read = 0; // restart from beginning
BLConfig_ReadMask = 0; // reset read configuration bitmask
if(++motor_read_temperature >= MAX_MOTORS)
{
motor_read_temperature = 0;
BLFlags &= ~BLFLAG_READ_VERSION;
}
}
I2C_Stop(TWI_STATE_MOTOR_TX);
BLFlags |= BLFLAG_TX_COMPLETE;
I2C_TransferActive = 0;
return;
}
twi_state = 6; // if there are some bytes left
break;
 
// writing Gyro-Offsets
case 18:
I2C_WriteByte(0x98); // Address the DAC
break;
 
case 19:
I2C_WriteByte(0x10 + (dac_channel * 2)); // Select DAC Channel (0x10 = A, 0x12 = B, 0x14 = C)
break;
 
case 20:
switch(dac_channel)
{
case 0:
I2C_WriteByte(AnalogOffsetNick); // 1st byte for Channel A
break;
case 1:
I2C_WriteByte(AnalogOffsetRoll); // 1st byte for Channel B
break;
case 2:
I2C_WriteByte(AnalogOffsetGier); // 1st byte for Channel C
break;
}
break;
 
case 21:
I2C_WriteByte(0x80); // 2nd byte for all channels is 0x80
break;
 
case 22:
I2C_Stop(TWI_STATE_MOTOR_TX);
I2C_TransferActive = 0;
I2CTimeout = 10;
// repeat case 18...22 until all DAC Channels are updated
if(dac_channel < 2)
{
dac_channel ++; // jump to next channel
I2C_Start(TWI_STATE_GYRO_OFFSET_TX); // start transmission for next channel
}
else
{
dac_channel = 0; // reset dac channel counter
BLFlags |= BLFLAG_TX_COMPLETE;
}
break;
default:
I2C_Stop(TWI_STATE_MOTOR_TX);
BLFlags |= BLFLAG_TX_COMPLETE;
I2CTimeout = 10;
motor_write = 0;
motor_read = 0;
I2C_TransferActive = 0;
break;
}
 
}
 
 
uint8_t I2C_WriteBLConfig(uint8_t motor)
{
uint8_t i;
uint16_t timer;
 
if(MotorenEin || PC_MotortestActive) return(BLCONFIG_ERR_MOTOR_RUNNING); // not when motors are running!
if(motor > MAX_MOTORS) return (BLCONFIG_ERR_MOTOR_NOT_EXIST); // motor does not exist!
if(motor)
{
if(!(Motor[motor-1].State & MOTOR_STATE_PRESENT_MASK)) return(BLCONFIG_ERR_MOTOR_NOT_EXIST); // motor does not exist!
if(!(Motor[motor-1].Version & MOTOR_STATE_NEW_PROTOCOL_MASK)) return(BLCONFIG_ERR_HW_NOT_COMPATIBLE); // not a new BL!
}
// check BL configuration to send
if(BLConfig.Revision != BLCONFIG_REVISION) return (BLCONFIG_ERR_SW_NOT_COMPATIBLE); // bad revison
i = RAM_Checksum((uint8_t*)&BLConfig, sizeof(BLConfig_t) - 1);
if(i != BLConfig.crc) return(BLCONFIG_ERR_CHECKSUM); // bad checksum
 
timer = SetDelay(2000);
while(!(BLFlags & BLFLAG_TX_COMPLETE) && !CheckDelay(timer)); //wait for complete transfer
 
// prepare the bitmask
if(!motor) // 0 means all
{
BLConfig_WriteMask = 0xFF; // all motors at once with the same configuration
}
else //only one specific motor
{
BLConfig_WriteMask = 0x0001<<(motor-1);
}
for(i = 0; i < MAX_MOTORS; i++)
{
if((0x0001<<i) & BLConfig_WriteMask)
{
Motor[i].SetPoint = 0;
Motor[i].SetPointLowerBits = 0;
}
}
 
motor_write = 0;
// needs at least MAX_MOTORS loops of 2 ms (12*2ms = 24ms)
do
{
I2C_Start(TWI_STATE_MOTOR_TX); // start an i2c transmission
while(!(BLFlags & BLFLAG_TX_COMPLETE) && !CheckDelay(timer)); //wait for complete transfer
}while(BLConfig_WriteMask && !CheckDelay(timer)); // repeat until the BL config has been sent
if(BLConfig_WriteMask) return(BLCONFIG_ERR_MOTOR_NOT_EXIST);
return(BLCONFIG_SUCCESS);
}
 
uint8_t I2C_ReadBLConfig(uint8_t motor)
{
uint8_t i;
uint16_t timer;
 
if(MotorenEin || PC_MotortestActive) return(BLCONFIG_ERR_MOTOR_RUNNING); // not when motors are running!
if(motor > MAX_MOTORS) return (BLCONFIG_ERR_MOTOR_NOT_EXIST); // motor does not exist!
if(motor == 0) return (BLCONFIG_ERR_READ_NOT_POSSIBLE);
if(!(Motor[motor-1].State & MOTOR_STATE_PRESENT_MASK)) return(BLCONFIG_ERR_MOTOR_NOT_EXIST); // motor does not exist!
if(!(Motor[motor-1].Version & MOTOR_STATE_NEW_PROTOCOL_MASK)) return(BLCONFIG_ERR_HW_NOT_COMPATIBLE); // not a new BL!
 
timer = SetDelay(2000);
while(!(BLFlags & BLFLAG_TX_COMPLETE) && !CheckDelay(timer)); //wait for complete transfer
 
// prepare the bitmask
BLConfig_ReadMask = 0x0001<<(motor-1);
 
for(i = 0; i < MAX_MOTORS; i++)
{
if((0x0001<<i) & BLConfig_ReadMask)
{
Motor[i].SetPoint = 0;
Motor[i].SetPointLowerBits = 0;
}
}
 
motor_read = 0;
BLConfig.Revision = 0; // bad revision
BLConfig.crc = 0; // bad checksum
// needs at least MAX_MOTORS loops of 2 ms (12*2ms = 24ms)
do
{
I2C_Start(TWI_STATE_MOTOR_TX); // start an i2c transmission
while(!(BLFlags & BLFLAG_TX_COMPLETE) && !CheckDelay(timer)); //wait for complete transfer
}while(BLConfig_ReadMask && !CheckDelay(timer)); // repeat until the BL config has been received from all motors
// validate result
if(BLConfig.Revision != BLCONFIG_REVISION) return (BLCONFIG_ERR_SW_NOT_COMPATIBLE); // bad revison
i = RAM_Checksum((uint8_t*)&BLConfig, sizeof(BLConfig_t) - 1);
if(i != BLConfig.crc) return(BLCONFIG_ERR_CHECKSUM); // bad checksum
return(BLCONFIG_SUCCESS);
}
 
/branches/V0.86d_MartinW_Jeti+V0.20/uart.c
0,0 → 1,855
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) Holger Buss, Ingo Busker
// + only for non-profit use
// + www.MikroKopter.com
// + see the File "License.txt" for further Informations
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
#include <stdarg.h>
#include <string.h>
#include <avr/pgmspace.h>
#include "main.h"
#include "uart.h"
#include "libfc.h"
#include "eeprom.h"
 
#define FC_ADDRESS 1
#define NC_ADDRESS 2
#define MK3MAG_ADDRESS 3
#define BL_CTRL_ADDRESS 5
 
#define ABO_TIMEOUT 4000 // disable abo after 4 seconds
#define MAX_SENDE_BUFF 170
#define MAX_EMPFANGS_BUFF 170
 
#define BLPARAM_REVISION 1
#define MASK_SET_PWM_SCALING 0x01
#define MASK_SET_CURRENT_LIMIT 0x02
#define MASK_SET_TEMP_LIMIT 0x04
#define MASK_SET_CURRENT_SCALING 0x08
#define MASK_SET_BITCONFIG 0x10
#define MASK_RESET_CAPCOUNTER 0x20
#define MASK_SET_DEFAULT_PARAMS 0x40
#define MASK_SET_SAVE_EEPROM 0x80
 
typedef struct
{
unsigned char Revision; // revision of parameter structure
unsigned char Address; // target address
unsigned char PwmScaling; // maximum value of pwm setpoint
unsigned char CurrentLimit; // current limit in 1A steps
unsigned char TemperatureLimit; // in °C
unsigned char CurrentScaling; // scaling factor for current measurement
unsigned char BitConfig; // see defines above
unsigned char SetMask; // filter for active paramters
unsigned char Checksum; // checksum for parameter sturcture
} __attribute__((packed)) BLParameter_t;
 
 
unsigned char GetExternalControl = 0,DebugDisplayAnforderung1 = 0, DebugDisplayAnforderung = 0,DebugDataAnforderung = 0,GetVersionAnforderung = 0, GetPPMChannelAnforderung = 0;
unsigned char DisplayLine = 0;
unsigned volatile char SioTmp = 0;
unsigned volatile char NeuerDatensatzEmpfangen = 0;
unsigned volatile char NeueKoordinateEmpfangen = 0;
unsigned volatile char UebertragungAbgeschlossen = 1;
unsigned volatile char CntCrcError = 0;
unsigned volatile char AnzahlEmpfangsBytes = 0;
unsigned volatile char TxdBuffer[MAX_SENDE_BUFF];
unsigned volatile char RxdBuffer[MAX_EMPFANGS_BUFF];
 
unsigned char *pRxData = 0;
unsigned char RxDataLen = 0;
unsigned volatile char PC_DebugTimeout = 0;
unsigned volatile char PC_MotortestActive = 0;
unsigned char DebugTextAnforderung = 255;
 
unsigned char PcZugriff = 100;
unsigned char MotorTest[16];
unsigned char MeineSlaveAdresse = 1; // Flight-Ctrl
unsigned char ConfirmFrame;
struct str_DebugOut DebugOut;
struct str_ExternControl ExternControl;
struct str_VersionInfo VersionInfo;
struct str_WinkelOut WinkelOut;
struct str_Data3D Data3D;
 
int Display_Timer, Debug_Timer,Kompass_Timer,Timer3D;
unsigned int DebugDataIntervall = 0, Intervall3D = 0, Display_Interval = 0;
unsigned int AboTimeOut = 0;
unsigned volatile char ReceiverUpdateModeActive = 0; // 1 = Update 2 = JetiBox-Simulation
 
 
 
 
#ifdef WITH_FULL_ANALOG_TEXT /// MartinW main.h means no memsave
#warning : "### with normal ANALOG_TEXT[32][16] ###"
const unsigned char ANALOG_TEXT[32][16] PROGMEM =
{
//1234567890123456
"AngleNick ", //0
"AngleRoll ",
"AccNick ",
"AccRoll ",
"YawGyro ",
"Height Value ", //5
"AccZ ",
"Gas ",
"Compass Value ",
"Voltage [0.1V] ",
"Receiver Level ", //10
"Gyro Compass ",
"Motor 1 ",
"Motor 2 ",
"Motor 3 ",
"Motor 4 ", //15
"Motor 5 ",///
"Motor 6 ",///
"nc alt speed ",
"19 ",
"Servo ", //20
"Hovergas ",
"Current [0.1A] ",
"Capacity [mAh] ",
"Hight Setpoint ",
"Motor 7 ", //25 ///
"Motor 8 ",///
"Compass Setpoint",
"I2C-Error ",
"BL Limit ",
"GPS_Nick ", //30
"GPS_Roll "
};
#else
#warning : "### with reduced ANALOG_TEXT[32][13] ###"
const unsigned char ANALOG_TEXT[32][13] PROGMEM =
{
//1234567890123456
"AngleNick ", //0
"AngleRoll ",
"AccNick ",
"AccRoll ",
"YawGyro ",
"Height Value ", //5
"AccZ ",
"Gas ",
"Compass Value",
"Voltage[0.1V]",
"ReceiverLevel", //10
"Gyro Compass ",
"Motor 1 ",
"Motor 2 ",
"Motor 3 ",
"Motor 4 ", //15
"Motor 5 ",///
"Motor 6 ",///
"nc alt speed ",
"19 ",
"Servo ", //20
"Hovergas ",
"Current[0.1A]",
"Capacity[mAh]",
"Hight Setp ",
"Motor 8 ", //25 ///
"Motor 9 ",///
"Compass Setp ",
"I2C-Error ",
"BL Limit ",
"GPS_Nick ", //30
"GPS_Roll "
};
#endif
 
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//++ Sende-Part der Datenübertragung
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
ISR(USART0_TX_vect)
{
static unsigned int ptr = 0;
unsigned char tmp_tx;
 
if(!UebertragungAbgeschlossen)
{
ptr++; // die [0] wurde schon gesendet
tmp_tx = TxdBuffer[ptr];
if((tmp_tx == '\r') || (ptr == MAX_SENDE_BUFF))
{
ptr = 0;
UebertragungAbgeschlossen = 1;
}
UDR0 = tmp_tx;
}
else ptr = 0;
}
 
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//++ Empfangs-Part der Datenübertragung, incl. CRC-Auswertung
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
ISR(USART0_RX_vect)
{
static unsigned int crc;
static unsigned char crc1,crc2,buf_ptr;
static unsigned char UartState = 0;
unsigned char CrcOkay = 0;
 
if (ReceiverUpdateModeActive == 1) { UDR1 = UDR0; return; } // 1 = Update
if (ReceiverUpdateModeActive == 2) { RxdBuffer[0] = UDR0; return; } // 2 = JetiBox-Simulation
 
SioTmp = UDR0;
 
if(buf_ptr >= MAX_SENDE_BUFF) UartState = 0;
if(SioTmp == '\r' && UartState == 2)
{
UartState = 0;
crc -= RxdBuffer[buf_ptr-2];
crc -= RxdBuffer[buf_ptr-1];
crc %= 4096;
crc1 = '=' + crc / 64;
crc2 = '=' + crc % 64;
CrcOkay = 0;
if((crc1 == RxdBuffer[buf_ptr-2]) && (crc2 == RxdBuffer[buf_ptr-1])) CrcOkay = 1; else { CrcOkay = 0; CntCrcError++;};
if(!NeuerDatensatzEmpfangen && CrcOkay) // Datensatz schon verarbeitet
{
NeuerDatensatzEmpfangen = 1;
AnzahlEmpfangsBytes = buf_ptr + 1;
RxdBuffer[buf_ptr] = '\r';
if(RxdBuffer[2] == 'R')
{
#ifdef WITH_MKTOOL_Display /// MartinW main.h
#warning : "### with MKTool Display ###"
LcdClear();
#endif
 
wdt_enable(WDTO_250MS); // Reset-Commando
ServoActive = 0;
}
 
}
}
else
switch(UartState)
{
case 0:
if(SioTmp == '#' && !NeuerDatensatzEmpfangen) UartState = 1; // Startzeichen und Daten schon verarbeitet
buf_ptr = 0;
RxdBuffer[buf_ptr++] = SioTmp;
crc = SioTmp;
break;
case 1: // Adresse auswerten
UartState++;
RxdBuffer[buf_ptr++] = SioTmp;
crc += SioTmp;
break;
case 2: // Eingangsdaten sammeln
RxdBuffer[buf_ptr] = SioTmp;
if(buf_ptr < MAX_EMPFANGS_BUFF) buf_ptr++;
else UartState = 0;
crc += SioTmp;
break;
default:
UartState = 0;
break;
}
}
 
 
// --------------------------------------------------------------------------
void AddCRC(unsigned int wieviele)
{
unsigned int tmpCRC = 0,i;
for(i = 0; i < wieviele;i++)
{
tmpCRC += TxdBuffer[i];
}
tmpCRC %= 4096;
TxdBuffer[i++] = '=' + tmpCRC / 64;
TxdBuffer[i++] = '=' + tmpCRC % 64;
TxdBuffer[i++] = '\r';
UebertragungAbgeschlossen = 0;
UDR0 = TxdBuffer[0];
}
 
 
 
// --------------------------------------------------------------------------
void SendOutData(unsigned char cmd,unsigned char address, unsigned char BufferAnzahl, ...) //unsigned char *snd, unsigned char len)
{
va_list ap;
unsigned int pt = 0;
unsigned char a,b,c;
unsigned char ptr = 0;
 
unsigned char *snd = 0;
int len = 0;
 
TxdBuffer[pt++] = '#'; // Startzeichen
TxdBuffer[pt++] = 'a' + address; // Adresse (a=0; b=1,...)
TxdBuffer[pt++] = cmd; // Commando
 
va_start(ap, BufferAnzahl);
if(BufferAnzahl)
{
snd = va_arg(ap, unsigned char*);
len = va_arg(ap, int);
ptr = 0;
BufferAnzahl--;
}
while(len)
{
if(len)
{
a = snd[ptr++];
len--;
if((!len) && BufferAnzahl)
{
snd = va_arg(ap, unsigned char*);
len = va_arg(ap, int);
ptr = 0;
BufferAnzahl--;
}
}
else a = 0;
if(len)
{
b = snd[ptr++];
len--;
if((!len) && BufferAnzahl)
{
snd = va_arg(ap, unsigned char*);
len = va_arg(ap, int);
ptr = 0;
BufferAnzahl--;
}
}
else b = 0;
if(len)
{
c = snd[ptr++];
len--;
if((!len) && BufferAnzahl)
{
snd = va_arg(ap, unsigned char*);
len = va_arg(ap, int);
ptr = 0;
BufferAnzahl--;
}
}
else c = 0;
TxdBuffer[pt++] = '=' + (a >> 2);
TxdBuffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4));
TxdBuffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6));
TxdBuffer[pt++] = '=' + ( c & 0x3f);
}
va_end(ap);
AddCRC(pt);
}
 
// --------------------------------------------------------------------------
void Decode64(void) // die daten werden im rx buffer dekodiert, das geht nur, weil aus 4 byte immer 3 gemacht werden.
{
unsigned char a,b,c,d;
unsigned char x,y,z;
unsigned char ptrIn = 3; // start at begin of data block
unsigned char ptrOut = 3;
unsigned char len = AnzahlEmpfangsBytes - 6; // von der Gesamtbytezahl eines Frames gehen 3 Bytes des Headers ('#',Addr, Cmd) und 3 Bytes des Footers (CRC1, CRC2, '\r') ab.
 
while(len)
{
a = RxdBuffer[ptrIn++] - '=';
b = RxdBuffer[ptrIn++] - '=';
c = RxdBuffer[ptrIn++] - '=';
d = RxdBuffer[ptrIn++] - '=';
 
x = (a << 2) | (b >> 4);
y = ((b & 0x0f) << 4) | (c >> 2);
z = ((c & 0x03) << 6) | d;
 
if(len--) RxdBuffer[ptrOut++] = x; else break;
if(len--) RxdBuffer[ptrOut++] = y; else break;
if(len--) RxdBuffer[ptrOut++] = z; else break;
}
pRxData = (unsigned char*)&RxdBuffer[3]; // decodierte Daten beginnen beim 4. Byte
RxDataLen = ptrOut - 3; // wie viele Bytes wurden dekodiert?
 
}
 
// --------------------------------------------------------------------------
void BearbeiteRxDaten(void)
{
if(!NeuerDatensatzEmpfangen) return;
 
unsigned char tempchar1, tempchar2;
Decode64(); // dekodiere datenblock im Empfangsbuffer
switch(RxdBuffer[1]-'a') // check for Slave Address
{
case FC_ADDRESS: // FC special commands
switch(RxdBuffer[2])
{
case 'K':// Kompasswert
memcpy((unsigned char *)&KompassValue , (unsigned char *)pRxData, sizeof(KompassValue));
// KompassRichtung = ((540 + KompassValue - KompassSollWert) % 360) - 180;
break;
case 't':// Motortest
if(AnzahlEmpfangsBytes > 20) memcpy(&MotorTest[0], (unsigned char *)pRxData, sizeof(MotorTest));
else memcpy(&MotorTest[0], (unsigned char *)pRxData, 4);
PC_MotortestActive = 240;
//while(!UebertragungAbgeschlossen);
//SendOutData('T', MeineSlaveAdresse, 0);
PcZugriff = 255;
break;
 
case 'n':// "Get Mixer
while(!UebertragungAbgeschlossen);
SendOutData('N', FC_ADDRESS, 1, (unsigned char *) &Mixer, sizeof(Mixer) - 1);
Debug("Mixer lesen");
break;
 
case 'm':// "Write Mixer
if(pRxData[0] == EEMIXER_REVISION)
{
memcpy(&Mixer, (unsigned char *)pRxData, sizeof(Mixer) - 1);
MixerTable_WriteToEEProm();
tempchar1 = 1;
VersionInfo.HardwareError[1] &= ~FC_ERROR1_MIXER;
}
else
{
tempchar1 = 0;
}
while(!UebertragungAbgeschlossen);
SendOutData('M', FC_ADDRESS, 1, &tempchar1, sizeof(tempchar1));
break;
 
case 'p': // get PPM Channels
GetPPMChannelAnforderung = 1;
PcZugriff = 255;
break;
 
case 'q':// "Get"-Anforderung für Settings
// Bei Get werden die vom PC einstellbaren Werte vom PC zurückgelesen
if((10 <= pRxData[0]) && (pRxData[0] < 20))
{
tempchar1 = pRxData[0] - 10;
if(tempchar1< 1) tempchar1 = 1; // limit to 1
else if(tempchar1 > 5) tempchar1 = 5; // limit to 5
SetDefaultParameter(tempchar1, 1);
}
else if((20 <= pRxData[0]) && (pRxData[0] < 30))
{
tempchar1 = pRxData[0] - 20;
if(tempchar1< 1) tempchar1 = 1; // limit to 1
else if(tempchar1 > 5) tempchar1 = 5; // limit to 5
SetDefaultParameter(tempchar1, 0);
}
else
{
tempchar1 = pRxData[0];
if(tempchar1 == 0xFF)
{
tempchar1 = GetActiveParamSet();
}
if(tempchar1< 1) tempchar1 = 1; // limit to 1
else if(tempchar1 > 5) tempchar1 = 5; // limit to 5
// load requested parameter set
ParamSet_ReadFromEEProm(tempchar1);
}
while(!UebertragungAbgeschlossen);
SendOutData('Q', FC_ADDRESS, 2, &tempchar1, sizeof(tempchar1), (unsigned char *) &EE_Parameter, sizeof(EE_Parameter) - 1);
Debug("Lese Setting %d", tempchar1);
 
break;
 
case 's': // Parametersatz speichern
if((1 <= pRxData[0]) && (pRxData[0] <= 5) && (pRxData[1] == EEPARAM_REVISION) && MotorenEin == 0) // check for setting to be in range
{
memcpy(&EE_Parameter, (uint8_t*)&pRxData[1], sizeof(EE_Parameter) - 1);
ParamSet_WriteToEEProm(pRxData[0]);
Umschlag180Nick = (long) EE_Parameter.WinkelUmschlagNick * 2500L;
Umschlag180Roll = (long) EE_Parameter.WinkelUmschlagRoll * 2500L;
tempchar1 = GetActiveParamSet();
}
else
{
tempchar1 = 0; // mark in response an invlid setting
}
while(!UebertragungAbgeschlossen);
SendOutData('S', FC_ADDRESS, 1, &tempchar1, sizeof(tempchar1));
if(!MotorenEin) Piep(tempchar1,110);
LipoDetection(0);
LIBFC_ReceiverInit(EE_Parameter.Receiver);
break;
case 'f': // auf anderen Parametersatz umschalten
if((1 <= pRxData[0]) && (pRxData[0] <= 5)) ParamSet_ReadFromEEProm(pRxData[0]);
tempchar1 = GetActiveParamSet();
while(!UebertragungAbgeschlossen);
SendOutData('F', FC_ADDRESS, 1, &tempchar1, sizeof(tempchar1));
if(!MotorenEin) Piep(tempchar1,110);
LipoDetection(0);
LIBFC_ReceiverInit(EE_Parameter.Receiver);
break;
case 'y':// serial Potis
PPM_in[13] = (signed char) pRxData[0]; PPM_in[14] = (signed char) pRxData[1]; PPM_in[15] = (signed char) pRxData[2]; PPM_in[16] = (signed char) pRxData[3];
PPM_in[17] = (signed char) pRxData[4]; PPM_in[18] = (signed char) pRxData[5]; PPM_in[19] = (signed char) pRxData[6]; PPM_in[20] = (signed char) pRxData[7];
PPM_in[21] = (signed char) pRxData[8]; PPM_in[22] = (signed char) pRxData[9]; PPM_in[23] = (signed char) pRxData[10]; PPM_in[24] = (signed char) pRxData[11];
break;
 
case 'u': // request BL parameter
Debug("Reading BL %d", pRxData[0]);
// try to read BL configuration
tempchar2 = I2C_ReadBLConfig(pRxData[0]);
if(tempchar2 == BLCONFIG_SUCCESS) tempchar1 = 1;
else tempchar1 = 0;
while(!UebertragungAbgeschlossen); // wait for previous frame to be sent
SendOutData('U', FC_ADDRESS, 4, &tempchar1, sizeof(tempchar1), &tempchar2, sizeof(tempchar2), &pRxData[0], 1, &BLConfig, sizeof(BLConfig_t));
break;
 
case 'w': // write BL parameter
Debug("Writing BL %d", pRxData[0]);
if(RxDataLen >= 1+sizeof(BLConfig_t))
{
memcpy(&BLConfig, (uint8_t*)(&pRxData[1]), sizeof(BLConfig_t));
tempchar2 = I2C_WriteBLConfig(pRxData[0]);
if(tempchar2 == BLCONFIG_SUCCESS) tempchar1 = 1;
else tempchar1 = 0; // indicate error
while(!UebertragungAbgeschlossen); // wait for previous frame to be sent
SendOutData('W', FC_ADDRESS,2, &tempchar1, sizeof(tempchar1), &tempchar2, sizeof(tempchar2));
}
break;
case 'j':
if(MotorenEin) break;
#ifdef WITH_JETI_SIMULATION /// MartinW main.h means no memsave
#warning : "### with jeti update command ###"
 
 
tempchar1 = LIBFC_GetCPUType();
if((tempchar1 == CPU_ATMEGA644P) || (tempchar1 == CPU_ATMEGA1284P))
{
uint16_t ubrr = (uint16_t) ((uint32_t) F_CPU/ (8 * 38400L) - 1);
 
cli();
 
// UART0 & UART1 disable RX and TX-Interrupt
UCSR0B &= ~((1 << RXCIE0)|(1 << TXCIE0));
UCSR1B &= ~((1 << RXCIE1)|(1 << TXCIE1));
 
// UART0 & UART1 disable receiver and transmitter
UCSR0B &= ~((1 << TXEN0) | (1 << RXEN0));
UCSR1B &= ~((1 << TXEN1) | (1 << RXEN1));
 
// UART0 & UART1 flush receive buffer explicit
while ( UCSR1A & (1<<RXC1) ) UDR1;
while ( UCSR0A & (1<<RXC0) ) UDR0;
 
 
if(pRxData[0] == 1) ReceiverUpdateModeActive = 2;
else
{ // Jeti or HoTT update
//#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
if(pRxData[0] == 100) ubrr = (uint16_t) ((uint32_t) F_CPU/ (8 * 19200L) - 1); // HoTT
//#endif
ReceiverUpdateModeActive = 1;
// UART0 & UART1 set baudrate
UBRR1H = (uint8_t)(ubrr>>8);
UBRR1L = (uint8_t)ubrr;
UBRR0H = UBRR1H;
UBRR0L = UBRR1L;
// UART1 no parity
UCSR1C &= ~(1 << UPM11);
UCSR1C &= ~(1 << UPM10);
// UART1 8-bit
UCSR1B &= ~(1 << UCSZ12);
UCSR1C |= (1 << UCSZ11);
UCSR1C |= (1 << UCSZ10);
}
// UART0 & UART1 1 stop bit
UCSR1C &= ~(1 << USBS1);
UCSR0C &= ~(1 << USBS0);
// UART1 clear 9th bit
UCSR1B &= ~(1<<TXB81);
// enable receiver and transmitter for UART0 and UART1
UCSR0B |= (1 << TXEN0) | (1 << RXEN0);
UCSR1B |= (1 << TXEN1) | (1 << RXEN1);
// enable RX-Interrupt for UART0 and UART1
UCSR0B |= (1 << RXCIE0);
UCSR1B |= (1 << RXCIE1);
// disable other Interrupts
TIMSK0 = 0;
TIMSK1 = 0;
TIMSK2 = 0;
 
sei();
}
#else
#warning : "### without jeti update command ###"
 
#endif
break;
 
} // case FC_ADDRESS:
 
default: // any Slave Address
 
switch(RxdBuffer[2])
{
// 't' comand placed here only for compatibility to BL
case 't':// Motortest
if(AnzahlEmpfangsBytes >= sizeof(MotorTest)) memcpy(&MotorTest[0], (unsigned char *)pRxData, sizeof(MotorTest));
else memcpy(&MotorTest[0], (unsigned char *)pRxData, 4);
while(!UebertragungAbgeschlossen);
SendOutData('T', MeineSlaveAdresse, 0);
PC_MotortestActive = 250;
PcZugriff = 255;
AboTimeOut = SetDelay(ABO_TIMEOUT);
break;
// 'K' comand placed here only for compatibility to old MK3MAG software, that does not send the right Slave Address
case 'K':// Kompasswert
memcpy((unsigned char *)&KompassValue , (unsigned char *)pRxData, sizeof(KompassValue));
// KompassRichtung = ((540 + KompassValue - KompassSollWert) % 360) - 180;
break;
case 'a':// Texte der Analogwerte
DebugTextAnforderung = pRxData[0];
if (DebugTextAnforderung > 31) DebugTextAnforderung = 31;
PcZugriff = 255;
break;
case 'b':
memcpy((unsigned char *)&ExternControl, (unsigned char *)pRxData, sizeof(ExternControl));
ConfirmFrame = ExternControl.Frame;
PcZugriff = 255;
break;
case 'c': // Poll the 3D-Data
if(!Intervall3D) { if(pRxData[0]) Timer3D = SetDelay(pRxData[0] * 10);}
Intervall3D = pRxData[0] * 10;
AboTimeOut = SetDelay(ABO_TIMEOUT);
break;
case 'd': // Poll the debug data
PcZugriff = 255;
DebugDataIntervall = (unsigned int)pRxData[0] * 10;
if(DebugDataIntervall > 0) DebugDataAnforderung = 1;
AboTimeOut = SetDelay(ABO_TIMEOUT);
break;
 
case 'h':// x-1 Displayzeilen
#ifdef WITH_MKTOOL_Display /// MartinW memorysave
#warning : "### with MKTool Display ###"
 
PcZugriff = 255;
if((pRxData[0] & 0x80) == 0x00) // old format
{
DisplayLine = 2;
Display_Interval = 0;
}
else // new format
{
RemoteKeys |= ~pRxData[0];
Display_Interval = (unsigned int)pRxData[1] * 10;
DisplayLine = 4;
AboTimeOut = SetDelay(ABO_TIMEOUT);
}
DebugDisplayAnforderung = 1;
break;
 
case 'l':// x-1 Displayzeilen
PcZugriff = 255;
MenuePunkt = pRxData[0];
DebugDisplayAnforderung1 = 1;
#endif
break;
case 'v': // Version-Anforderung und Ausbaustufe
GetVersionAnforderung = 1;
break;
 
case 'g'://
GetExternalControl = 1;
break;
 
default:
//unsupported command received
break;
}
break; // default:
}
NeuerDatensatzEmpfangen = 0;
pRxData = 0;
RxDataLen = 0;
}
 
//############################################################################
//Routine für die Serielle Ausgabe
void uart_putchar (char c)
//############################################################################
{
//Warten solange bis Zeichen gesendet wurde
loop_until_bit_is_set(UCSR0A, UDRE0);
//Ausgabe des Zeichens
UDR0 = c;
}
 
 
//############################################################################
//INstallation der Seriellen Schnittstelle
void UART_Init (void)
//############################################################################
{
unsigned int ubrr = (unsigned int) ((unsigned long) F_CPU/(8 * USART0_BAUD) - 1);
 
//Enable TXEN im Register UCR TX-Data Enable & RX Enable
UCSR0B = (1 << TXEN0) | (1 << RXEN0);
// UART Double Speed (U2X)
UCSR0A |= (1 << U2X0);
// RX-Interrupt Freigabe
UCSR0B |= (1 << RXCIE0);
// TX-Interrupt Freigabe
UCSR0B |= (1 << TXCIE0);
// USART0 Baud Rate Register
// set clock divider
UBRR0H = (uint8_t)(ubrr >> 8);
UBRR0L = (uint8_t)ubrr;
 
Debug_Timer = SetDelay(DebugDataIntervall);
Kompass_Timer = SetDelay(220);
 
VersionInfo.SWMajor = VERSION_MAJOR;
VersionInfo.SWMinor = VERSION_MINOR;
VersionInfo.SWPatch = VERSION_PATCH;
VersionInfo.ProtoMajor = VERSION_SERIAL_MAJOR;
VersionInfo.ProtoMinor = VERSION_SERIAL_MINOR;
 
pRxData = 0;
RxDataLen = 0;
}
 
//---------------------------------------------------------------------------------------------
void DatenUebertragung(void)
{
if(!UebertragungAbgeschlossen) return;
 
if(CheckDelay(AboTimeOut))
{
Display_Interval = 0;
DebugDataIntervall = 0;
Intervall3D = 0;
}
 
#ifdef WITH_MKTOOL_Display //main.h
#warning : "### with MKTool Display ###"
 
if(((Display_Interval>0 && CheckDelay(Display_Timer)) || DebugDisplayAnforderung) && UebertragungAbgeschlossen)
{
if(DisplayLine > 3)// new format
{
Menu();
SendOutData('H', FC_ADDRESS, 1, (uint8_t *)DisplayBuff, 80);
}
else // old format
{
LCD_printfxy(0,0,"!!! INCOMPATIBLE !!!");
SendOutData('H', FC_ADDRESS, 2, &DisplayLine, sizeof(DisplayLine), (uint8_t *)DisplayBuff, 20);
if(DisplayLine++ > 3) DisplayLine = 0;
}
Display_Timer = SetDelay(Display_Interval);
DebugDisplayAnforderung = 0;
}
if(DebugDisplayAnforderung1 && UebertragungAbgeschlossen)
{
Menu();
SendOutData('L', FC_ADDRESS, 3, &MenuePunkt, sizeof(MenuePunkt), &MaxMenue, sizeof(MaxMenue), DisplayBuff, sizeof(DisplayBuff));
DebugDisplayAnforderung1 = 0;
}
#endif
 
if(GetVersionAnforderung && UebertragungAbgeschlossen)
{
SendOutData('V', FC_ADDRESS, 1, (unsigned char *) &VersionInfo, sizeof(VersionInfo));
GetVersionAnforderung = 0;
Debug_OK("Version gesendet");
}
 
if(GetExternalControl && UebertragungAbgeschlossen) // Bei Get werden die vom PC einstellbaren Werte vom PC zurückgelesen
{
SendOutData('G',MeineSlaveAdresse, 1, (unsigned char *) &ExternControl, sizeof(ExternControl));
GetExternalControl = 0;
}
if((CheckDelay(Kompass_Timer)) && UebertragungAbgeschlossen)
{
WinkelOut.Winkel[0] = (int) (IntegralNick / (EE_Parameter.GyroAccFaktor * 4)); // etwa in 0.1 Grad
WinkelOut.Winkel[1] = (int) (IntegralRoll / (EE_Parameter.GyroAccFaktor * 4)); // etwa in 0.1 Grad
WinkelOut.UserParameter[0] = Parameter_UserParam1;
WinkelOut.UserParameter[1] = Parameter_UserParam2;
SendOutData('k', MK3MAG_ADDRESS, 1, (unsigned char *) &WinkelOut,sizeof(WinkelOut));
if(WinkelOut.CalcState > 4) WinkelOut.CalcState = 6; // wird dann in SPI auf Null gesetzt
Kompass_Timer = SetDelay(99);
}
if(((DebugDataIntervall>0 && CheckDelay(Debug_Timer)) || DebugDataAnforderung) && UebertragungAbgeschlossen)
{
CopyDebugValues();
SendOutData('D', FC_ADDRESS, 1, (unsigned char *) &DebugOut,sizeof(DebugOut));
DebugDataAnforderung = 0;
if(DebugDataIntervall>0) Debug_Timer = SetDelay(DebugDataIntervall);
}
if(Intervall3D > 0 && CheckDelay(Timer3D) && UebertragungAbgeschlossen)
{
Data3D.Winkel[0] = (int) (IntegralNick / (EE_Parameter.GyroAccFaktor * 4)); // etwa in 0.1 Grad
Data3D.Winkel[1] = (int) (IntegralRoll / (EE_Parameter.GyroAccFaktor * 4)); // etwa in 0.1 Grad
Data3D.Winkel[2] = (int) ((10 * ErsatzKompass) / GIER_GRAD_FAKTOR);
Data3D.Centroid[0] = SummeNick >> 9;
Data3D.Centroid[1] = SummeRoll >> 9;
Data3D.Centroid[2] = Mess_Integral_Gier >> 9;
SendOutData('C', FC_ADDRESS, 1, (unsigned char *) &Data3D,sizeof(Data3D));
Timer3D = SetDelay(Intervall3D);
}
if(DebugTextAnforderung != 255) // Texte für die Analogdaten
{
#ifdef WITH_FULL_ANALOG_TEXT /// MartinW main.h means no memsave
#warning : "### with normal ANALOG_TEXT[32][16] ###"
unsigned char label[16]; // local sram buffer
memcpy_P(label, ANALOG_TEXT[DebugTextAnforderung], 16); // read lable from flash to sra
SendOutData('A', FC_ADDRESS, 2, (unsigned char *)&DebugTextAnforderung, sizeof(DebugTextAnforderung),label, 16);
 
#else
#warning : "### with reduced ANALOG_TEXT[32][13] ###"
unsigned char label[16]=" "; // local sram buffer ///MartinW; for MKTool, needs 32 bytes
memcpy_P(label, ANALOG_TEXT[DebugTextAnforderung], 13); // read lable from flash to sra
SendOutData('A', FC_ADDRESS, 2, (unsigned char *)&DebugTextAnforderung, sizeof(DebugTextAnforderung),label, 16);
#endif
DebugTextAnforderung = 255;
}
if(ConfirmFrame && UebertragungAbgeschlossen) // Datensatz bestätigen
{
SendOutData('B', FC_ADDRESS, 1, (uint8_t*)&ConfirmFrame, sizeof(ConfirmFrame));
ConfirmFrame = 0;
}
 
if(GetPPMChannelAnforderung && UebertragungAbgeschlossen)
{
SendOutData('P', FC_ADDRESS, 1, (unsigned char *) &PPM_in, sizeof(PPM_in));
GetPPMChannelAnforderung = 0;
}
 
#ifdef DEBUG // only include functions if DEBUG is defined
if(SendDebugOutput && UebertragungAbgeschlossen)
{
SendOutData('0', FC_ADDRESS, 1, (unsigned char *) &tDebug, sizeof(tDebug));
SendDebugOutput = 0;
}
#endif
 
}