Subversion Repositories Projects

Compare Revisions

Ignore whitespace Rev 2202 → Rev 2203

/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/10DOF/bmp085.c
0,0 → 1,224
/*
bmp085 lib 0x01
 
copyright (c) Davide Gironi, 2012
 
Released under GPLv3.
Please refer to LICENSE file for licensing information.
*/
 
//############################################################################
//# HISTORY bmp085.c
//#
//# 19.09.2015 cebra
//# - add: Library für BMP085/BMP180 Luftdrucksensor, GY-87 Sensorboard
//#
//############################################################################
 
 
 
 
 
 
 
 
 
#ifdef USE_KOMPASS
 
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include <avr/io.h>
#include <util/delay.h>
 
#include "bmp085.h"
 
//path to i2c fleury lib
#include BMP085_I2CFLEURYPATH
 
/*
* i2c write
*/
void bmp085_writemem(uint8_t reg, uint8_t value) {
i2c_start_wait(BMP085_ADDR | I2C_WRITE);
i2c_write(reg);
i2c_write(value);
i2c_stop();
}
 
/*
* i2c read
*/
void bmp085_readmem(uint8_t reg, uint8_t buff[], uint8_t bytes) {
uint8_t i =0;
i2c_start_wait(BMP085_ADDR | I2C_WRITE);
i2c_write(reg);
i2c_rep_start(BMP085_ADDR | I2C_READ);
for(i=0; i<bytes; i++) {
if(i==bytes-1)
buff[i] = i2c_readNak();
else
buff[i] = i2c_readAck();
}
i2c_stop();
}
 
 
#if BMP085_FILTERPRESSURE == 1
#define BMP085_AVARAGECOEF 21
static long k[BMP085_AVARAGECOEF];
long bmp085_avaragefilter(long input) {
uint8_t i=0;
long sum=0;
for (i=0; i<BMP085_AVARAGECOEF; i++) {
k[i] = k[i+1];
}
k[BMP085_AVARAGECOEF-1] = input;
for (i=0; i<BMP085_AVARAGECOEF; i++) {
sum += k[i];
}
return (sum /BMP085_AVARAGECOEF) ;
}
#endif
 
/*
* read calibration registers
*/
void bmp085_getcalibration() {
uint8_t buff[2];
memset(buff, 0, sizeof(buff));
 
bmp085_readmem(BMP085_REGAC1, buff, 2);
bmp085_regac1 = ((int)buff[0] <<8 | ((int)buff[1]));
bmp085_readmem(BMP085_REGAC2, buff, 2);
bmp085_regac2 = ((int)buff[0] <<8 | ((int)buff[1]));
bmp085_readmem(BMP085_REGAC3, buff, 2);
bmp085_regac3 = ((int)buff[0] <<8 | ((int)buff[1]));
bmp085_readmem(BMP085_REGAC4, buff, 2);
bmp085_regac4 = ((unsigned int)buff[0] <<8 | ((unsigned int)buff[1]));
bmp085_readmem(BMP085_REGAC5, buff, 2);
bmp085_regac5 = ((unsigned int)buff[0] <<8 | ((unsigned int)buff[1]));
bmp085_readmem(BMP085_REGAC6, buff, 2);
bmp085_regac6 = ((unsigned int)buff[0] <<8 | ((unsigned int)buff[1]));
bmp085_readmem(BMP085_REGB1, buff, 2);
bmp085_regb1 = ((int)buff[0] <<8 | ((int)buff[1]));
bmp085_readmem(BMP085_REGB2, buff, 2);
bmp085_regb2 = ((int)buff[0] <<8 | ((int)buff[1]));
bmp085_readmem(BMP085_REGMB, buff, 2);
bmp085_regmb = ((int)buff[0] <<8 | ((int)buff[1]));
bmp085_readmem(BMP085_REGMC, buff, 2);
bmp085_regmc = ((int)buff[0] <<8 | ((int)buff[1]));
bmp085_readmem(BMP085_REGMD, buff, 2);
bmp085_regmd = ((int)buff[0] <<8 | ((int)buff[1]));
}
 
/*
* get raw temperature as read by registers, and do some calculation to convert it
*/
void bmp085_getrawtemperature() {
uint8_t buff[2];
memset(buff, 0, sizeof(buff));
long ut,x1,x2;
 
//read raw temperature
bmp085_writemem(BMP085_REGCONTROL, BMP085_REGREADTEMPERATURE);
_delay_ms(5); // min. 4.5ms read Temp delay
bmp085_readmem(BMP085_REGCONTROLOUTPUT, buff, 2);
ut = ((long)buff[0] << 8 | ((long)buff[1])); //uncompensated temperature value
 
//calculate raw temperature
x1 = ((long)ut - bmp085_regac6) * bmp085_regac5 >> 15;
x2 = ((long)bmp085_regmc << 11) / (x1 + bmp085_regmd);
bmp085_rawtemperature = x1 + x2;
}
 
/*
* get raw pressure as read by registers, and do some calculation to convert it
*/
void bmp085_getrawpressure() {
uint8_t buff[3];
memset(buff, 0, sizeof(buff));
long up,x1,x2,x3,b3,b6,p;
unsigned long b4,b7;
 
#if BMP085_AUTOUPDATETEMP == 1
bmp085_getrawtemperature();
#endif
 
//read raw pressure
bmp085_writemem(BMP085_REGCONTROL, BMP085_REGREADPRESSURE+(BMP085_MODE << 6));
_delay_ms(2 + (3<<BMP085_MODE));
bmp085_readmem(BMP085_REGCONTROLOUTPUT, buff, 3);
up = ((((long)buff[0] <<16) | ((long)buff[1] <<8) | ((long)buff[2])) >> (8-BMP085_MODE)); // uncompensated pressure value
 
//calculate raw pressure
b6 = bmp085_rawtemperature - 4000;
x1 = (bmp085_regb2* (b6 * b6) >> 12) >> 11;
x2 = (bmp085_regac2 * b6) >> 11;
x3 = x1 + x2;
b3 = (((((long)bmp085_regac1) * 4 + x3) << BMP085_MODE) + 2) >> 2;
x1 = (bmp085_regac3 * b6) >> 13;
x2 = (bmp085_regb1 * ((b6 * b6) >> 12)) >> 16;
x3 = ((x1 + x2) + 2) >> 2;
b4 = (bmp085_regac4 * (uint32_t)(x3 + 32768)) >> 15;
b7 = ((uint32_t)up - b3) * (50000 >> BMP085_MODE);
p = b7 < 0x80000000 ? (b7 << 1) / b4 : (b7 / b4) << 1;
x1 = (p >> 8) * (p >> 8);
x1 = (x1 * 3038) >> 16;
x2 = (-7357 * p) >> 16;
bmp085_rawpressure = p + ((x1 + x2 + 3791) >> 4);
 
#if BMP085_FILTERPRESSURE == 1
bmp085_rawpressure = bmp085_avaragefilter(bmp085_rawpressure);
#endif
}
 
/*
* get celsius temperature
*/
double bmp085_gettemperature() {
bmp085_getrawtemperature();
double temperature = ((bmp085_rawtemperature + 8)>>4);
temperature = temperature /10;
return temperature;
}
 
/*
* get pressure
*/
int32_t bmp085_getpressure() {
bmp085_getrawpressure();
return bmp085_rawpressure + BMP085_UNITPAOFFSET;
}
 
/*
* get altitude
*/
double bmp085_getaltitude() {
bmp085_getrawpressure();
return ((1 - pow(bmp085_rawpressure/(double)101325, 0.1903 )) / 0.0000225577) + BMP085_UNITMOFFSET;
}
 
/*
* init bmp085
*/
void bmp085_init() {
#if BMP085_I2CINIT == 1
//init i2c
i2c_init();
_delay_us(10);
#endif
 
bmp085_getcalibration(); //get calibration data
bmp085_getrawtemperature(); //update raw temperature, at least the first time
 
#if BMP085_FILTERPRESSURE == 1
//initialize the avarage filter
uint8_t i=0;
for (i=0; i<BMP085_AVARAGECOEF; i++) {
bmp085_getrawpressure();
}
#endif
}
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/10DOF/bmp085.h
0,0 → 1,74
/*
bmp085 lib 0x01
 
copyright (c) Davide Gironi, 2012
 
Released under GPLv3.
Please refer to LICENSE file for licensing information.
 
References:
- this library is a porting of the bmp085driver 0.4 ardunio library
http://code.google.com/p/bmp085driver/
 
Notes:
- to compile with avrgcc you may define -lm flag for some math functions
*/
 
 
#ifndef BMP085_H_
#define BMP085_H_
 
#include <stdio.h>
#include <avr/io.h>
 
#define BMP085_ADDR (0x77<<1) //0x77 default I2C address
 
#define BMP085_I2CFLEURYPATH "i2cmaster.h" //define the path to i2c fleury lib
#define BMP085_I2CINIT 1 //init i2c
 
//registers
#define BMP085_REGAC1 0xAA
#define BMP085_REGAC2 0xAC
#define BMP085_REGAC3 0xAE
#define BMP085_REGAC4 0xB0
#define BMP085_REGAC5 0xB2
#define BMP085_REGAC6 0xB4
#define BMP085_REGB1 0xB6
#define BMP085_REGB2 0xB8
#define BMP085_REGMB 0xBA
#define BMP085_REGMC 0xBC
#define BMP085_REGMD 0xBE
#define BMP085_REGCONTROL 0xF4 //control
#define BMP085_REGCONTROLOUTPUT 0xF6 //output 0xF6=MSB, 0xF7=LSB, 0xF8=XLSB
#define BMP085_REGREADTEMPERATURE 0x2E //read temperature
#define BMP085_REGREADPRESSURE 0x34 //read pressure
 
//modes
#define BMP085_MODEULTRALOWPOWER 0 //oversampling=0, internalsamples=1, maxconvtimepressure=4.5ms, avgcurrent=3uA, RMSnoise_hPA=0.06, RMSnoise_m=0.5
#define BMP085_MODESTANDARD 1 //oversampling=1, internalsamples=2, maxconvtimepressure=7.5ms, avgcurrent=5uA, RMSnoise_hPA=0.05, RMSnoise_m=0.4
#define BMP085_MODEHIGHRES 2 //oversampling=2, internalsamples=4, maxconvtimepressure=13.5ms, avgcurrent=7uA, RMSnoise_hPA=0.04, RMSnoise_m=0.3
#define BMP085_MODEULTRAHIGHRES 3 //oversampling=3, internalsamples=8, maxconvtimepressure=25.5ms, avgcurrent=12uA, RMSnoise_hPA=0.03, RMSnoise_m=0.25
 
//autoupdate temperature enabled
#define BMP085_AUTOUPDATETEMP 1 //autoupdate temperature every read
 
//setup parameters
#define BMP085_MODE BMP085_MODEULTRAHIGHRES //define a mode
#define BMP085_UNITPAOFFSET 0 //define a unit offset (pa)
#define BMP085_UNITMOFFSET 0 //define a unit offset (m)
 
//avarage filter
#define BMP085_FILTERPRESSURE 1 //avarage filter for pressure
 
//variables
int bmp085_regac1, bmp085_regac2, bmp085_regac3, bmp085_regb1, bmp085_regb2, bmp085_regmb, bmp085_regmc, bmp085_regmd;
unsigned int bmp085_regac4, bmp085_regac5, bmp085_regac6;
long bmp085_rawtemperature, bmp085_rawpressure;
 
//functions
extern void bmp085_init();
extern int32_t bmp085_getpressure();
extern double bmp085_getaltitude();
extern double bmp085_gettemperature();
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/10DOF/hmc5883l.c
0,0 → 1,131
/*
hmc5883l lib 0x01
 
copyright (c) Davide Gironi, 2012
 
Released under GPLv3.
Please refer to LICENSE file for licensing information.
*/
//############################################################################
//# HISTORY hmc5883l.c
//#
//# 19.09.2015 cebra
//# - add: Library für HMC5883L Compass, GY-87 Sensorboard
//#
//############################################################################
 
#ifdef USE_KOMPASS
#include <stdlib.h>
#include <avr/io.h>
#include <util/delay.h>
 
#include "hmc5883l.h"
 
//path to i2c fleury lib
#include HMC5883L_I2CFLEURYPATH
 
static double hmc5883l_scale = 0;
 
/*
* init the hmc5883l
*/
void hmc5883l_init() {
#if HMC5883L_I2CINIT == 1
//init i2c
i2c_init();
_delay_us(10);
#endif
 
//set scale
hmc5883l_scale = 0;
uint8_t regValue = 0x00;
#if HMC5883L_SCALE == HMC5883L_SCALE088
regValue = 0x00;
hmc5883l_scale = 0.73;
#elif HMC5883L_SCALE == HMC5883L_SCALE13
regValue = 0x01;
hmc5883l_scale = 0.92;
#elif HMC5883L_SCALE == HMC5883L_SCALE19
regValue = 0x02;
hmc5883l_scale = 1.22;
#elif HMC5883L_SCALE == HMC5883L_SCALE25
regValue = 0x03;
hmc5883l_scale = 1.52;
#elif HMC5883L_SCALE == HMC5883L_SCALE40
regValue = 0x04;
hmc5883l_scale = 2.27;
#elif HMC5883L_SCALE == HMC5883L_SCALE47
regValue = 0x05;
hmc5883l_scale = 2.56;
#elif HMC5883L_SCALE == HMC5883L_SCALE56
regValue = 0x06;
hmc5883l_scale = 3.03;
#elif HMC5883L_SCALE == HMC5883L_SCALE81
regValue = 0x07;
hmc5883l_scale = 4.35;
#endif
 
//setting is in the top 3 bits of the register.
regValue = regValue << 5;
i2c_start_wait(HMC5883L_ADDR | I2C_WRITE);
i2c_write(HMC5883L_CONFREGB);
i2c_write(regValue);
i2c_stop();
 
//set measurement mode
i2c_start_wait(HMC5883L_ADDR | I2C_WRITE);
i2c_write(HMC5883L_MODEREG);
i2c_write(HMC5883L_MEASUREMODE);
i2c_stop();
}
 
/*
* get raw data
*/
void hmc5883l_getrawdata(int16_t *mxraw, int16_t *myraw, int16_t *mzraw) {
uint8_t i = 0;
uint8_t buff[6];
 
i2c_start_wait(HMC5883L_ADDR | I2C_WRITE);
i2c_write(HMC5883L_DATAREGBEGIN);
i2c_stop();
i2c_start_wait(HMC5883L_ADDR | I2C_READ);
for(i=0; i<6; i++) {
if(i==6-1)
buff[i] = i2c_readNak();
else
buff[i] = i2c_readAck();
}
i2c_stop();
 
*mxraw = (int16_t)((buff[0] << 8) | buff[1]);
*mzraw = (int16_t)((buff[2] << 8) | buff[3]);
*myraw = (int16_t)((buff[4] << 8) | buff[5]);
}
 
/*
* get scaled data
*/
void hmc5883l_getdata(double *mx, double *my, double *mz) {
int16_t mxraw = 0;
int16_t myraw = 0;
int16_t mzraw = 0;
hmc5883l_getrawdata(&mxraw, &myraw, &mzraw);
 
#if HMC5883L_CALIBRATED == 1
float mxt = mxraw - HMC5883L_OFFSETX;
float myt = myraw - HMC5883L_OFFSETY;
float mzt = mzraw - HMC5883L_OFFSETZ;
*mx = HMC5883L_GAINX1 * mxt + HMC5883L_GAINX2 * myt + HMC5883L_GAINX3 * mzt;
*my = HMC5883L_GAINY1 * mxt + HMC5883L_GAINY2 * myt + HMC5883L_GAINY3 * mzt;
*mz = HMC5883L_GAINZ1 * mxt + HMC5883L_GAINZ2 * myt + HMC5883L_GAINZ3 * mzt;
#else
*mx = mxraw * hmc5883l_scale;
*my = myraw * hmc5883l_scale;
*mz = mzraw * hmc5883l_scale;
#endif
 
 
 
}
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/10DOF/hmc5883l.h
0,0 → 1,71
/*
hmc5883l lib 0x01
 
copyright (c) Davide Gironi, 2012
 
Released under GPLv3.
Please refer to LICENSE file for licensing information.
 
References:
- HMC5883L Triple Axis Magnetometer Arduino Library
http://bildr.org/2012/02/hmc5883l_arduino/
*/
 
 
#ifndef HMC5883L_H_
#define HMC5883L_H_
 
//definitions
#define HMC5883L_ADDR (0x1E<<1) //device address
 
//i2c settings
#define HMC5883L_I2CFLEURYPATH "i2cmaster.h" //define the path to i2c fleury lib
#define HMC5883L_I2CINIT 1 //init i2c
 
//registers
#define HMC5883L_CONFREGA 0x00
#define HMC5883L_CONFREGB 0x01
#define HMC5883L_MODEREG 0x02
#define HMC5883L_DATAREGBEGIN 0x03
 
//setup measurement mode
#define HMC5883L_MEASURECONTINOUS 0x00
#define HMC5883L_MEASURESINGLESHOT 0x01
#define HMC5883L_MEASUREIDLE 0x03
#define HMC5883L_MEASUREMODE HMC5883L_MEASURECONTINOUS
 
//setup scale
#define HMC5883L_SCALE088 1 //0.88
#define HMC5883L_SCALE13 2 //1.3
#define HMC5883L_SCALE19 3 //1.9
#define HMC5883L_SCALE25 4 //2.5
#define HMC5883L_SCALE40 5 //4.0
#define HMC5883L_SCALE47 6 //4.7
#define HMC5883L_SCALE56 7 //5.6
#define HMC5883L_SCALE81 8 //8.1
#define HMC5883L_SCALE HMC5883L_SCALE13
 
#define HMC5883L_CALIBRATED 1 //enable this if this magn is calibrated
 
//calibration values
#if HMC5883L_CALIBRATED == 1
#define HMC5883L_OFFSETX -99.7
#define HMC5883L_OFFSETY -154.0
#define HMC5883L_OFFSETZ -22.7
#define HMC5883L_GAINX1 0.952017
#define HMC5883L_GAINX2 0.00195895
#define HMC5883L_GAINX3 0.0139661
#define HMC5883L_GAINY1 0.00195895
#define HMC5883L_GAINY2 0.882824
#define HMC5883L_GAINY3 0.00760243
#define HMC5883L_GAINZ1 0.0139661
#define HMC5883L_GAINZ2 0.00760243
#define HMC5883L_GAINZ3 0.995365
#endif
 
//functions
extern void hmc5883l_init();
extern void hmc5883l_getrawdata(int16_t *mxraw, int16_t *myraw, int16_t *mzraw);
extern void hmc5883l_getdata(double *mx, double *my, double *mz);
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/10DOF/mpu6050.c
0,0 → 1,694
/*
MPU6050 lib 0x02
 
copyright (c) Davide Gironi, 2012
 
Released under GPLv3.
Please refer to LICENSE file for licensing information.
*/
//############################################################################
//# HISTORY mpu6050.c
//#
//# 19.09.2015 cebra
//# - add: Library für MPU6050 Gyro, ACC, GY-87 Sensorboard
//#
//############################################################################
 
#ifdef USE_KOMPASS
#include <stdlib.h>
#include <string.h>
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include <util/delay.h>
 
#include "mpu6050.h"
 
#if MPU6050_GETATTITUDE == 1 || MPU6050_GETATTITUDE == 2
#include <math.h> //include libm
#endif
 
//path to i2c fleury lib
#include "i2cmaster.h"
 
volatile uint8_t buffer[14];
 
/*
* read bytes from chip register
*/
int8_t mpu6050_readBytes(uint8_t regAddr, uint8_t length, uint8_t *data) {
uint8_t i = 0;
int8_t count = 0;
if(length > 0) {
//request register
i2c_start(MPU6050_ADDR | I2C_WRITE);
i2c_write(regAddr);
_delay_us(10);
//read data
i2c_start(MPU6050_ADDR | I2C_READ);
for(i=0; i<length; i++) {
count++;
if(i==length-1)
data[i] = i2c_readNak();
else
data[i] = i2c_readAck();
}
i2c_stop();
}
return count;
}
 
/*
* read 1 byte from chip register
*/
int8_t mpu6050_readByte(uint8_t regAddr, uint8_t *data) {
return mpu6050_readBytes(regAddr, 1, data);
}
 
/*
* write bytes to chip register
*/
void mpu6050_writeBytes(uint8_t regAddr, uint8_t length, uint8_t* data) {
if(length > 0) {
//write data
i2c_start(MPU6050_ADDR | I2C_WRITE);
i2c_write(regAddr); //reg
for (uint8_t i = 0; i < length; i++) {
i2c_write((uint8_t) data[i]);
}
i2c_stop();
}
}
 
/*
* write 1 byte to chip register
*/
void mpu6050_writeByte(uint8_t regAddr, uint8_t data) {
return mpu6050_writeBytes(regAddr, 1, &data);
}
 
/*
* read bits from chip register
*/
int8_t mpu6050_readBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data) {
// 01101001 read byte
// 76543210 bit numbers
// xxx args: bitStart=4, length=3
// 010 masked
// -> 010 shifted
int8_t count = 0;
if(length > 0) {
uint8_t b;
if ((count = mpu6050_readByte(regAddr, &b)) != 0) {
uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
b &= mask;
b >>= (bitStart - length + 1);
*data = b;
}
}
return count;
}
 
/*
* read 1 bit from chip register
*/
int8_t mpu6050_readBit(uint8_t regAddr, uint8_t bitNum, uint8_t *data) {
uint8_t b;
uint8_t count = mpu6050_readByte(regAddr, &b);
*data = b & (1 << bitNum);
return count;
}
 
/*
* write bit/bits to chip register
*/
void mpu6050_writeBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data) {
// 010 value to write
// 76543210 bit numbers
// xxx args: bitStart=4, length=3
// 00011100 mask byte
// 10101111 original value (sample)
// 10100011 original & ~mask
// 10101011 masked | value
if(length > 0) {
uint8_t b = 0;
if (mpu6050_readByte(regAddr, &b) != 0) { //get current data
uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1);
data <<= (bitStart - length + 1); // shift data into correct position
data &= mask; // zero all non-important bits in data
b &= ~(mask); // zero all important bits in existing byte
b |= data; // combine data with existing byte
mpu6050_writeByte(regAddr, b);
}
}
}
 
/*
* write one bit to chip register
*/
void mpu6050_writeBit(uint8_t regAddr, uint8_t bitNum, uint8_t data) {
uint8_t b;
mpu6050_readByte(regAddr, &b);
b = (data != 0) ? (b | (1 << bitNum)) : (b & ~(1 << bitNum));
mpu6050_writeByte(regAddr, b);
}
 
#if MPU6050_GETATTITUDE == 2
/*
* write word/words to chip register
*/
void mpu6050_writeWords(uint8_t regAddr, uint8_t length, uint16_t* data) {
if(length > 0) {
uint8_t i = 0;
//write data
i2c_start(MPU6050_ADDR | I2C_WRITE);
i2c_write(regAddr); //reg
for (i = 0; i < length * 2; i++) {
i2c_write((uint8_t)(data[i++] >> 8)); // send MSB
i2c_write((uint8_t)data[i]); // send LSB
}
i2c_stop();
}
}
 
/*
* set a chip memory bank
*/
void mpu6050_setMemoryBank(uint8_t bank, uint8_t prefetchEnabled, uint8_t userBank) {
bank &= 0x1F;
if (userBank) bank |= 0x20;
if (prefetchEnabled) bank |= 0x40;
mpu6050_writeByte(MPU6050_RA_BANK_SEL, bank);
}
 
/*
* set memory start address
*/
void mpu6050_setMemoryStartAddress(uint8_t address) {
mpu6050_writeByte(MPU6050_RA_MEM_START_ADDR, address);
}
 
/*
* read a memory block
*/
void mpu6050_readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address) {
mpu6050_setMemoryBank(bank, 0, 0);
mpu6050_setMemoryStartAddress(address);
uint8_t chunkSize;
for (uint16_t i = 0; i < dataSize;) {
// determine correct chunk size according to bank position and data size
chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
 
// make sure we don't go past the data size
if (i + chunkSize > dataSize) chunkSize = dataSize - i;
 
// make sure this chunk doesn't go past the bank boundary (256 bytes)
if (chunkSize > 256 - address) chunkSize = 256 - address;
 
// read the chunk of data as specified
mpu6050_readBytes(MPU6050_RA_MEM_R_W, chunkSize, data + i);
 
// increase byte index by [chunkSize]
i += chunkSize;
 
// uint8_t automatically wraps to 0 at 256
address += chunkSize;
 
// if we aren't done, update bank (if necessary) and address
if (i < dataSize) {
if (address == 0) bank++;
mpu6050_setMemoryBank(bank, 0, 0);
mpu6050_setMemoryStartAddress(address);
}
}
}
 
/*
* write a memory block
*/
uint8_t mpu6050_writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, uint8_t verify, uint8_t useProgMem) {
mpu6050_setMemoryBank(bank, 0, 0);
mpu6050_setMemoryStartAddress(address);
uint8_t chunkSize;
uint8_t *verifyBuffer = 0;
uint8_t *progBuffer = 0;
uint16_t i;
uint8_t j;
if (verify) verifyBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE);
if (useProgMem) progBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE);
for (i = 0; i < dataSize;) {
// determine correct chunk size according to bank position and data size
chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE;
 
// make sure we don't go past the data size
if (i + chunkSize > dataSize) chunkSize = dataSize - i;
 
// make sure this chunk doesn't go past the bank boundary (256 bytes)
if (chunkSize > 256 - address) chunkSize = 256 - address;
 
if (useProgMem) {
// write the chunk of data as specified
for (j = 0; j < chunkSize; j++) progBuffer[j] = pgm_read_byte(data + i + j);
} else {
// write the chunk of data as specified
progBuffer = (uint8_t *)data + i;
}
 
mpu6050_writeBytes(MPU6050_RA_MEM_R_W, chunkSize, progBuffer);
 
// verify data if needed
if (verify && verifyBuffer) {
mpu6050_setMemoryBank(bank, 0, 0);
mpu6050_setMemoryStartAddress(address);
mpu6050_readBytes(MPU6050_RA_MEM_R_W, chunkSize, verifyBuffer);
if (memcmp(progBuffer, verifyBuffer, chunkSize) != 0) {
free(verifyBuffer);
if (useProgMem) free(progBuffer);
return 0; // uh oh.
}
}
 
// increase byte index by [chunkSize]
i += chunkSize;
 
// uint8_t automatically wraps to 0 at 256
address += chunkSize;
 
// if we aren't done, update bank (if necessary) and address
if (i < dataSize) {
if (address == 0) bank++;
mpu6050_setMemoryBank(bank, 0, 0);
mpu6050_setMemoryStartAddress(address);
}
}
if (verify) free(verifyBuffer);
if (useProgMem) free(progBuffer);
return 1;
}
 
/*
* write a dmp configuration set
*/
uint8_t mpu6050_writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, uint8_t useProgMem) {
uint8_t *progBuffer = 0;
uint8_t success, special;
uint16_t i, j;
if (useProgMem) {
progBuffer = (uint8_t *)malloc(8); // assume 8-byte blocks, realloc later if necessary
}
 
// config set data is a long string of blocks with the following structure:
// [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]]
uint8_t bank, offset, length;
for (i = 0; i < dataSize;) {
if (useProgMem) {
bank = pgm_read_byte(data + i++);
offset = pgm_read_byte(data + i++);
length = pgm_read_byte(data + i++);
} else {
bank = data[i++];
offset = data[i++];
length = data[i++];
}
 
// write data or perform special action
if (length > 0) {
// regular block of data to write
if (useProgMem) {
if (sizeof(progBuffer) < length) progBuffer = (uint8_t *)realloc(progBuffer, length);
for (j = 0; j < length; j++) progBuffer[j] = pgm_read_byte(data + i + j);
} else {
progBuffer = (uint8_t *)data + i;
}
success = mpu6050_writeMemoryBlock(progBuffer, length, bank, offset, 1, 0);
i += length;
} else {
// special instruction
// NOTE: this kind of behavior (what and when to do certain things)
// is totally undocumented. This code is in here based on observed
// behavior only, and exactly why (or even whether) it has to be here
// is anybody's guess for now.
if (useProgMem) {
special = pgm_read_byte(data + i++);
} else {
special = data[i++];
}
if (special == 0x01) {
// enable DMP-related interrupts
 
//mpu6050_writeBit(MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, 1); //setIntZeroMotionEnabled
//mpu6050_writeBit(MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, 1); //setIntFIFOBufferOverflowEnabled
//mpu6050_writeBit(MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, 1); //setIntDMPEnabled
mpu6050_writeByte(MPU6050_RA_INT_ENABLE, 0x32); // single operation
 
success = 1;
} else {
// unknown special command
success = 0;
}
}
 
if (!success) {
if (useProgMem) free(progBuffer);
return 0; // uh oh
}
}
if (useProgMem) free(progBuffer);
return 1;
}
 
/*
* get the fifo count
*/
uint16_t mpu6050_getFIFOCount(void) {
mpu6050_readBytes(MPU6050_RA_FIFO_COUNTH, 2, (uint8_t *)buffer);
return (((uint16_t)buffer[0]) << 8) | buffer[1];
}
 
/*
* read fifo bytes
*/
void mpu6050_getFIFOBytes(uint8_t *data, uint8_t length) {
mpu6050_readBytes(MPU6050_RA_FIFO_R_W, length, data);
}
 
/*
* get the interrupt status
*/
uint8_t mpu6050_getIntStatus(void) {
mpu6050_readByte(MPU6050_RA_INT_STATUS, (uint8_t *)buffer);
return buffer[0];
}
 
/*
* reset fifo
*/
void mpu6050_resetFIFO(void) {
mpu6050_writeBit(MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_RESET_BIT, 1);
}
 
/*
* get gyro offset X
*/
int8_t mpu6050_getXGyroOffset(void) {
mpu6050_readBits(MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, (uint8_t *)buffer);
return buffer[0];
}
 
/*
* set gyro offset X
*/
void mpu6050_setXGyroOffset(int8_t offset) {
mpu6050_writeBits(MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
}
 
/*
* get gyro offset Y
*/
int8_t mpu6050_getYGyroOffset(void) {
mpu6050_readBits(MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, (uint8_t *)buffer);
return buffer[0];
}
 
/*
* set gyro offset Y
*/
void mpu6050_setYGyroOffset(int8_t offset) {
mpu6050_writeBits(MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
}
 
/*
* get gyro offset Z
*/
int8_t mpu6050_getZGyroOffset(void) {
mpu6050_readBits(MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, (uint8_t *)buffer);
return buffer[0];
}
 
/*
* set gyro offset Z
*/
void mpu6050_setZGyroOffset(int8_t offset) {
mpu6050_writeBits(MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset);
}
#endif
 
/*
* set sleep disabled
*/
void mpu6050_setSleepDisabled() {
mpu6050_writeBit(MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, 0);
}
 
/*
* set sleep enabled
*/
void mpu6050_setSleepEnabled(void) {
mpu6050_writeBit(MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, 1);
}
 
 
/*
* test connectino to chip
*/
uint8_t mpu6050_testConnection(void) {
mpu6050_readBits(MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, (uint8_t *)buffer);
if(buffer[0] == 0x34)
return 1;
else
return 0;
}
 
/*
* initialize the accel and gyro
*/
void mpu6050_init(void) {
//allow mpu6050 chip clocks to start up
_delay_ms(100);
 
//set sleep disabled
mpu6050_setSleepDisabled();
//wake up delay needed sleep disabled
_delay_ms(10);
 
//set clock source
// it is highly recommended that the device be configured to use one of the gyroscopes (or an external clock source)
// as the clock reference for improved stability
mpu6050_writeBits(MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, MPU6050_CLOCK_PLL_XGYRO);
//set DLPF bandwidth to 42Hz
mpu6050_writeBits(MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, MPU6050_DLPF_BW_42);
//set sampe rate
mpu6050_writeByte(MPU6050_RA_SMPLRT_DIV, 4); //1khz / (1 + 4) = 200Hz
//set gyro range
mpu6050_writeBits(MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, MPU6050_GYRO_FS);
//set accel range
mpu6050_writeBits(MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, MPU6050_ACCEL_FS);
 
#if MPU6050_GETATTITUDE == 1
#error "Do not enable timer 0 it is in use elsewhere!"
//MPU6050_TIMER0INIT
#endif
}
 
//can not accept many request if we alreay have getattitude requests
/*
* get raw data
*/
void mpu6050_getRawData(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz) {
mpu6050_readBytes(MPU6050_RA_ACCEL_XOUT_H, 14, (uint8_t *)buffer);
 
*ax = (((int16_t)buffer[0]) << 8) | buffer[1];
*ay = (((int16_t)buffer[2]) << 8) | buffer[3];
*az = (((int16_t)buffer[4]) << 8) | buffer[5];
*gx = (((int16_t)buffer[8]) << 8) | buffer[9];
*gy = (((int16_t)buffer[10]) << 8) | buffer[11];
*gz = (((int16_t)buffer[12]) << 8) | buffer[13];
}
 
/*
* get raw data converted to g and deg/sec values
*/
void mpu6050_getConvData(double* axg, double* ayg, double* azg, double* gxds, double* gyds, double* gzds) {
int16_t ax = 0;
int16_t ay = 0;
int16_t az = 0;
int16_t gx = 0;
int16_t gy = 0;
int16_t gz = 0;
mpu6050_getRawData(&ax, &ay, &az, &gx, &gy, &gz);
 
#if MPU6050_CALIBRATEDACCGYRO == 1
*axg = (double)(ax-MPU6050_AXOFFSET)/MPU6050_AXGAIN;
*ayg = (double)(ay-MPU6050_AYOFFSET)/MPU6050_AYGAIN;
*azg = (double)(az-MPU6050_AZOFFSET)/MPU6050_AZGAIN;
*gxds = (double)(gx-MPU6050_GXOFFSET)/MPU6050_GXGAIN;
*gyds = (double)(gy-MPU6050_GYOFFSET)/MPU6050_GYGAIN;
*gzds = (double)(gz-MPU6050_GZOFFSET)/MPU6050_GZGAIN;
#else
*axg = (double)(ax)/MPU6050_AGAIN;
*ayg = (double)(ay)/MPU6050_AGAIN;
*azg = (double)(az)/MPU6050_AGAIN;
*gxds = (double)(gx)/MPU6050_GGAIN;
*gyds = (double)(gy)/MPU6050_GGAIN;
*gzds = (double)(gz)/MPU6050_GGAIN;
#endif
}
 
#if MPU6050_GETATTITUDE == 1
 
volatile float q0 = 1.0f, q1 = 0.0f, q2 = 0.0f, q3 = 0.0f;
volatile float integralFBx = 0.0f, integralFBy = 0.0f, integralFBz = 0.0f;
/*
* Mahony update function (for 6DOF)
*/
void mpu6050_mahonyUpdate(float gx, float gy, float gz, float ax, float ay, float az) {
float norm;
float halfvx, halfvy, halfvz;
float halfex, halfey, halfez;
float qa, qb, qc;
 
// Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer normalisation)
if(!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) {
 
// Normalise accelerometer measurement
norm = sqrt(ax * ax + ay * ay + az * az);
ax /= norm;
ay /= norm;
az /= norm;
 
// Estimated direction of gravity and vector perpendicular to magnetic flux
halfvx = q1 * q3 - q0 * q2;
halfvy = q0 * q1 + q2 * q3;
halfvz = q0 * q0 - 0.5f + q3 * q3;
 
// Error is sum of cross product between estimated and measured direction of gravity
halfex = (ay * halfvz - az * halfvy);
halfey = (az * halfvx - ax * halfvz);
halfez = (ax * halfvy - ay * halfvx);
 
// Compute and apply integral feedback if enabled
if(mpu6050_mahonytwoKiDef > 0.0f) {
integralFBx += mpu6050_mahonytwoKiDef * halfex * (1.0f / mpu6050_mahonysampleFreq); // integral error scaled by Ki
integralFBy += mpu6050_mahonytwoKiDef * halfey * (1.0f / mpu6050_mahonysampleFreq);
integralFBz += mpu6050_mahonytwoKiDef * halfez * (1.0f / mpu6050_mahonysampleFreq);
gx += integralFBx; // apply integral feedback
gy += integralFBy;
gz += integralFBz;
} else {
integralFBx = 0.0f; // prevent integral windup
integralFBy = 0.0f;
integralFBz = 0.0f;
}
 
// Apply proportional feedback
gx += mpu6050_mahonytwoKpDef * halfex;
gy += mpu6050_mahonytwoKpDef * halfey;
gz += mpu6050_mahonytwoKpDef * halfez;
}
 
// Integrate rate of change of quaternion
gx *= (0.5f * (1.0f / mpu6050_mahonysampleFreq)); // pre-multiply common factors
gy *= (0.5f * (1.0f / mpu6050_mahonysampleFreq));
gz *= (0.5f * (1.0f / mpu6050_mahonysampleFreq));
qa = q0;
qb = q1;
qc = q2;
q0 += (-qb * gx - qc * gy - q3 * gz);
q1 += (qa * gx + qc * gz - q3 * gy);
q2 += (qa * gy - qb * gz + q3 * gx);
q3 += (qa * gz + qb * gy - qc * gx);
 
// Normalise quaternion
norm = sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
q0 /= norm;
q1 /= norm;
q2 /= norm;
q3 /= norm;
}
 
/*
* update quaternion
*/
void mpu6050_updateQuaternion(void) {
int16_t ax = 0;
int16_t ay = 0;
int16_t az = 0;
int16_t gx = 0;
int16_t gy = 0;
int16_t gz = 0;
double axg = 0;
double ayg = 0;
double azg = 0;
double gxrs = 0;
double gyrs = 0;
double gzrs = 0;
 
//get raw data
while(1) {
mpu6050_readBit(MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DATA_RDY_BIT, (uint8_t *)buffer);
if(buffer[0])
break;
_delay_us(10);
}
 
mpu6050_readBytes(MPU6050_RA_ACCEL_XOUT_H, 14, (uint8_t *)buffer);
ax = (((int16_t)buffer[0]) << 8) | buffer[1];
ay = (((int16_t)buffer[2]) << 8) | buffer[3];
az = (((int16_t)buffer[4]) << 8) | buffer[5];
gx = (((int16_t)buffer[8]) << 8) | buffer[9];
gy = (((int16_t)buffer[10]) << 8) | buffer[11];
gz = (((int16_t)buffer[12]) << 8) | buffer[13];
 
#if MPU6050_CALIBRATEDACCGYRO == 1
axg = (double)(ax-MPU6050_AXOFFSET)/MPU6050_AXGAIN;
ayg = (double)(ay-MPU6050_AYOFFSET)/MPU6050_AYGAIN;
azg = (double)(az-MPU6050_AZOFFSET)/MPU6050_AZGAIN;
gxrs = (double)(gx-MPU6050_GXOFFSET)/MPU6050_GXGAIN*0.01745329; //degree to radians
gyrs = (double)(gy-MPU6050_GYOFFSET)/MPU6050_GYGAIN*0.01745329; //degree to radians
gzrs = (double)(gz-MPU6050_GZOFFSET)/MPU6050_GZGAIN*0.01745329; //degree to radians
#else
axg = (double)(ax)/MPU6050_AGAIN;
ayg = (double)(ay)/MPU6050_AGAIN;
azg = (double)(az)/MPU6050_AGAIN;
gxrs = (double)(gx)/MPU6050_GGAIN*0.01745329; //degree to radians
gyrs = (double)(gy)/MPU6050_GGAIN*0.01745329; //degree to radians
gzrs = (double)(gz)/MPU6050_GGAIN*0.01745329; //degree to radians
#endif
 
//compute data
mpu6050_mahonyUpdate(gxrs, gyrs, gzrs, axg, ayg, azg);
}
 
/*
* update timer for attitude
*/
ISR(TIMER0_OVF_vect) {
mpu6050_updateQuaternion();
}
 
/*
* get quaternion
*/
void mpu6050_getQuaternion(double *qw, double *qx, double *qy, double *qz) {
*qw = q0;
*qx = q1;
*qy = q2;
*qz = q3;
}
 
/*
* get euler angles
* aerospace sequence, to obtain sensor attitude:
* 1. rotate around sensor Z plane by yaw
* 2. rotate around sensor Y plane by pitch
* 3. rotate around sensor X plane by roll
*/
void mpu6050_getRollPitchYaw(double *roll, double *pitch, double *yaw) {
*yaw = atan2(2*q1*q2 - 2*q0*q3, 2*q0*q0 + 2*q1*q1 - 1);
*pitch = -asin(2*q1*q3 + 2*q0*q2);
*roll = atan2(2*q2*q3 - 2*q0*q1, 2*q0*q0 + 2*q3*q3 - 1);
}
 
#endif
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/10DOF/mpu6050.h
0,0 → 1,174
/*
MPU6050 lib 0x02
 
copyright (c) Davide Gironi, 2012
 
Released under GPLv3.
Please refer to LICENSE file for licensing information.
 
References:
- most of the code is a port of the arduino mpu6050 library by Jeff Rowberg
https://github.com/jrowberg/i2cdevlib
- Mahony complementary filter for attitude estimation
http://www.x-io.co.uk
*/
 
 
#ifndef MPU6050_H_
#define MPU6050_H_
 
#include <avr/io.h>
#include "mpu6050registers.h"
 
#ifdef __cplusplus
extern "C" {
#endif
 
//i2c settings
#define MPU6050_I2CFLEURYPATH "i2cmaster.h" //define the path to i2c fleury lib
#define MPU6050_I2CINIT 0 //init i2c
 
//definitions
#define MPU6050_ADDR (0x68 <<1) //device address - 0x68 pin low (GND), 0x69 pin high (VCC)
 
//enable the getattitude functions
//because we do not have a magnetometer, we have to start the chip always in the same position
//then to obtain your object attitude you have to apply the aerospace sequence
//0 disabled
//1 mahony filter
//2 dmp chip processor
#define MPU6050_GETATTITUDE 2
 
//definitions for raw data
//gyro and acc scale
#define MPU6050_GYRO_FS MPU6050_GYRO_FS_2000
#define MPU6050_ACCEL_FS MPU6050_ACCEL_FS_2
 
#define MPU6050_GYRO_LSB_250 131.0
#define MPU6050_GYRO_LSB_500 65.5
#define MPU6050_GYRO_LSB_1000 32.8
#define MPU6050_GYRO_LSB_2000 16.4
#if MPU6050_GYRO_FS == MPU6050_GYRO_FS_250
#define MPU6050_GGAIN MPU6050_GYRO_LSB_250
#elif MPU6050_GYRO_FS == MPU6050_GYRO_FS_500
#define MPU6050_GGAIN MPU6050_GYRO_LSB_500
#elif MPU6050_GYRO_FS == MPU6050_GYRO_FS_1000
#define MPU6050_GGAIN MPU6050_GYRO_LSB_1000
#elif MPU6050_GYRO_FS == MPU6050_GYRO_FS_2000
#define MPU6050_GGAIN MPU6050_GYRO_LSB_2000
#endif
 
#define MPU6050_ACCEL_LSB_2 16384.0
#define MPU6050_ACCEL_LSB_4 8192.0
#define MPU6050_ACCEL_LSB_8 4096.0
#define MPU6050_ACCEL_LSB_16 2048.0
#if MPU6050_ACCEL_FS == MPU6050_ACCEL_FS_2
#define MPU6050_AGAIN MPU6050_ACCEL_LSB_2
#elif MPU6050_ACCEL_FS == MPU6050_ACCEL_FS_4
#define MPU6050_AGAIN MPU6050_ACCEL_LSB_4
#elif MPU6050_ACCEL_FS == MPU6050_ACCEL_FS_8
#define MPU6050_AGAIN MPU6050_ACCEL_LSB_8
#elif MPU6050_ACCEL_FS == MPU6050_ACCEL_FS_16
#define MPU6050_AGAIN MPU6050_ACCEL_LSB_16
#endif
 
#define MPU6050_CALIBRATEDACCGYRO 1 //set to 1 if is calibrated
#if MPU6050_CALIBRATEDACCGYRO == 1
#define MPU6050_AXOFFSET 0
#define MPU6050_AYOFFSET 0
#define MPU6050_AZOFFSET 0
#define MPU6050_AXGAIN 16384.0
#define MPU6050_AYGAIN 16384.0
#define MPU6050_AZGAIN 16384.0
#define MPU6050_GXOFFSET -42
#define MPU6050_GYOFFSET 9
#define MPU6050_GZOFFSET -29
#define MPU6050_GXGAIN 16.4
#define MPU6050_GYGAIN 16.4
#define MPU6050_GZGAIN 16.4
#endif
 
//definitions for attitude 1 function estimation
#if MPU6050_GETATTITUDE == 1
#error "GETATTITUDE == 1 is not supported!"
//setup timer0 overflow event and define madgwickAHRSsampleFreq equal to timer0 frequency
//timerfreq = (FCPU / prescaler) / timerscale
// timerscale 8-bit = 256
// es. 61 = (16000000 / 1024) / 256
#define MPU6050_TIMER0INIT TCCR0B |=(1<<CS02)|(1<<CS00); TIMSK0 |=(1<<TOIE0);
#define mpu6050_mahonysampleFreq 61.0f // sample frequency in Hz
#define mpu6050_mahonytwoKpDef (2.0f * 0.5f) // 2 * proportional gain
#define mpu6050_mahonytwoKiDef (2.0f * 0.1f) // 2 * integral gain
#endif
 
 
#if MPU6050_GETATTITUDE == 2
//dmp definitions
//packet size
#define MPU6050_DMP_dmpPacketSize 42
//define INT0 rise edge interrupt
#define MPU6050_DMP_INT0SETUP EICRA |= (1<<ISC01) | (1<<ISC00)
//define enable and disable INT0 rise edge interrupt
#define MPU6050_DMP_INT0DISABLE EIMSK &= ~(1<<INT0)
#define MPU6050_DMP_INT0ENABLE EIMSK |= (1<<INT0)
extern volatile uint8_t mpu6050_mpuInterrupt;
#endif
 
//functions
extern void mpu6050_init(void);
extern uint8_t mpu6050_testConnection(void);
 
#if MPU6050_GETATTITUDE == 0
extern void mpu6050_getRawData(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
extern void mpu6050_getConvData(double* axg, double* ayg, double* azg, double* gxds, double* gyds, double* gzds);
#endif
 
extern void mpu6050_setSleepDisabled(void);
extern void mpu6050_setSleepEnabled(void);
 
extern int8_t mpu6050_readBytes(uint8_t regAddr, uint8_t length, uint8_t *data);
extern int8_t mpu6050_readByte(uint8_t regAddr, uint8_t *data);
extern void mpu6050_writeBytes(uint8_t regAddr, uint8_t length, uint8_t* data);
extern void mpu6050_writeByte(uint8_t regAddr, uint8_t data);
extern int8_t mpu6050_readBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data);
extern int8_t mpu6050_readBit(uint8_t regAddr, uint8_t bitNum, uint8_t *data);
extern void mpu6050_writeBits(uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data);
extern void mpu6050_writeBit(uint8_t regAddr, uint8_t bitNum, uint8_t data);
 
#if MPU6050_GETATTITUDE == 1
extern void mpu6050_updateQuaternion(void);
extern void mpu6050_getQuaternion(double *qw, double *qx, double *qy, double *qz);
extern void mpu6050_getRollPitchYaw(double *pitch, double *roll, double *yaw);
#endif
 
#if MPU6050_GETATTITUDE == 2
extern void mpu6050_writeWords(uint8_t regAddr, uint8_t length, uint16_t* data);
extern void mpu6050_setMemoryBank(uint8_t bank, uint8_t prefetchEnabled, uint8_t userBank);
extern void mpu6050_setMemoryStartAddress(uint8_t address);
extern void mpu6050_readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address);
extern uint8_t mpu6050_writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, uint8_t verify, uint8_t useProgMem);
extern uint8_t mpu6050_writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, uint8_t useProgMem);
extern uint16_t mpu6050_getFIFOCount(void);
extern void mpu6050_getFIFOBytes(uint8_t *data, uint8_t length);
extern uint8_t mpu6050_getIntStatus(void);
extern void mpu6050_resetFIFO();
extern int8_t mpu6050_getXGyroOffset(void);
extern void mpu6050_setXGyroOffset(int8_t offset);
extern int8_t mpu6050_getYGyroOffset(void);
extern void mpu6050_setYGyroOffset(int8_t offset);
extern int8_t mpu6050_getZGyroOffset(void);
extern void mpu6050_setZGyroOffset(int8_t offset);
//base dmp
extern uint8_t mpu6050_dmpInitialize(void);
extern void mpu6050_dmpEnable(void);
extern void mpu6050_dmpDisable(void);
extern void mpu6050_getQuaternion(const uint8_t* packet, double *qw, double *qx, double *qy, double *qz);
extern void mpu6050_getRollPitchYaw(double qw, double qx, double qy, double qz, double *roll, double *pitch, double *yaw);
extern uint8_t mpu6050_getQuaternionWait(double *qw, double *qx, double *qy, double *qz);
#endif
 
#ifdef __cplusplus
}
#endif
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/10DOF/mpu6050dmp6.c
0,0 → 1,495
/*
MPU6050 lib 0x02
 
copyright (c) Davide Gironi, 2012
 
Released under GPLv3.
Please refer to LICENSE file for licensing information.
*/
 
//############################################################################
//# HISTORY mpu6050dmp6.c
//#
//# 19.09.2015 cebra
//# - add: Library für MPU6050 Gyro, ACC, DMP-Routinen für IMU, GY-87 Sensorboard
//#
//############################################################################
 
#ifdef USE_KOMPASS
/*
* This file contains all the functions needed to process 6-axis orientation by the internal chip processor
*/
 
//to enable get roll, pitch and yaw function we include the math function
//if some error appears we must add -lm and -lc to C linker, the linker line should become somethink like this
//${COMMAND} -lm ${FLAGS} ${OUTPUT_FLAG} ${OUTPUT_PREFIX}${OUTPUT} ${INPUTS} -lc
 
 
#include "mpu6050.h"
 
#if MPU6050_GETATTITUDE == 2
 
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include <util/delay.h>
#include <math.h> //include libm
 
#define MPU6050_DMP_CODE_SIZE 1929
#define MPU6050_DMP_CONFIG_SIZE 192
#define MPU6050_DMP_UPDATES_SIZE 47
 
volatile uint8_t mpu6050_mpuInterrupt = 0;
uint8_t *dmpPacketBuffer;
uint16_t mpu6050_fifoCount = 0;
uint8_t mpu6050_mpuIntStatus = 0;
uint8_t mpu6050_fifoBuffer[64];
 
 
/* ================================================================================================ *
| Default MotionApps v2.0 42-byte FIFO packet structure: |
| |
| [QUAT W][ ][QUAT X][ ][QUAT Y][ ][QUAT Z][ ][GYRO X][ ][GYRO Y][ ] |
| 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 |
| |
| [GYRO Z][ ][ACC X ][ ][ACC Y ][ ][ACC Z ][ ][ ] |
| 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 |
* ================================================================================================ */
 
// this block of memory gets written to the MPU on start-up, and it seems
// to be volatile memory, so it has to be done each time (it only takes ~1
// second though)
const unsigned char mpu6050_dmpMemory[MPU6050_DMP_CODE_SIZE] PROGMEM = {
// bank 0, 256 bytes
0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00,
0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01,
0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01,
0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00,
0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00,
0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82,
0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00,
0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0,
0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC,
0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4,
0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10,
 
// bank 1, 256 bytes
0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00,
0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8,
0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7,
0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C,
0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C,
0x80, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0,
 
// bank 2, 256 bytes
0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x01, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00,
0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
 
// bank 3, 256 bytes
0xD8, 0xDC, 0xBA, 0xA2, 0xF1, 0xDE, 0xB2, 0xB8, 0xB4, 0xA8, 0x81, 0x91, 0xF7, 0x4A, 0x90, 0x7F,
0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA, 0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2,
0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80, 0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF,
0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0, 0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C,
0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1, 0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1,
0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3, 0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01,
0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88, 0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80,
0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF, 0xF2, 0xAA, 0xC5, 0xCD, 0xC7, 0xA9, 0x0C,
0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89, 0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80,
0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9, 0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E,
0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A, 0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9,
0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11, 0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24,
0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55, 0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xAF, 0xF0,
0x00, 0x28, 0x50, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xD9, 0xFA, 0xA3, 0x86,
0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1,
0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86,
 
// bank 4, 256 bytes
0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA,
0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C,
0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8,
0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3,
0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84,
0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5,
0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3,
0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1,
0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5,
0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D,
0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D,
0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A,
0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8,
0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87,
 
// bank 5, 256 bytes
0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8,
0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68,
0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D,
0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94,
0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA,
0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56,
0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9,
0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA,
0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0xA8, 0x8A,
0x9A, 0xF5, 0x20, 0xAA, 0xDA, 0xDF, 0xD8, 0xA8, 0x40, 0xAA, 0xD0, 0xDA, 0xDE, 0xD8, 0xA8, 0x60,
0xAA, 0xDA, 0xD0, 0xDF, 0xD8, 0xF1, 0x97, 0x86, 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97,
0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40, 0xB8, 0xB0, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04,
0x28, 0x51, 0x79, 0x1D, 0x30, 0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78,
0x78, 0x9B, 0xF1, 0x1A, 0xB0, 0xF0, 0x8A, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x8B, 0x29, 0x51, 0x79,
0x8A, 0x24, 0x70, 0x59, 0x8B, 0x20, 0x58, 0x71, 0x8A, 0x44, 0x69, 0x38, 0x8B, 0x39, 0x40, 0x68,
0x8A, 0x64, 0x48, 0x31, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71, 0x58, 0x44, 0x68,
 
// bank 6, 256 bytes
0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0x8C, 0xA8, 0x04,
0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02, 0x26, 0x46, 0x66,
0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31,
0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19, 0x31, 0x48, 0x60,
0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86, 0xA8, 0x6E, 0x76,
0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A, 0x6E, 0x8A, 0x56,
0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E, 0x9D, 0xB8, 0xAD,
0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0x81, 0x91,
0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8,
0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51, 0xD9, 0x04, 0xAE,
0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19, 0x81, 0xAD, 0xD9,
0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9, 0xAD, 0xAD, 0xAD,
0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76, 0xF3, 0xAC, 0x2E,
0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC, 0x30, 0x18, 0xA8,
0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24, 0xF2, 0xB0, 0x89,
0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9, 0xD8, 0xD8, 0x79,
 
// bank 7, 138 bytes (remainder)
0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D, 0xD9, 0x28, 0xD8,
0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D, 0x80, 0x25, 0xDA,
0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34, 0x3C, 0xF3, 0xAB,
0x8B, 0xF8, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xFA, 0xB0, 0x87, 0x9C, 0xB9, 0xA3,
0xDD, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x95, 0xF1, 0xA3, 0xA3, 0xA3, 0x9D, 0xF1, 0xA3, 0xA3, 0xA3,
0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3,
0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0xA3, 0xA3, 0xA3,
0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0xA3, 0xDC,
0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xD8, 0xD8, 0xFF
};
 
const unsigned char mpu6050_dmpConfig[MPU6050_DMP_CONFIG_SIZE] PROGMEM = {
// BANK OFFSET LENGTH [DATA]
0x03, 0x7B, 0x03, 0x4C, 0xCD, 0x6C, // FCFG_1 inv_set_gyro_calibration
0x03, 0xAB, 0x03, 0x36, 0x56, 0x76, // FCFG_3 inv_set_gyro_calibration
0x00, 0x68, 0x04, 0x02, 0xCB, 0x47, 0xA2, // D_0_104 inv_set_gyro_calibration
0x02, 0x18, 0x04, 0x00, 0x05, 0x8B, 0xC1, // D_0_24 inv_set_gyro_calibration
0x01, 0x0C, 0x04, 0x00, 0x00, 0x00, 0x00, // D_1_152 inv_set_accel_calibration
0x03, 0x7F, 0x06, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_accel_calibration
0x03, 0x89, 0x03, 0x26, 0x46, 0x66, // FCFG_7 inv_set_accel_calibration
0x00, 0x6C, 0x02, 0x20, 0x00, // D_0_108 inv_set_accel_calibration
0x02, 0x40, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_00 inv_set_compass_calibration
0x02, 0x44, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_01
0x02, 0x48, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_02
0x02, 0x4C, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_10
0x02, 0x50, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_11
0x02, 0x54, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_12
0x02, 0x58, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_20
0x02, 0x5C, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_21
0x02, 0xBC, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_22
0x01, 0xEC, 0x04, 0x00, 0x00, 0x40, 0x00, // D_1_236 inv_apply_endian_accel
0x03, 0x7F, 0x06, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_mpu_sensors
0x04, 0x02, 0x03, 0x0D, 0x35, 0x5D, // CFG_MOTION_BIAS inv_turn_on_bias_from_no_motion
0x04, 0x09, 0x04, 0x87, 0x2D, 0x35, 0x3D, // FCFG_5 inv_set_bias_update
0x00, 0xA3, 0x01, 0x00, // D_0_163 inv_set_dead_zone
// SPECIAL 0x01 = enable interrupts
0x00, 0x00, 0x00, 0x01, // SET INT_ENABLE at i=22, SPECIAL INSTRUCTION
0x07, 0x86, 0x01, 0xFE, // CFG_6 inv_set_fifo_interupt
0x07, 0x41, 0x05, 0xF1, 0x20, 0x28, 0x30, 0x38, // CFG_8 inv_send_quaternion
0x07, 0x7E, 0x01, 0x30, // CFG_16 inv_set_footer
0x07, 0x46, 0x01, 0x9A, // CFG_GYRO_SOURCE inv_send_gyro
0x07, 0x47, 0x04, 0xF1, 0x28, 0x30, 0x38, // CFG_9 inv_send_gyro -> inv_construct3_fifo
0x07, 0x6C, 0x04, 0xF1, 0x28, 0x30, 0x38, // CFG_12 inv_send_accel -> inv_construct3_fifo
0x02, 0x16, 0x02, 0x00, 0x09 // D_0_22 inv_set_fifo_rate
 
// This very last 0x01 WAS a 0x09, which drops the FIFO rate down to 20 Hz. 0x07 is 25 Hz,
// 0x01 is 100Hz. Going faster than 100Hz (0x00=200Hz) tends to result in very noisy data.
// DMP output frequency is calculated easily using this equation: (200Hz / (1 + value))
 
// It is important to make sure the host processor can keep up with reading and processing
// the FIFO output at the desired rate. Handling FIFO overflow cleanly is also a good idea.
};
 
const unsigned char mpu6050_dmpUpdates[MPU6050_DMP_UPDATES_SIZE] PROGMEM = {
0x01, 0xB2, 0x02, 0xFF, 0xFF,
0x01, 0x90, 0x04, 0x09, 0x23, 0xA1, 0x35,
0x01, 0x6A, 0x02, 0x06, 0x00,
0x01, 0x60, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x60, 0x04, 0x40, 0x00, 0x00, 0x00,
0x01, 0x62, 0x02, 0x00, 0x00,
0x00, 0x60, 0x04, 0x00, 0x40, 0x00, 0x00
};
 
/*
* initialize mpu6050 dmp
*/
uint8_t mpu6050_dmpInitialize() {
//setup interrupt
MPU6050_DMP_INT0SETUP;
 
//reset
mpu6050_writeBit(MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_DEVICE_RESET_BIT, 1);
_delay_ms(30);//wait after reset
 
//disable sleep mode
mpu6050_setSleepDisabled();
 
//set memorybank to 0
mpu6050_setMemoryBank(0, 0, 0);
 
//get X/Y/Z gyro offsets
int8_t xgOffset = mpu6050_getXGyroOffset();
int8_t ygOffset = mpu6050_getYGyroOffset();
int8_t zgOffset = mpu6050_getZGyroOffset();
 
//setting slave 0 address to 0x7F
mpu6050_writeByte(MPU6050_RA_I2C_SLV0_ADDR + 0*3, 0x7F);
//disabling I2C Master mode
mpu6050_writeBit(MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, 0);
//setting slave 0 address to 0x68 (self)
mpu6050_writeByte(MPU6050_RA_I2C_SLV0_ADDR + 0*3, 0x68);
//resetting I2C Master control
mpu6050_writeBit(MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_RESET_BIT, 1);
_delay_ms(20);
 
//load DMP code into memory banks
if (mpu6050_writeMemoryBlock(mpu6050_dmpMemory, MPU6050_DMP_CODE_SIZE, 0, 0, 1, 1) == 1) {
if (mpu6050_writeDMPConfigurationSet(mpu6050_dmpConfig, MPU6050_DMP_CONFIG_SIZE, 1)) {
 
//set clock source
mpu6050_writeBits(MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, MPU6050_CLOCK_PLL_ZGYRO);
 
//set DMP and FIFO_OFLOW interrupts enabled
mpu6050_writeByte(MPU6050_RA_INT_ENABLE, 0x12);
 
//set sample rate
mpu6050_writeByte(MPU6050_RA_SMPLRT_DIV, 4); // 1khz / (1 + 4) = 200 Hz
 
//set external frame sync to TEMP_OUT_L[0]
mpu6050_writeBits(MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, MPU6050_EXT_SYNC_TEMP_OUT_L);
 
//set DLPF bandwidth to 42Hz
mpu6050_writeBits(MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, MPU6050_DLPF_BW_42);
 
//set gyro sensitivity to +/- 2000 deg/sec
mpu6050_writeBits(MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, MPU6050_GYRO_FS_2000);
 
//set DMP configuration bytes (function unknown)
mpu6050_writeByte(MPU6050_RA_DMP_CFG_1, 0x03);
mpu6050_writeByte(MPU6050_RA_DMP_CFG_2, 0x00);
 
//clear OTP Bank flag
mpu6050_writeBit(MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, 0);
 
//set X/Y/Z gyro offsets to previous values
//xgOffset = 0;
//ygOffset = 0;
zgOffset = 90;
 
mpu6050_setXGyroOffset(xgOffset);
mpu6050_setYGyroOffset(ygOffset);
mpu6050_setZGyroOffset(zgOffset);
 
//set X/Y/Z gyro user offsets to zero
mpu6050_writeWords(MPU6050_RA_XG_OFFS_USRH, 1, 0);
mpu6050_writeWords(MPU6050_RA_YG_OFFS_USRH, 1, 0);
mpu6050_writeWords(MPU6050_RA_ZG_OFFS_USRH, 1, 0);
 
//writing final memory update 1/7 (function unknown)
uint8_t dmpUpdate[16], j;
uint16_t pos = 0;
for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&mpu6050_dmpUpdates[pos]);
mpu6050_writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1], 1, 0);
 
//writing final memory update 2/7 (function unknown)
for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&mpu6050_dmpUpdates[pos]);
mpu6050_writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1], 1, 0);
 
//reset FIFO
mpu6050_writeBits(MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_RESET_BIT, 1, 1);
 
//reading FIFO count
uint8_t fifoCount = mpu6050_getFIFOCount();
uint8_t fifoBuffer[128];
 
//current FIFO count
mpu6050_readBytes(MPU6050_RA_FIFO_R_W, fifoCount, fifoBuffer);
 
//setting motion detection threshold to 2
mpu6050_writeByte(MPU6050_RA_MOT_THR, 2);
 
//setting zero-motion detection threshold to 156
mpu6050_writeByte(MPU6050_RA_ZRMOT_THR, 156);
 
//setting motion detection duration to 80
mpu6050_writeByte(MPU6050_RA_MOT_DUR, 80);
 
//setting zero-motion detection duration to 0
mpu6050_writeByte(MPU6050_RA_ZRMOT_DUR, 0);
 
//reset FIFO
mpu6050_writeBit(MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_RESET_BIT, 1);
 
//enabling FIFO
mpu6050_writeBit(MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, 1);
 
//enabling DMP
mpu6050_dmpEnable();
 
//resetting DMP
mpu6050_writeBit(MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_RESET_BIT, 1);
 
//waiting for FIFO count > 2
while ((fifoCount = mpu6050_getFIFOCount()) < 3);
 
//writing final memory update 3/7 (function unknown)
for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&mpu6050_dmpUpdates[pos]);
mpu6050_writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1], 1, 0);
 
//writing final memory update 4/7 (function unknown)
for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&mpu6050_dmpUpdates[pos]);
mpu6050_writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1], 1, 0);
 
//writing final memory update 5/7 (function unknown)
for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&mpu6050_dmpUpdates[pos]);
mpu6050_writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1], 1, 0);
 
//reading FIFO data..."));
mpu6050_getFIFOBytes(fifoBuffer, fifoCount);
 
//reading final memory update 6/7 (function unknown)
for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&mpu6050_dmpUpdates[pos]);
mpu6050_readMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
 
//waiting for FIFO count > 2
while ((fifoCount = mpu6050_getFIFOCount()) < 3);
 
//reading FIFO data
mpu6050_getFIFOBytes(fifoBuffer, fifoCount);
 
//writing final memory update 7/7 (function unknown)
for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&mpu6050_dmpUpdates[pos]);
mpu6050_writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1], 1, 0);
 
//disabling DMP (you turn it on later)
mpu6050_dmpDisable();
 
//resetting FIFO and clearing INT status one last time
mpu6050_writeBit(MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_RESET_BIT, 1);
} else {
return 2; // configuration block loading failed
}
} else {
return 1; // main binary block loading failed
}
return 0; // success
}
 
/*
* enable dmp
*/
void mpu6050_dmpEnable() {
MPU6050_DMP_INT0ENABLE;
mpu6050_writeBit(MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, 1);
}
 
/*
* disable dmp
*/
void mpu6050_dmpDisable() {
MPU6050_DMP_INT0DISABLE;
mpu6050_writeBit(MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, 0);
}
 
/*
* get quaternion from packet
*/
void mpu6050_getQuaternion(const uint8_t* packet, double *qw, double *qx, double *qy, double *qz) {
if (packet == 0) packet = dmpPacketBuffer;
*qw = (double)((packet[0] << 8) + packet[1]) / 16384.0f;
*qx = (double)((packet[4] << 8) + packet[5]) / 16384.0f;
*qy = (double)((packet[8] << 8) + packet[9]) / 16384.0f;
*qz = (double)((packet[12] << 8) + packet[13]) / 16384.0f;
}
 
/*
* get euler angles
* aerospace sequence, to obtain sensor attitude:
* 1. rotate around sensor Z plane by yaw
* 2. rotate around sensor Y plane by pitch
* 3. rotate around sensor X plane by roll
*/
void mpu6050_getRollPitchYaw(double qw, double qx, double qy, double qz, double *roll, double *pitch, double *yaw) {
*yaw = atan2(2*qx*qy - 2*qw*qz, 2*qw*qw + 2*qx*qx - 1);
*pitch = -asin(2*qx*qz + 2*qw*qy);
*roll = atan2(2*qy*qz - 2*qw*qx, 2*qw*qw + 2*qz*qz - 1);
}
 
/*
* get quaternion and wait
*/
uint8_t mpu6050_getQuaternionWait(double *qw, double *qx, double *qy, double *qz) {
while (!mpu6050_mpuInterrupt && mpu6050_fifoCount < MPU6050_DMP_dmpPacketSize);
//reset interrupt
mpu6050_mpuInterrupt = 0;
 
//check for overflow
mpu6050_mpuIntStatus = mpu6050_getIntStatus();
mpu6050_fifoCount = mpu6050_getFIFOCount();
if ((mpu6050_mpuIntStatus & 0x10) || mpu6050_fifoCount == 1024) {
//reset
mpu6050_resetFIFO();
} else if (mpu6050_mpuIntStatus & 0x02) {
//wait for correct available data length, should be a VERY short wait
while (mpu6050_fifoCount < MPU6050_DMP_dmpPacketSize)
mpu6050_fifoCount = mpu6050_getFIFOCount();
//read a packet from FIFO
mpu6050_getFIFOBytes(mpu6050_fifoBuffer, MPU6050_DMP_dmpPacketSize);
mpu6050_fifoCount -= MPU6050_DMP_dmpPacketSize;
//get quaternion
mpu6050_getQuaternion(mpu6050_fifoBuffer, qw, qx, qy, qz);
return 1;
}
 
return 0;
}
 
/*
* on interrupt set data availabe
*/
ISR (INT0_vect) {
mpu6050_mpuInterrupt = 1;
}
 
#endif
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/10DOF/mpu6050registers.h
0,0 → 1,365
/*
MPU6050 lib 0x02
 
copyright (c) Davide Gironi, 2012
 
Released under GPLv3.
Please refer to LICENSE file for licensing information.
*/
 
 
#ifndef MPU6050REGISTERS_H_
#define MPU6050REGISTERS_H_
 
#define MPU6050_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
#define MPU6050_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
#define MPU6050_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
#define MPU6050_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN
#define MPU6050_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN
#define MPU6050_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN
#define MPU6050_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS
#define MPU6050_RA_XA_OFFS_L_TC 0x07
#define MPU6050_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS
#define MPU6050_RA_YA_OFFS_L_TC 0x09
#define MPU6050_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS
#define MPU6050_RA_ZA_OFFS_L_TC 0x0B
#define MPU6050_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR
#define MPU6050_RA_XG_OFFS_USRL 0x14
#define MPU6050_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR
#define MPU6050_RA_YG_OFFS_USRL 0x16
#define MPU6050_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR
#define MPU6050_RA_ZG_OFFS_USRL 0x18
#define MPU6050_RA_SMPLRT_DIV 0x19
#define MPU6050_RA_CONFIG 0x1A
#define MPU6050_RA_GYRO_CONFIG 0x1B
#define MPU6050_RA_ACCEL_CONFIG 0x1C
#define MPU6050_RA_FF_THR 0x1D
#define MPU6050_RA_FF_DUR 0x1E
#define MPU6050_RA_MOT_THR 0x1F
#define MPU6050_RA_MOT_DUR 0x20
#define MPU6050_RA_ZRMOT_THR 0x21
#define MPU6050_RA_ZRMOT_DUR 0x22
#define MPU6050_RA_FIFO_EN 0x23
#define MPU6050_RA_I2C_MST_CTRL 0x24
#define MPU6050_RA_I2C_SLV0_ADDR 0x25
#define MPU6050_RA_I2C_SLV0_REG 0x26
#define MPU6050_RA_I2C_SLV0_CTRL 0x27
#define MPU6050_RA_I2C_SLV1_ADDR 0x28
#define MPU6050_RA_I2C_SLV1_REG 0x29
#define MPU6050_RA_I2C_SLV1_CTRL 0x2A
#define MPU6050_RA_I2C_SLV2_ADDR 0x2B
#define MPU6050_RA_I2C_SLV2_REG 0x2C
#define MPU6050_RA_I2C_SLV2_CTRL 0x2D
#define MPU6050_RA_I2C_SLV3_ADDR 0x2E
#define MPU6050_RA_I2C_SLV3_REG 0x2F
#define MPU6050_RA_I2C_SLV3_CTRL 0x30
#define MPU6050_RA_I2C_SLV4_ADDR 0x31
#define MPU6050_RA_I2C_SLV4_REG 0x32
#define MPU6050_RA_I2C_SLV4_DO 0x33
#define MPU6050_RA_I2C_SLV4_CTRL 0x34
#define MPU6050_RA_I2C_SLV4_DI 0x35
#define MPU6050_RA_I2C_MST_STATUS 0x36
#define MPU6050_RA_INT_PIN_CFG 0x37
#define MPU6050_RA_INT_ENABLE 0x38
#define MPU6050_RA_DMP_INT_STATUS 0x39
#define MPU6050_RA_INT_STATUS 0x3A
#define MPU6050_RA_ACCEL_XOUT_H 0x3B
#define MPU6050_RA_ACCEL_XOUT_L 0x3C
#define MPU6050_RA_ACCEL_YOUT_H 0x3D
#define MPU6050_RA_ACCEL_YOUT_L 0x3E
#define MPU6050_RA_ACCEL_ZOUT_H 0x3F
#define MPU6050_RA_ACCEL_ZOUT_L 0x40
#define MPU6050_RA_TEMP_OUT_H 0x41
#define MPU6050_RA_TEMP_OUT_L 0x42
#define MPU6050_RA_GYRO_XOUT_H 0x43
#define MPU6050_RA_GYRO_XOUT_L 0x44
#define MPU6050_RA_GYRO_YOUT_H 0x45
#define MPU6050_RA_GYRO_YOUT_L 0x46
#define MPU6050_RA_GYRO_ZOUT_H 0x47
#define MPU6050_RA_GYRO_ZOUT_L 0x48
#define MPU6050_RA_EXT_SENS_DATA_00 0x49
#define MPU6050_RA_EXT_SENS_DATA_01 0x4A
#define MPU6050_RA_EXT_SENS_DATA_02 0x4B
#define MPU6050_RA_EXT_SENS_DATA_03 0x4C
#define MPU6050_RA_EXT_SENS_DATA_04 0x4D
#define MPU6050_RA_EXT_SENS_DATA_05 0x4E
#define MPU6050_RA_EXT_SENS_DATA_06 0x4F
#define MPU6050_RA_EXT_SENS_DATA_07 0x50
#define MPU6050_RA_EXT_SENS_DATA_08 0x51
#define MPU6050_RA_EXT_SENS_DATA_09 0x52
#define MPU6050_RA_EXT_SENS_DATA_10 0x53
#define MPU6050_RA_EXT_SENS_DATA_11 0x54
#define MPU6050_RA_EXT_SENS_DATA_12 0x55
#define MPU6050_RA_EXT_SENS_DATA_13 0x56
#define MPU6050_RA_EXT_SENS_DATA_14 0x57
#define MPU6050_RA_EXT_SENS_DATA_15 0x58
#define MPU6050_RA_EXT_SENS_DATA_16 0x59
#define MPU6050_RA_EXT_SENS_DATA_17 0x5A
#define MPU6050_RA_EXT_SENS_DATA_18 0x5B
#define MPU6050_RA_EXT_SENS_DATA_19 0x5C
#define MPU6050_RA_EXT_SENS_DATA_20 0x5D
#define MPU6050_RA_EXT_SENS_DATA_21 0x5E
#define MPU6050_RA_EXT_SENS_DATA_22 0x5F
#define MPU6050_RA_EXT_SENS_DATA_23 0x60
#define MPU6050_RA_MOT_DETECT_STATUS 0x61
#define MPU6050_RA_I2C_SLV0_DO 0x63
#define MPU6050_RA_I2C_SLV1_DO 0x64
#define MPU6050_RA_I2C_SLV2_DO 0x65
#define MPU6050_RA_I2C_SLV3_DO 0x66
#define MPU6050_RA_I2C_MST_DELAY_CTRL 0x67
#define MPU6050_RA_SIGNAL_PATH_RESET 0x68
#define MPU6050_RA_MOT_DETECT_CTRL 0x69
#define MPU6050_RA_USER_CTRL 0x6A
#define MPU6050_RA_PWR_MGMT_1 0x6B
#define MPU6050_RA_PWR_MGMT_2 0x6C
#define MPU6050_RA_BANK_SEL 0x6D
#define MPU6050_RA_MEM_START_ADDR 0x6E
#define MPU6050_RA_MEM_R_W 0x6F
#define MPU6050_RA_DMP_CFG_1 0x70
#define MPU6050_RA_DMP_CFG_2 0x71
#define MPU6050_RA_FIFO_COUNTH 0x72
#define MPU6050_RA_FIFO_COUNTL 0x73
#define MPU6050_RA_FIFO_R_W 0x74
#define MPU6050_RA_WHO_AM_I 0x75
 
#define MPU6050_TC_PWR_MODE_BIT 7
#define MPU6050_TC_OFFSET_BIT 6
#define MPU6050_TC_OFFSET_LENGTH 6
#define MPU6050_TC_OTP_BNK_VLD_BIT 0
 
#define MPU6050_VDDIO_LEVEL_VLOGIC 0
#define MPU6050_VDDIO_LEVEL_VDD 1
 
#define MPU6050_CFG_EXT_SYNC_SET_BIT 5
#define MPU6050_CFG_EXT_SYNC_SET_LENGTH 3
#define MPU6050_CFG_DLPF_CFG_BIT 2
#define MPU6050_CFG_DLPF_CFG_LENGTH 3
 
#define MPU6050_EXT_SYNC_DISABLED 0x0
#define MPU6050_EXT_SYNC_TEMP_OUT_L 0x1
#define MPU6050_EXT_SYNC_GYRO_XOUT_L 0x2
#define MPU6050_EXT_SYNC_GYRO_YOUT_L 0x3
#define MPU6050_EXT_SYNC_GYRO_ZOUT_L 0x4
#define MPU6050_EXT_SYNC_ACCEL_XOUT_L 0x5
#define MPU6050_EXT_SYNC_ACCEL_YOUT_L 0x6
#define MPU6050_EXT_SYNC_ACCEL_ZOUT_L 0x7
 
#define MPU6050_DLPF_BW_256 0x00
#define MPU6050_DLPF_BW_188 0x01
#define MPU6050_DLPF_BW_98 0x02
#define MPU6050_DLPF_BW_42 0x03
#define MPU6050_DLPF_BW_20 0x04
#define MPU6050_DLPF_BW_10 0x05
#define MPU6050_DLPF_BW_5 0x06
 
#define MPU6050_GCONFIG_FS_SEL_BIT 4
#define MPU6050_GCONFIG_FS_SEL_LENGTH 2
 
#define MPU6050_GYRO_FS_250 0x00
#define MPU6050_GYRO_FS_500 0x01
#define MPU6050_GYRO_FS_1000 0x02
#define MPU6050_GYRO_FS_2000 0x03
 
#define MPU6050_ACONFIG_XA_ST_BIT 7
#define MPU6050_ACONFIG_YA_ST_BIT 6
#define MPU6050_ACONFIG_ZA_ST_BIT 5
#define MPU6050_ACONFIG_AFS_SEL_BIT 4
#define MPU6050_ACONFIG_AFS_SEL_LENGTH 2
#define MPU6050_ACONFIG_ACCEL_HPF_BIT 2
#define MPU6050_ACONFIG_ACCEL_HPF_LENGTH 3
 
#define MPU6050_ACCEL_FS_2 0x00
#define MPU6050_ACCEL_FS_4 0x01
#define MPU6050_ACCEL_FS_8 0x02
#define MPU6050_ACCEL_FS_16 0x03
 
#define MPU6050_DHPF_RESET 0x00
#define MPU6050_DHPF_5 0x01
#define MPU6050_DHPF_2P5 0x02
#define MPU6050_DHPF_1P25 0x03
#define MPU6050_DHPF_0P63 0x04
#define MPU6050_DHPF_HOLD 0x07
 
#define MPU6050_TEMP_FIFO_EN_BIT 7
#define MPU6050_XG_FIFO_EN_BIT 6
#define MPU6050_YG_FIFO_EN_BIT 5
#define MPU6050_ZG_FIFO_EN_BIT 4
#define MPU6050_ACCEL_FIFO_EN_BIT 3
#define MPU6050_SLV2_FIFO_EN_BIT 2
#define MPU6050_SLV1_FIFO_EN_BIT 1
#define MPU6050_SLV0_FIFO_EN_BIT 0
 
#define MPU6050_MULT_MST_EN_BIT 7
#define MPU6050_WAIT_FOR_ES_BIT 6
#define MPU6050_SLV_3_FIFO_EN_BIT 5
#define MPU6050_I2C_MST_P_NSR_BIT 4
#define MPU6050_I2C_MST_CLK_BIT 3
#define MPU6050_I2C_MST_CLK_LENGTH 4
 
#define MPU6050_CLOCK_DIV_348 0x0
#define MPU6050_CLOCK_DIV_333 0x1
#define MPU6050_CLOCK_DIV_320 0x2
#define MPU6050_CLOCK_DIV_308 0x3
#define MPU6050_CLOCK_DIV_296 0x4
#define MPU6050_CLOCK_DIV_286 0x5
#define MPU6050_CLOCK_DIV_276 0x6
#define MPU6050_CLOCK_DIV_267 0x7
#define MPU6050_CLOCK_DIV_258 0x8
#define MPU6050_CLOCK_DIV_500 0x9
#define MPU6050_CLOCK_DIV_471 0xA
#define MPU6050_CLOCK_DIV_444 0xB
#define MPU6050_CLOCK_DIV_421 0xC
#define MPU6050_CLOCK_DIV_400 0xD
#define MPU6050_CLOCK_DIV_381 0xE
#define MPU6050_CLOCK_DIV_364 0xF
 
#define MPU6050_I2C_SLV_RW_BIT 7
#define MPU6050_I2C_SLV_ADDR_BIT 6
#define MPU6050_I2C_SLV_ADDR_LENGTH 7
#define MPU6050_I2C_SLV_EN_BIT 7
#define MPU6050_I2C_SLV_BYTE_SW_BIT 6
#define MPU6050_I2C_SLV_REG_DIS_BIT 5
#define MPU6050_I2C_SLV_GRP_BIT 4
#define MPU6050_I2C_SLV_LEN_BIT 3
#define MPU6050_I2C_SLV_LEN_LENGTH 4
 
#define MPU6050_I2C_SLV4_RW_BIT 7
#define MPU6050_I2C_SLV4_ADDR_BIT 6
#define MPU6050_I2C_SLV4_ADDR_LENGTH 7
#define MPU6050_I2C_SLV4_EN_BIT 7
#define MPU6050_I2C_SLV4_INT_EN_BIT 6
#define MPU6050_I2C_SLV4_REG_DIS_BIT 5
#define MPU6050_I2C_SLV4_MST_DLY_BIT 4
#define MPU6050_I2C_SLV4_MST_DLY_LENGTH 5
 
#define MPU6050_MST_PASS_THROUGH_BIT 7
#define MPU6050_MST_I2C_SLV4_DONE_BIT 6
#define MPU6050_MST_I2C_LOST_ARB_BIT 5
#define MPU6050_MST_I2C_SLV4_NACK_BIT 4
#define MPU6050_MST_I2C_SLV3_NACK_BIT 3
#define MPU6050_MST_I2C_SLV2_NACK_BIT 2
#define MPU6050_MST_I2C_SLV1_NACK_BIT 1
#define MPU6050_MST_I2C_SLV0_NACK_BIT 0
 
#define MPU6050_INTCFG_INT_LEVEL_BIT 7
#define MPU6050_INTCFG_INT_OPEN_BIT 6
#define MPU6050_INTCFG_LATCH_INT_EN_BIT 5
#define MPU6050_INTCFG_INT_RD_CLEAR_BIT 4
#define MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT 3
#define MPU6050_INTCFG_FSYNC_INT_EN_BIT 2
#define MPU6050_INTCFG_I2C_BYPASS_EN_BIT 1
#define MPU6050_INTCFG_CLKOUT_EN_BIT 0
 
#define MPU6050_INTMODE_ACTIVEHIGH 0x00
#define MPU6050_INTMODE_ACTIVELOW 0x01
 
#define MPU6050_INTDRV_PUSHPULL 0x00
#define MPU6050_INTDRV_OPENDRAIN 0x01
 
#define MPU6050_INTLATCH_50USPULSE 0x00
#define MPU6050_INTLATCH_WAITCLEAR 0x01
 
#define MPU6050_INTCLEAR_STATUSREAD 0x00
#define MPU6050_INTCLEAR_ANYREAD 0x01
 
#define MPU6050_INTERRUPT_FF_BIT 7
#define MPU6050_INTERRUPT_MOT_BIT 6
#define MPU6050_INTERRUPT_ZMOT_BIT 5
#define MPU6050_INTERRUPT_FIFO_OFLOW_BIT 4
#define MPU6050_INTERRUPT_I2C_MST_INT_BIT 3
#define MPU6050_INTERRUPT_PLL_RDY_INT_BIT 2
#define MPU6050_INTERRUPT_DMP_INT_BIT 1
#define MPU6050_INTERRUPT_DATA_RDY_BIT 0
 
// TODO: figure out what these actually do
// UMPL source code is not very obivous
#define MPU6050_DMPINT_5_BIT 5
#define MPU6050_DMPINT_4_BIT 4
#define MPU6050_DMPINT_3_BIT 3
#define MPU6050_DMPINT_2_BIT 2
#define MPU6050_DMPINT_1_BIT 1
#define MPU6050_DMPINT_0_BIT 0
 
#define MPU6050_MOTION_MOT_XNEG_BIT 7
#define MPU6050_MOTION_MOT_XPOS_BIT 6
#define MPU6050_MOTION_MOT_YNEG_BIT 5
#define MPU6050_MOTION_MOT_YPOS_BIT 4
#define MPU6050_MOTION_MOT_ZNEG_BIT 3
#define MPU6050_MOTION_MOT_ZPOS_BIT 2
#define MPU6050_MOTION_MOT_ZRMOT_BIT 0
 
#define MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT 7
#define MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT 4
#define MPU6050_DELAYCTRL_I2C_SLV3_DLY_EN_BIT 3
#define MPU6050_DELAYCTRL_I2C_SLV2_DLY_EN_BIT 2
#define MPU6050_DELAYCTRL_I2C_SLV1_DLY_EN_BIT 1
#define MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT 0
 
#define MPU6050_PATHRESET_GYRO_RESET_BIT 2
#define MPU6050_PATHRESET_ACCEL_RESET_BIT 1
#define MPU6050_PATHRESET_TEMP_RESET_BIT 0
 
#define MPU6050_DETECT_ACCEL_ON_DELAY_BIT 5
#define MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH 2
#define MPU6050_DETECT_FF_COUNT_BIT 3
#define MPU6050_DETECT_FF_COUNT_LENGTH 2
#define MPU6050_DETECT_MOT_COUNT_BIT 1
#define MPU6050_DETECT_MOT_COUNT_LENGTH 2
 
#define MPU6050_DETECT_DECREMENT_RESET 0x0
#define MPU6050_DETECT_DECREMENT_1 0x1
#define MPU6050_DETECT_DECREMENT_2 0x2
#define MPU6050_DETECT_DECREMENT_4 0x3
 
#define MPU6050_USERCTRL_DMP_EN_BIT 7
#define MPU6050_USERCTRL_FIFO_EN_BIT 6
#define MPU6050_USERCTRL_I2C_MST_EN_BIT 5
#define MPU6050_USERCTRL_I2C_IF_DIS_BIT 4
#define MPU6050_USERCTRL_DMP_RESET_BIT 3
#define MPU6050_USERCTRL_FIFO_RESET_BIT 2
#define MPU6050_USERCTRL_I2C_MST_RESET_BIT 1
#define MPU6050_USERCTRL_SIG_COND_RESET_BIT 0
 
#define MPU6050_PWR1_DEVICE_RESET_BIT 7
#define MPU6050_PWR1_SLEEP_BIT 6
#define MPU6050_PWR1_CYCLE_BIT 5
#define MPU6050_PWR1_TEMP_DIS_BIT 3
#define MPU6050_PWR1_CLKSEL_BIT 2
#define MPU6050_PWR1_CLKSEL_LENGTH 3
 
#define MPU6050_CLOCK_INTERNAL 0x00
#define MPU6050_CLOCK_PLL_XGYRO 0x01
#define MPU6050_CLOCK_PLL_YGYRO 0x02
#define MPU6050_CLOCK_PLL_ZGYRO 0x03
#define MPU6050_CLOCK_PLL_EXT32K 0x04
#define MPU6050_CLOCK_PLL_EXT19M 0x05
#define MPU6050_CLOCK_KEEP_RESET 0x07
 
#define MPU6050_PWR2_LP_WAKE_CTRL_BIT 7
#define MPU6050_PWR2_LP_WAKE_CTRL_LENGTH 2
#define MPU6050_PWR2_STBY_XA_BIT 5
#define MPU6050_PWR2_STBY_YA_BIT 4
#define MPU6050_PWR2_STBY_ZA_BIT 3
#define MPU6050_PWR2_STBY_XG_BIT 2
#define MPU6050_PWR2_STBY_YG_BIT 1
#define MPU6050_PWR2_STBY_ZG_BIT 0
 
#define MPU6050_WAKE_FREQ_1P25 0x0
#define MPU6050_WAKE_FREQ_2P5 0x1
#define MPU6050_WAKE_FREQ_5 0x2
#define MPU6050_WAKE_FREQ_10 0x3
 
#define MPU6050_BANKSEL_PRFTCH_EN_BIT 6
#define MPU6050_BANKSEL_CFG_USER_BANK_BIT 5
#define MPU6050_BANKSEL_MEM_SEL_BIT 4
#define MPU6050_BANKSEL_MEM_SEL_LENGTH 5
 
#define MPU6050_WHO_AM_I_BIT 6
#define MPU6050_WHO_AM_I_LENGTH 6
 
#define MPU6050_DMP_MEMORY_BANKS 8
#define MPU6050_DMP_MEMORY_BANK_SIZE 256
#define MPU6050_DMP_MEMORY_CHUNK_SIZE 16
 
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/10DOF/sensor.c
0,0 → 1,30
/*
* sensor.c
*
* Created on: 18.09.2015
* Author: cebra
*/
//############################################################################
//# HISTORY sensor.c
//#
//# 19.09.2015 cebra
//# - add: Routinen für das GY-87 Sensorboard zur Berechnung der Kompasswerte etc.
//#
//############################################################################
 
 
#ifdef USE_KOMPASS
#include "mpu6050.h"
#include "sensor.h"
 
 
 
 
void Init_Sensors(void)
 
{
 
 
 
}
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/10DOF/sensor.h
0,0 → 1,15
/*
* sensor.h
*
* Created on: 18.09.2015
* Author: cebra
*/
 
#ifndef SENSOR_H_
#define SENSOR_H_
 
 
 
 
 
#endif /* 10DOF_SENSOR_H_ */
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/10DOF
Property changes:
Added: svn:ignore
+_old
+
+_doc
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/HAL_HW3_9.c
0,0 → 1,562
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY HAL_HW3_9.c
//#
//#
//# 10.11.2014 cebra
//# - chg: Displaybeleuchtung aktiv einschalten beim Start
//#
//# 14.06.2014 OG
//# - chg: InitHWPorts() - umgestellt auf PKT_TitlePKTlipo(false) da eine
//# richtige LiPo-Anzeige im Startbildschirm zu diesem Zeitpunkt noch
//# nicht moeglich ist
//# - chg: InitHWPorts() - bt_init() umgestellt auf BTM222_Initalize()
//#
//# 11.06.2014 OG
//# - fix: InitHWPorts() einstellen der Sprache geht jetzt wieder
//#
//# 10.06.2014 OG
//# - chg: InitHWPorts() - umgestellt auf Wi232_Initalize()
//#
//# 08.06.2014 OG
//# - chg: InitHWPorts() - Aufruf von InitWi232() geaendert
//#
//# 28.05.2014 OG
//# - chg: InitHWPorts() - Bearbeiten der Sprache auskommentiert weil sich
//# Edit_generic() geaendert hat und notwendige Texte aus einem Menue
//# bezieht welches hier in der HAL nicht vorhanden ist
//#
//# 01.04.2014 OG
//# - chg: PCB_WiFlyPatch umbenannt zu PCB_SV2RxTxPatch
//#
//# 24.03.2014 OG
//# - chg: InitHWPorts(): den Begriff "WiFly" bzw. "WiFly Patch" geaendert
//# zu "SV2 Patch"
//#
//# 21.02.2014 OG
//# - chg: InitHWPorts() auf PKT_TitlePKTVersion() angepasst
//#
//# 20.02.2014 OG
//# - chg: InitHWPorts() Anzeige vom Startscreen ueberarbeitet
//# - chg: Code-Formatierung
//#
//# 30.01.2014 OG
//# - add: Unterstuetzung fuer USE_BLUETOOTH
//#
//# 29.01.2014 OG
//# - del: #include "display.h"
//#
//# 25.08.2013 Cebra
//# - add: #ifdef USE_TRACKING vor Servo_init
//#
//# 07.07.2013 OG
//# - add: DEBUG_SV2_EXTENSION in InitHWPorts() bzgl. Anzeige von "A:.. B:.." usw.
//#
//# 26.06.2013 OG
//# - del: Code zu USE_PKT_STARTINFO
//#
//# 26.06.2013 Cebra
//# - add: Modulumschaltung für WiFlypatch umgebaut
//# - chg: Wartezeit nach Einschalten von BT auf 3 Sekunden verlängert
//#
//# 22.06.2013 cebra
//# - chg: Fehler in CheckPCB führte zu fehlerhafter Lipomessung, alle Pins von Port A waren auf Eingang
//#
//# 13.06.2013 cebra
//# - chg: Displaybeleuchtung ohne Helligkeitssteuerung
//#
//# 15.05.2013 OG
//# - chg: define USE_PKT_STARTINFO ergaenzt (siehe main.h)
//#
//# 28.04.2013 OG
//# - add: Unterstuetzung von define USE_FONT_BIG (Layoutanpassung)
//#
//# 12.04.2013 Cebra
//# - chg: Fehler bei der Umschaltung Wi232/Kabelverbindung beim Start des PKT
//###########################################################################
 
 
#ifndef HAL_HW3_9_C_
#define HAL_HW3_9_C_
 
#include "cpu.h"
#include <inttypes.h>
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <avr/eeprom.h>
#include <util/delay.h>
#include <stdbool.h>
#include <stdlib.h>
 
#include "main.h"
 
//#if defined HWVERSION3_9
#include "eeprom/eeprom.h"
#include "messages.h"
#include "lcd/lcd.h"
#include "uart/usart.h"
#include "uart/uart1.h"
#include "timer/timer.h"
 
#include "wi232/Wi232.h"
//#include "i2cmaster.h"
#include "bluetooth/bluetooth.h"
#include "bluetooth/error.h"
#include "connect.h"
#include "lipo/lipo.h"
#include "pkt/pkt.h"
#include "setup/setup.h"
#include "osd/osd.h"
#include "sound/pwmsine8bit.h"
#include "tracking/ng_servo.h"
 
 
 
volatile uint8_t USBBT;
volatile uint8_t U02SV2;
volatile uint8_t PCB_Version;
volatile uint8_t PCB_SV2RxTxPatch;
 
 
uint8_t PortA;
uint8_t PortB;
uint8_t PortC;
uint8_t PortD;
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void CheckPCB(void)
{
//
DDRA = 0x00;
DDRB = 0x00;
DDRC = 0x00;
DDRD = 0x00;
PortA = PINA;
PortB = PINB;
PortC = PINC;
PortD = PIND;
 
 
DDRC = 0x00;
PORTC &= ~(1<<PORTC7); // Pullup setzen
if (PINC & (1<<PINC7) ) PCB_Version = PKT39m; else PCB_Version = PKT39x;
PORTC &= ~(1<<PORTC0); // Pullup setzen
if (PINC & (1<<PINC0) ) PCB_SV2RxTxPatch = false; else PCB_SV2RxTxPatch = true;
PORTC |= (1<<PORTC0); // Pullup aus
 
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void InitHWPorts( void ) // Initialisierung der Hardware für die jeweilige Leiterplattenversion
{
int8_t yoffs;
 
CheckPCB(); // Version der Leiterplatte prüfen
 
if( PCB_SV2RxTxPatch )
{
DDRC |= (1<<DDC0)|(1<<DDC1); // Ausgang: C0 Reset BT, C1 Reset WiFly
PORTC &= ~((1<<BT_Reset)|(1<<WiFly_Reset)|(1<<USB_Reset)); // Erst alle Module ausschalten
}
 
PORTA |= (1<<PORTA4)|(1<<PORTA5)|(1<<PORTA6)|(1<<PORTA7); // Enable Pull Up for the 4 keys
DDRA &= ~(1<<DDA4); // Eingang: A4 auf Low setzen (Power On)
 
if( Config.Lipomessung == true )
{
DDRA &= ~(1<<DDA1); // Eingang: PKT Lipo Messung
//PORTA &= ~(1<<PORTA1);
}
 
DDRB = 0xFF; // alles Ausgaenge
 
PORTC |= (1<<PORTC4)|(1<<PORTC7); // Enable Pull Up for LBO + Summer
DDRC |= (1<<DDC2)|(1<<DDC3)|(1<<DDC5)|(1<<DDC6|(1<<DDC7)); // Ausgang: Led2,Rs232Switch,Summer
DDRC &= ~(1<<DDC4); // Eingang: LowBat LTC1308
 
if( PCB_SV2RxTxPatch ) clr_USBOn();
else _BTOn(); // Erstmal USB dektivieren, damit beim versehentlichen Einschalten USB im PC ruhig bleibt
 
 
DDRD |= (1<<DDD4)|(1<<DDD5)|(1<<DDD6)|(1<<DDD7); // Ausgang: PiepserTest, Servo, Wi232-CMD und Beleuchtung
PORTD |= (1<<PORTD6); // Wi232-CMD auf High schalten
set_D_LIGHT(); // Displaybeleuchtung an
 
 
set_V_On(); // Spannung mit T3 halten
Timer0_Init(); // system
 
Display_on = 1;
USART_Init (UART_BAUD_SELECT(USART_BAUD,F_CPU));
uart1_init (UART_BAUD_SELECT(USART_BAUD,F_CPU)); // USB
// I2C_Init(1);
// i2c_init();
 
LCD_Init(0); // muss vor "ReadParameter" stehen
ReadParameter(); // aktuelle Werte aus EEProm auslesen
 
#ifdef USE_TRACKING
servoInit(SERVO_PERIODE);
#endif
 
//servoSetDefaultPos();
sei();
 
Old_Baudrate = Config.PKT_Baudrate;
SetBaudUart1( Config.PKT_Baudrate );
SetBaudUart0( Config.PKT_Baudrate );
 
// 10.11.2015 cebra
// TODO cebra: diese Stelle muss bei HW_Sound überarbeitet werden
// if( (Config.HWSound==0) && (PCB_Version == PKT39m) )
// {
// Timer2_Init(); // Displaybeleuchtung oder Soundmodul
// OCR2A = Config.LCD_Helligkeit * 2.55;
// }
 
 
 
 
#ifdef USE_SOUND
if (Config.HWSound==1) InitSound();
#endif
 
 
LCD_Init(1);
set_beep ( 400, 0x0080, BeepNormal);
 
OSD_active = false; // keine OSD Ausgabe
 
ADC_Init(); // ADC für Lipomessung// MartinR: verschoben
 
 
//-------------------------
// beim ersten Start (oder nach Reset) Sprache abfragen
//-------------------------
if( Config.DisplayLanguage > NUM_LANG )
{
Config.DisplayLanguage = 1;
//Config.DisplayLanguage = Edit_generic( Config.DisplayLanguage, 0, 1, Language,1, NULL,NULL); // OG: ?? hierbei wird die falsche Sprache angezeigt - warum?
Config.DisplayLanguage = Edit_generic( 2, 0, 1, Language,1, NULL,NULL);
WriteParameter();
}
 
 
//-------------------------
// Anzeige Start-Screen
//-------------------------
PKT_TitlePKTlipo( false ); // Titel mit PKT-Version anzeigen (und clearscreen)
 
yoffs = 11;
 
if( PCB_SV2RxTxPatch )
{
lcdx_printp_center( 2, PSTR("SV2 Patch"), MNORMAL, 0,7); // "SV2 Patch" (ehemals "Wifly Patch")
yoffs = 5;
}
 
if( PCB_Version==PKT39m )
{
lcdx_printp_center( 1, PSTR("HW 3.9m (09.2011)"), MNORMAL, 0,yoffs);
}
 
if( PCB_Version==PKT39x )
{
lcdx_printp_center( 1, PSTR("HW 3.9x (11.2012)"), MNORMAL, 0,yoffs);
}
 
lcdx_printp_center( 5, strGet(BOOT1), MNORMAL, 0,2); // "Taste 1 Sekunde"
lcdx_printp_center( 6, strGet(BOOT2), MNORMAL, 0,4); // "festhalten!"
lcd_rect_round( 0, 5*8-2, 127, 2*8+8, 1, R2); // Rahmen
 
 
//-------------------------
//-------------------------
 
#ifdef DEBUG_SV2_EXTENSION
lcd_printpns_at (0, 7, PSTR("A:"),0);
lcd_print_hex(PortA,0);
lcd_printpns_at (5, 7, PSTR("B:"),0);
lcd_print_hex(PortB,0);
lcd_printpns_at (10, 7, PSTR("C:"),0);
lcd_print_hex(PortC,0);
lcd_printpns_at (15, 7, PSTR("D:"),0);
lcd_print_hex(PortD,0);
#endif
 
 
//_delay_ms(800);
_delay_ms(900);
 
if (PINA & (1<<PINA7)) // Spannung eingeschaltet lassen
clr_V_On();
 
 
_delay_ms(100);
 
set_beep ( 400, 0x0080, BeepNormal);
get_key_press(KEY_ALL);
 
#ifdef USE_SOUND
if (Config.HWSound==1);
{
playTone(505,100,Config.Volume);
playTone(515,100,Config.Volume);
playTone(525,100,Config.Volume);
playTone(535,100,Config.Volume);
playTone(525,100,Config.Volume);
playTone(515,100,Config.Volume);
playTone(505,100,Config.Volume);
}
#endif
 
//lcd_cls(); // 20.02.2014 OG
 
 
// servoSetPosition(1,0);
// _delay_ms(250);
// servoSetPosition(0,0);
// _delay_ms(250);
// servoSetPosition(1,400);
// _delay_ms(250);
// servoSetPosition(0,400);
// _delay_ms(250);
// servoSetPosition(1,0);
// _delay_ms(250);
// servoSetPosition(0,0);
// _delay_ms(250);
// servoSetPosition(1,400);
// _delay_ms(250);
// servoSetPosition(0,400);
 
 
set_BTOff();
//set_Modul_On(USB);
 
if( (Config.UseWi == true) && (Config.WiIsSet == false) )
{
Wi232_Initalize(); // wenn Wi232 nicht initialisiert ist, dann jetzt tun
}
 
 
#ifdef USE_BLUETOOTH
if ((Config.UseBT == true) && (Config.BTIsSet == false)) // BT ausschalten
{
//lcd_cls();
BTM222_Initalize();
// set_USBOn();
}
bt_start();
#endif // end: #ifdef USE_BLUETOOTH
 
 
if( (Config.UseWi == true) && (Config.U02SV2 == 0) )
{
Change_Output(Uart02Wi); // Verbindung zu Wi232 herstellen
}
else
{
Change_Output(Uart02FC); // Verbindung zu SV" (Kabel) herstellen
}
 
} // InitHWPorts()
 
 
 
//#define set_BEEP() (PORTC &= ~(1 << Summer)) // Summer
//#define clr_BEEP() (PORTC |= (1 << Summer))
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void set_BEEP(void)
{
if (PCB_Version == PKT39m)
PORTC &= ~(1 << Summer); // Summer
if (PCB_Version == PKT39x)
PORTD &= ~(1 << SummerV2); // Summer
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void clr_BEEP(void)
{
if (PCB_Version == PKT39m)
PORTC |= (1 << Summer); // Summer
if (PCB_Version == PKT39x)
PORTD |= (1 << SummerV2); // Summer
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void set_D_LIGHT(void) /* Displaybeleuchtung ein*/
{
if (PCB_Version == PKT39m)
{
// if (Config.HWSound==0)
// {
// // PWM einschalten
// TCCR2A |= (1 << WGM21) | (1 << WGM20) | (1 << COM2A1);
// TCCR2B |= (1 << CS20);
// }
// else
clr_DISPLAYLIGHT();
}
 
if (PCB_Version == PKT39x)
{
// if (HWSound==0)
// {
// // PWM einschalten
// TCCR2A |= (1 << WGM21) | (1 << WGM20) | (1 << COM2A1);
// TCCR2B |= (1 << CS20);
// }
// else
clr_DISPLAYLIGHTV2();
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void clr_D_LIGHT(void) /* Displaybeleuchtung aus*/
{
if (PCB_Version == PKT39m)
{
// if (Config.HWSound==0)
// {
// // PWM ausschalten
// TCCR2A = 0;
// TCCR2B = 0;
// }
// else
 
set_DISPLAYLIGHT();
}
if (PCB_Version == PKT39x)
{
// if (HWSound==0)
// {
// // PWM ausschalten
// TCCR2A = 0;
// TCCR2B = 0;
// }
// else
set_DISPLAYLIGHTV2();
}
}
uint8_t BTIsOn=0;
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void set_Modul_On(uint8_t Modul) // Umschaltfunktionen für Leiterplatte 3.9x mit WiFlypatch
{
 
if (PCB_SV2RxTxPatch) PORTC &= ~((1<<BT_Reset)|(1<<WiFly_Reset)|(1<<USB_Reset)); // Erst alle Module ausschalten
 
switch (Modul)
{
case USB: if (PCB_SV2RxTxPatch) set_USBOn();
else set_USBOn();
BTIsOn = 0;
break;
 
case Bluetooth: if (PCB_SV2RxTxPatch) set_BTM222On();
else _BTOn();
if (BTIsOn == 0)
{
BTIsOn = 1;
_delay_ms(3000); // wait for BTM222 initialisation
}
break;
case Wlan: set_WiFlyOn();
BTIsOn = 0;
break;
}
 
 
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void set_BTOn(void)
{
if (BTIsOn == 0)
{
if (PCB_SV2RxTxPatch) set_Modul_On(Bluetooth);
else
{
_BTOn();
BTIsOn = 1;
_delay_ms(3000);
}
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void set_BTOff(void)
{
if( PCB_SV2RxTxPatch )
set_Modul_On(USB);
else
{
set_USBOn();
BTIsOn = 0;
}
}
 
 
 
#endif
//#endif // HAL_HW3_9_C_
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/HAL_HW3_9.h
0,0 → 1,194
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY HAL_HW3_9.h
//#
//# 01.04.2014 OG
//# - chg: PCB_WiFlyPatch umbenannt zu PCB_SV2RxTxPatch
//#
//# 26.06.2013 Cebra
//# - add: defines für WyFlypatch Port C0 + C1
//#
//# 17.05.2013 OG
//# - add: defines: KEY_ENTER_LONG, KEY_ESC_LONG, KEY_PLUS_LONG, KEY_MINUS_LONG
//############################################################################
 
 
#ifndef HAL_HW3_9_H_
#define HAL_HW3_9_H_
 
 
 
//#define PIEPSER_NERVT // Summer zu Testzwecken ganz Ausschalten
 
#define PKT39m 1
#define PKT39x 2
 
#define USB 1
#define Bluetooth 2
#define Wlan 3
 
 
 
// Hardware 3.9 Portbelegung
#define KEY_PIN PINA // Port A als Input
 
#define Touch0 PA0 // Pin 37
#define Touch1 PA1 // Pin 36
#define Touch2 PA2 // Pin 35
#define Touch3 PA3 // Pin 34
#define KEY_EXT PINA3 // MartinR
 
#define Key1 PA4 // Pin 33
#define Key2 PA5 // Pin 32
#define Key3 PA6 // Pin 31
#define Key4 PA7 // Pin 30
 
#define USB2Wi PB0 // Pin 40 aktiv low > IC5
#define VoltageHold PB1 // Pin 41 High = Spannung T3 halten
#define Display_Reset PB2 // Pin 42
#define Display_A0 PB3 // Pin 43
#define Display_CS PB4 // Pin 44
#define Display_SI PB5 // Pin 1
#define LED1 PB6 // Pin 2 Low = LED1 (nicht benutzbar wegen SCL
#define Display_SCL PB7 // Pin 3
 
#define I2C_SCL PC0 // Pin 19 SCL
#define I2C_CDA PC1 // Pin 20 SDA
 
#define BT_Reset PC0 // Pin 19 Reseteingang BTM222 / WiyFlypatch
#define WiFly_Reset PC1 // Pin 20 Reseteingang WyFly / WiyFlypatch
 
#define USB2FC PC2 // Pin 21 aktiv low > IC5
#define USB_BT PC3 // Pin 22 high = USB, Low = Bluetooth, LED2
 
#define USB_Reset PC3 // Pin 22 Reseteingang USB FT232 / WiFlypatch
 
#define LowBat PC4 // Pin 23 Low Bat Warning Lipo PKT,Input
#define Uart02Wi PC5 // Pin 24 aktiv Low > IC4
#define Uart02FC PC6 // Pin 25 aktiv Low > IC4
#define Summer PC7 // Pin 26 Low = Summer
#define DisplaybeleuchtungV2 PC7 // Pin 26 High = Display-LED PCB 3.9x
 
#define Uart0RxD PD0 // Pin 9 über IC4 =Wi | SV2
#define Uart0TxD PD1 // Pin 10 über IC4 =Wi | SV2
#define Uart1RxD PD2 // Pin 11 direkt = USB, BTM, über IC5 = Wi | SV2
#define Uart1TxD PD3 // Pin 12 direkt = USB, BTM, über IC5 = Wi | SV2
#define SERVO2 PD4 // Pin 13 PWM Servo 2
#define SERVO1 PD5 // Pin 14 PWM Servo 1
#define Wi232_CMD PD6 // Pin 15 aktiv Low = Wi232 CMD
#define Displaybeleuchtung PD7 // Pin 16 High = Display-LED PCB 3.9m
#define SummerV2 PD7 // Pin 16 Low = Summer, PCB 3.9x
 
#define KEY_ENTER Key1
#define KEY_ESC Key2
#define KEY_PLUS Key3
#define KEY_MINUS Key4
 
#define KEY_NONE 0 // keine Taste (menuctrl)
 
#define KEY_ENTER_LONG KEY_ENTER+100 // for long press keys used in scrollbox & menuctrl
#define KEY_ESC_LONG KEY_ESC+100
#define KEY_PLUS_LONG KEY_PLUS+100
#define KEY_MINUS_LONG KEY_MINUS+100
 
 
// |= schaltet Ausgang auf HIGH
// &= ~ schaltet Ausgang auf LOW
 
#define set_reset() (PORTB |= (1 << Display_Reset))
#define clr_reset() (PORTB &= ~(1 << Display_Reset))
 
#define set_A0() (PORTB |= (1 << Display_A0))
#define clr_A0() (PORTB &= ~(1 << Display_A0))
 
#define set_cs() (PORTB |= (1 << Display_CS))
#define clr_cs() (PORTB &= ~(1 << Display_CS))
 
#define set_si() (PORTB |= (1 << Display_SI))
#define clr_si() (PORTB &= ~(1 << Display_SI))
 
#define set_scl() (PORTB |= (1 << Display_SCL))
#define clr_scl() (PORTB &= ~(1 << Display_SCL))
 
#define _BTOn() (PORTC &= ~(1 << USB_BT)) // Bluetooth ein
 
#define set_USBOn() (PORTC |= (1 << USB_Reset)) // USB ein
#define clr_USBOn() (PORTC &= ~(1 << USB_Reset)) // USB aus
 
#define set_BTM222On() (PORTC |= (1 << BT_Reset)) // BT ein
#define clr_BTM222On() (PORTC &= ~(1 << BT_Reset)) // BT aus
 
#define set_WiFlyOn() (PORTC |= (1 << WiFly_Reset)) // WiFly ein
#define clr_WiFlyOn() (PORTC &= ~(1 << WiFly_Reset)) // WiFly aus
 
#define clr_V_On() (PORTB &= ~(1 << VoltageHold)) // Spannung mit T3 halten
#define set_V_On() (PORTB |= (1 << VoltageHold))
 
#define set_USB2FC() (PORTC &= ~(1 << USB2FC)) // USB mit FC-Kabel verbinden
#define clr_USB2FC() (PORTC |= (1 << USB2FC))
 
#define set_USB2Wi() (PORTB &= ~(1 << USB2Wi)) // USB mit Wi232 verbinden
#define clr_USB2Wi() (PORTB |= (1 << USB2Wi))
 
#define set_Uart02FC() (PORTC &= ~(1 << Uart02FC)) // Uart0 mit FC-Kabel verbinden
#define clr_Uart02FC() (PORTC |= (1 << Uart02FC))
 
#define set_Uart02Wi() (PORTC &= ~(1 << Uart02Wi)) // Uart0 mit Wi232 verbinden
#define clr_Uart02Wi() (PORTC |= (1 << Uart02Wi))
 
 
#define set_DISPLAYLIGHT() (PORTD &= ~(1 << Displaybeleuchtung)) // Displaybeleuchtung PCB3.9m
#define clr_DISPLAYLIGHT() (PORTD |= (1 << Displaybeleuchtung))
#define set_DISPLAYLIGHTV2() (PORTC &= ~(1 << DisplaybeleuchtungV2)) // Displaybeleuchtung PCB3.9x
#define clr_DISPLAYLIGHTV2() (PORTC |= (1 << DisplaybeleuchtungV2))
 
#define set_WI232CMD() (PORTD &= ~(1 << Wi232_CMD)) // Wi232 Programmierpin
#define clr_WI232CMD() (PORTD |= (1 << Wi232_CMD))
 
 
 
void set_D_LIGHT(void); /* Displaybeleuchtung ein*/
void clr_D_LIGHT(void); /* Displaybeleuchtung aus */
void set_BEEP(void); /* Beeper ein*/
void clr_BEEP(void); /* Beeper aus*/
void InitHWPorts(void);
void set_BTOn(void); /* Bluetooth einschalten*/
void set_BTOff(void); /* Bluetooth einschalten*/
void set_Modul_On(uint8_t Modul);
extern volatile uint8_t PCB_Version;
extern volatile uint8_t PCB_SV2RxTxPatch;
 
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/avr-nmea-gps-library/nmea.c
0,0 → 1,525
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
//############################################################################
//# HISTORY nmea.c
//#
//# 08.08.2015 CB
//# - add: Einführung eines neuen Interruptbasierten NMEA Parsers
//# cpp-Code auf c geändert und an PKT angepasst
//#
//############################################################################
 
/* URSPRUNG:
File: nmea.cpp
Version: 0.1.0
Date: Feb. 23, 2013
License: GPL v2
NMEA GPS content parser
****************************************************************************
Copyright (C) 2013 Radu Motisan <radu.motisan@gmail.com>
http://www.pocketmagic.net
 
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 2 of the License, or
(at your option) any later version.
 
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
 
You should have received a copy of the GNU General Public License
along with this program; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
****************************************************************************
*/
 
#include "nmea.h"
#include "../timer/timer.h"
//#include <stdio.h>
//#include <stdlib.h>
//#include <util/delay.h>
#include <stdbool.h>
 
 
#define MAX_POWER 10
#define getPower(x) (int32_t)pgm_read_dword(&powers[x])
static const int32_t powers[MAX_POWER] PROGMEM = {1, 10, 100, 1000, 10000, 100000, 1000000, 10000000, 100000000, 1000000000};
 
uint8_t m_bFlagRead, // flag used by the parser, when a valid sentence has begun
m_bFlagDataReady = false; // valid GPS fix and data available, user can call reader functions
volatile uint32_t res_nNMEAcounter = 0; // NMEA Datensatzzähler
volatile uint32_t res_nCRCerror = 0; // zählt die CRC Errors beim dekodieren
uint8_t receiveNMEA = false;
char tmp_words[20][15], // hold parsed words for one given NMEA sentence
tmp_szChecksum[15]; // hold the received checksum for one given NMEA sentence
 
// will be set to true for characters between $ and * only
bool m_bFlagComputedCks ; // used to compute checksum and indicate valid checksum interval (between $ and * in a given sentence)
int m_nChecksum ; // numeric checksum, computed for a given sentence
bool m_bFlagReceivedCks ; // after getting * we start cuttings the received checksum
int index_received_checksum ; // used to parse received checksum
 
// word cutting variables
int m_nWordIdx , // the current word in a sentence
m_nPrevIdx, // last character index where we did a cut
m_nNowIdx ; // current character index
 
// globals to store parser results
int32_t res_fLongitude; // GPRMC and GPGGA
int32_t res_fLatitude; // GPRMC and GPGGA
unsigned char res_nUTCHour, res_nUTCMin, res_nUTCSec, // GPRMC and GPGGA
res_nUTCDay, res_nUTCMonth, res_nUTCYear; // GPRMC
char Time[9]; // GPRMC and GPGGA
uint8_t res_nSatellitesUsed; // GPGGA
uint8_t res_nGPSfix; // GPGGA
int16_t res_nHDOP; // GPGGA
int16_t res_fAltitude; // GPGGA
float res_fSpeed; // GPRMC
int16_t res_fBearing; // GPRMC
 
NMEA_GPGGA_t NMEA; // Variable mit der Struktur für die NMEA Daten für PKT
 
// the parser, currently handling GPRMC and GPGGA, but easy to add any new sentences
// void parsedata();
// aux functions
int digit2dec(char hexdigit);
float string2float(char* s);
int mstrcmp(const char *s1, const char *s2);
 
 
 
 
/*
* The serial data is assembled on the fly, without using any redundant buffers.
* When a sentence is complete (one that starts with $, ending in EOL), all processing is done on
* this temporary buffer that we've built: checksum computation, extracting sentence "words" (the CSV values),
* and so on.
* When a new sentence is fully assembled using the fusedata function, the code calls parsedata.
* This function in turn, splits the sentences and interprets the data. Here is part of the parser function,
* handling both the $GPRMC NMEA sentence:
*/
uint8_t fusedata(char c)
 
{
if (c == '$') {
m_bFlagRead = true;
// init parser vars
m_bFlagComputedCks = false;
m_nChecksum = 0;
// after getting * we start cuttings the received m_nChecksum
m_bFlagReceivedCks = false;
index_received_checksum = 0;
// word cutting variables
m_nWordIdx = 0; m_nPrevIdx = 0; m_nNowIdx = 0;
timer_nmea_timeout = NMEA_TIMEOUT; // Timeout Timer setzen
}
if (m_bFlagRead) {
// check ending
if (c == '\r' || c== '\n') {
// catch last ending item too
tmp_words[m_nWordIdx][m_nNowIdx - m_nPrevIdx] = 0;
m_nWordIdx++;
// cut received m_nChecksum
tmp_szChecksum[index_received_checksum] = 0;
// sentence complete, read done
m_bFlagRead = false;
// parse
parsedata();
} else {
// computed m_nChecksum logic: count all chars between $ and * exclusively
if (m_bFlagComputedCks && c == '*') m_bFlagComputedCks = false;
if (m_bFlagComputedCks) m_nChecksum ^= c;
if (c == '$') m_bFlagComputedCks = true;
// received m_nChecksum
if (m_bFlagReceivedCks) {
tmp_szChecksum[index_received_checksum] = c;
index_received_checksum++;
}
if (c == '*') m_bFlagReceivedCks = true;
// build a word
tmp_words[m_nWordIdx][m_nNowIdx - m_nPrevIdx] = c;
if (c == ',') {
tmp_words[m_nWordIdx][m_nNowIdx - m_nPrevIdx] = 0;
m_nWordIdx++;
m_nPrevIdx = m_nNowIdx;
}
else m_nNowIdx++;
}
}
return m_nWordIdx;
}
 
 
/*
* parse internal tmp_ structures, fused by pushdata, and set the data flag when done
*/
void parsedata(void) {
int received_cks = 16*digit2dec(tmp_szChecksum[0]) + digit2dec(tmp_szChecksum[1]);
//uart1.Send("seq: [cc:%X][words:%d][rc:%s:%d]\r\n", m_nChecksum,m_nWordIdx, tmp_szChecksum, received_cks);
// check checksum, and return if invalid!
if (m_nChecksum != received_cks) {
m_bFlagDataReady = false;
res_nCRCerror = res_nCRCerror+1;
return;
}
/* $GPGGA
* $GPGGA,hhmmss.ss,llll.ll,a,yyyyy.yy,a,x,xx,x.x,x.x,M,x.x,M,x.x,xxxx*hh
* ex: $GPGGA,230600.501,4543.8895,N,02112.7238,E,1,03,3.3,96.7,M,39.0,M,,0000*6A,
*
* WORDS:
* 1 = UTC of Position
* 2 = Latitude
* 3 = N or S
* 4 = Longitude
* 5 = E or W
* 6 = GPS quality indicator (0=invalid; 1=GPS fix; 2=Diff. GPS fix)
* 7 = Number of satellites in use [not those in view]
* 8 = Horizontal dilution of position
* 9 = Antenna altitude above/below mean sea level (geoid)
* 10 = Meters (Antenna height unit)
* 11 = Geoidal separation (Diff. between WGS-84 earth ellipsoid and mean sea level.
* -geoid is below WGS-84 ellipsoid)
* 12 = Meters (Units of geoidal separation)
* 13 = Age in seconds since last update from diff. reference station
* 14 = Diff. reference station ID#
* 15 = Checksum
*/
if (mstrcmp(tmp_words[0], "$GPGGA") == 0) {
// Check GPS Fix: 0=no fix, 1=GPS fix, 2=Dif. GPS fix
res_nGPSfix = atoi(&tmp_words[6][0]);
NMEA.SatFix = res_nGPSfix;
if (tmp_words[6][0] == '0') {
// clear data
res_fLatitude = 0;
res_fLongitude = 0;
// m_bFlagDataReady = false;
 
// return;
}
// parse time
res_nUTCHour = digit2dec(tmp_words[1][0]) * 10 + digit2dec(tmp_words[1][1]);
res_nUTCMin = digit2dec(tmp_words[1][2]) * 10 + digit2dec(tmp_words[1][3]);
res_nUTCSec = digit2dec(tmp_words[1][4]) * 10 + digit2dec(tmp_words[1][5]);
NMEA_getTime (tmp_words[1]);
 
// parse latitude and longitude in NMEA format
// res_fLatitude = string2float(tmp_words[2]);
// res_fLongitude = string2float(tmp_words[4]);
 
// get decimal format
// if (tmp_words[3][0] == 'S') res_fLatitude *= -1.0;
// if (tmp_words[5][0] == 'W') res_fLongitude *= -1.0;
// float degrees = trunc(res_fLatitude / 100.0f);
// float minutes = res_fLatitude - (degrees * 100.0f);
// res_fLatitude = degrees + minutes / 60.0f;
// degrees = trunc(res_fLongitude / 100.0f);
// minutes = res_fLongitude - (degrees * 100.0f);
// res_fLongitude = degrees + minutes / 60.0f;
 
res_fLatitude = NMEA_calcLatitude(tmp_words[2],tmp_words[3]);
res_fLongitude = NMEA_calcLongitude(tmp_words[4],tmp_words[5]);
NMEA.Latitude = res_fLatitude;
NMEA.Longitude = res_fLongitude;
// parse number of satellites
res_nSatellitesUsed = (int)string2float(tmp_words[7]);
NMEA.SatsInUse = atoi(tmp_words[7]);
// parse HDOP
res_nHDOP = NMEA_floatStrToInt(tmp_words[8],1);
NMEA.HDOP = res_nHDOP;
 
// parse altitude
// res_fAltitude = string2float(tmp_words[9]);
res_fAltitude = NMEA_floatStrToInt( tmp_words[9], 1);
NMEA.Altitude = res_fAltitude;
// data ready
m_bFlagDataReady = true;
res_nNMEAcounter = res_nNMEAcounter +1;
NMEA.Counter = res_nNMEAcounter;
 
}
 
// 8.8.2015 CB wird zur Zeit nicht benötigt
/* $GPRMC
* note: a siRF chipset will not support magnetic headers.
* $GPRMC,hhmmss.ss,A,llll.ll,a,yyyyy.yy,a,x.x,x.x,ddmmyy,x.x,a*hh
* ex: $GPRMC,230558.501,A,4543.8901,N,02112.7219,E,1.50,181.47,230213,,,A*66,
*
* WORDS:
* 1 = UTC of position fix
* 2 = Data status (V=navigation receiver warning)
* 3 = Latitude of fix
* 4 = N or S
* 5 = Longitude of fix
* 6 = E or W
* 7 = Speed over ground in knots
* 8 = Track made good in degrees True, Bearing This indicates the direction that the device is currently moving in,
* from 0 to 360, measured in “azimuth”.
* 9 = UT date
* 10 = Magnetic variation degrees (Easterly var. subtracts from true course)
* 11 = E or W
* 12 = Checksum
*/
// if (mstrcmp(tmp_words[0], "$GPRMC") == 0) {
// // Check data status: A-ok, V-invalid
// if (tmp_words[2][0] == 'V') {
// // clear data
// res_fLatitude = 0;
// res_fLongitude = 0;
//// m_bFlagDataReady = false;
// return;
// }
//// // parse time
//// res_nUTCHour = digit2dec(tmp_words[1][0]) * 10 + digit2dec(tmp_words[1][1]);
//// res_nUTCMin = digit2dec(tmp_words[1][2]) * 10 + digit2dec(tmp_words[1][3]);
//// res_nUTCSec = digit2dec(tmp_words[1][4]) * 10 + digit2dec(tmp_words[1][5]);
//// // parse latitude and longitude in NMEA format
//// res_fLatitude = string2float(tmp_words[3]);
//// res_fLongitude = string2float(tmp_words[5]);
//// // get decimal format
//// if (tmp_words[4][0] == 'S') res_fLatitude *= -1.0;
//// if (tmp_words[6][0] == 'W') res_fLongitude *= -1.0;
//// float degrees = trunc(res_fLatitude / 100.0f);
//// float minutes = res_fLatitude - (degrees * 100.0f);
//// res_fLatitude = degrees + minutes / 60.0f;
//// degrees = trunc(res_fLongitude / 100.0f);
//// minutes = res_fLongitude - (degrees * 100.0f);
//// res_fLongitude = degrees + minutes / 60.0f;
// //parse speed
// // The knot (pronounced not) is a unit of speed equal to one nautical mile (1.852 km) per hour
// res_fSpeed = NMEA_floatStrToInt(tmp_words[7],1);
// res_fSpeed /= 1.852; // convert to km/h
// // parse bearing
// res_fBearing = NMEA_floatStrToInt(tmp_words[8],1);
//// // parse UTC date
//// res_nUTCDay = digit2dec(tmp_words[9][0]) * 10 + digit2dec(tmp_words[9][1]);
//// res_nUTCMonth = digit2dec(tmp_words[9][2]) * 10 + digit2dec(tmp_words[9][3]);
//// res_nUTCYear = digit2dec(tmp_words[9][4]) * 10 + digit2dec(tmp_words[9][5]);
//
// // data ready
// res_nNMEAcounter = res_nNMEAcounter +1;
// NMEA.Counter = res_nNMEAcounter;
// m_bFlagDataReady = true;
// }
}
 
 
 
//--------------------------------------------------------------
// NMEA latitudes are in the form ddmm.mmmmm, we want an integer in 1E-7 degree steps
//--------------------------------------------------------------
int32_t NMEA_calcLatitude( const char *s, const char *NS)
{
int32_t deg;
int32_t min;
 
//lcdx_puts_at(0,5,NS,0,0,0);
deg = (s[0] - '0') * 10 + s[1] - '0'; // First 2 chars are full degrees
min = NMEA_floatStrToInt( &s[2], 6) / 6; // Minutes * 1E5 * 100 / 60 = Minutes * 1E6 / 6 = 1E-7 degree steps
 
deg = deg * 10000000 + min;
 
if( *NS == 'S' )
{
deg = -deg;
}
 
return deg;
}
 
 
 
//--------------------------------------------------------------
// NMEA longitudes are in the form dddmm.mmmmm, we want an integer in 1E-7 degree steps
//--------------------------------------------------------------
int32_t NMEA_calcLongitude( const char *s, const char *WE)
{
int32_t deg;
int32_t min;
 
//lcdx_puts_at(10,5,WE,0,0,0);
deg = ((s[0] - '0') * 10 + s[1] - '0') * 10 + s[2] - '0'; // First 3 chars are full degrees
min = NMEA_floatStrToInt( &s[3], 6) / 6; // Minutes * 1E5 * 100 / 60 = Minutes * 1E6 / 6 = 1E-7 degree steps
 
deg = deg * 10000000 + min;
 
if( *WE == 'W' )
{
deg = -deg;
}
 
return deg;
}
 
//--------------------------------------------------------------
void NMEA_getTime( const char *s)
{
uint8_t sem = 0;
uint8_t i;
 
for( i=0; i<6; i++ )
{
NMEA.Time[sem++] = s[i];
 
if( i==1 || i==3)
NMEA.Time[sem++] = ':';
 
}
NMEA.Time[sem] = '\0';
}
 
//--------------------------------------------------------------
/*
* returns base-16 value of chars '0'-'9' and 'A'-'F';
* does not trap invalid chars!
*/
int digit2dec(char digit)
{
if ((int)digit >= 65)
return ((int)digit - 55);
else
return ((int)digit - 48);
}
 
//--------------------------------------------------------------
/* returns base-10 value of zero-terminated string
* that contains only chars '+','-','0'-'9','.';
* does not trap invalid strings!
*/
float string2float(char* s) {
long integer_part = 0;
float decimal_part = 0.0;
float decimal_pivot = 0.1;
bool isdecimal = false, isnegative = false;
char c;
while ( ( c = *s++) ) {
// skip special/sign chars
if (c == '-') { isnegative = true; continue; }
if (c == '+') continue;
if (c == '.') { isdecimal = true; continue; }
if (!isdecimal) {
integer_part = (10 * integer_part) + (c - 48);
}
else {
decimal_part += decimal_pivot * (float)(c - 48);
decimal_pivot /= 10.0;
}
}
// add integer part
decimal_part += (float)integer_part;
// check negative
if (isnegative) decimal_part = - decimal_part;
 
return decimal_part;
}
 
 
//--------------------------------------------------------------
// Trying to avoid floating point maths here. Converts a floating point string to an integer with a smaller unit
// i.e. floatStrToInt("4.5", 2) = 4.5 * 1E2 = 450
//--------------------------------------------------------------
int32_t NMEA_floatStrToInt( const char *s, int32_t power1 )
{
char *endPtr;
int32_t v;
 
v = strtol(s, &endPtr, 10);
 
if( *endPtr == '.' )
{
for (s = endPtr + 1; *s && power1; s++)
{
v = v * 10 + (*s - '0');
--power1;
}
}
 
if( power1 )
{
// Table to avoid multiple multiplications
v = v * getPower(power1);
}
 
return v;
}
 
 
//--------------------------------------------------------------
int mstrcmp(const char *s1, const char *s2)
{
while((*s1 && *s2) && (*s1 == *s2))
s1++,s2++;
return *s1 - *s2;
}
 
//--------------------------------------------------------------
bool NMEA_isdataready() {
return m_bFlagDataReady;
}
 
int NMEA_getHour() {
return res_nUTCHour;
}
int NMEA_getMinute() {
return res_nUTCMin;
}
int NMEA_getSecond() {
return res_nUTCSec;
}
int NMEA_getDay() {
return res_nUTCDay;
}
int NMEA_getMonth() {
return res_nUTCMonth;
}
int NMEA_getYear() {
return res_nUTCYear;
}
 
int32_t NMEA_getLatitude() {
return res_fLatitude;
}
 
int32_t NMEA_getLongitude() {
return res_fLongitude;
}
 
uint8_t NMEA_getSatellites() {
return res_nSatellitesUsed;
}
 
uint8_t NMEA_getGPSfix() {
return res_nGPSfix;
}
int16_t NMEA_getHDOP() {
return res_nHDOP;
}
 
int16_t NMEA_getAltitude() {
return res_fAltitude;
}
 
float NMEA_getSpeed() {
return res_fSpeed;
}
 
int16_t NMEA_getBearing() {
return res_fBearing;
}
uint32_t NMEA_getNMEAcounter() {
return res_nNMEAcounter;
}
 
uint32_t NMEA_getCRCerror() {
return res_nCRCerror;
}
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/avr-nmea-gps-library/nmea.h
0,0 → 1,135
/*
File: nmea.h
Version: 0.1.0
Date: Feb. 23, 2013
License: GPL v2
NMEA GPS content parser
****************************************************************************
Copyright (C) 2013 Radu Motisan <radu.motisan@gmail.com>
http://www.pocketmagic.net
 
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 2 of the License, or
(at your option) any later version.
 
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
 
You should have received a copy of the GNU General Public License
along with this program; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
****************************************************************************
*/
 
#include <string.h>
//#include <util/delay.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <stdbool.h>
#include <stdlib.h>
#include <math.h>
#include <stdio.h>
 
//---------------------------------
#define NMEA_TIMEOUT 500 // Timeout 5 sek.
//---------------------------------
typedef struct
{
uint32_t Counter; // Zaehler empfangene GPGGA Pakete
int32_t Latitude; // in 1E-7 deg
int32_t Longitude; // in 1E-7 deg
int16_t Altitude; // Hoehe in Meter
uint8_t SatFix; // GPS Quality indicator (0=no fix, 1=GPS fix, 2=Dif. GPS fix, 6=Estimated)
uint8_t SatsInUse; // Number of satelites currently in use
int16_t HDOP; // Horizontal Dilution of Precision, 1.1 -xx.x, niederiger = besser
char Time[9]; // "hh:mm:ss"
} NMEA_GPGGA_t;
 
//---------------------------------
// export vars
//---------------------------------
extern NMEA_GPGGA_t NMEA;
extern uint8_t receiveNMEA;
extern volatile uint32_t res_nNMEAcounter;
 
// /*class NMEA {
//
// private:
// bool m_bFlagRead, // flag used by the parser, when a valid sentence has begun
// m_bFlagDataReady; // valid GPS fix and data available, user can call reader functions
// char tmp_words[20][15], // hold parsed words for one given NMEA sentence
// tmp_szChecksum[15]; // hold the received checksum for one given NMEA sentence
//
// // will be set to true for characters between $ and * only
// bool m_bFlagComputedCks ; // used to compute checksum and indicate valid checksum interval (between $ and * in a given sentence)
// int m_nChecksum ; // numeric checksum, computed for a given sentence
// bool m_bFlagReceivedCks ; // after getting * we start cuttings the received checksum
// int index_received_checksum ; // used to parse received checksum
//
// // word cutting variables
// int m_nWordIdx , // the current word in a sentence
// m_nPrevIdx, // last character index where we did a cut
// m_nNowIdx ; // current character index
//
// // globals to store parser results
// float res_fLongitude; // GPRMC and GPGGA
// float res_fLatitude; // GPRMC and GPGGA
// unsigned char res_nUTCHour, res_nUTCMin, res_nUTCSec, // GPRMC and GPGGA
// res_nUTCDay, res_nUTCMonth, res_nUTCYear; // GPRMC
// int res_nSatellitesUsed; // GPGGA
// float res_fAltitude; // GPGGA
// float res_fSpeed; // GPRMC
// float res_fBearing; // GPRMC
//
// // the parser, currently handling GPRMC and GPGGA, but easy to add any new sentences
// void parsedata();
// // aux functions
// int digit2dec(char hexdigit);
// float string2float(char* s);
// int mstrcmp(const char *s1, const char *s2);
//
// public:
// // constructor, initing a few variables
/*
* The serial data is assembled on the fly, without using any redundant buffers.
* When a sentence is complete (one that starts with $, ending in EOL), all processing is done on
* this temporary buffer that we've built: checksum computation, extracting sentence "words" (the CSV values),
* and so on.
* When a new sentence is fully assembled using the fusedata function, the code calls parsedata.
* This function in turn, splits the sentences and interprets the data. Here is part of the parser function,
* handling both the $GPRMC NMEA sentence:
*/
uint8_t fusedata(char c);
void parsedata(void);
int32_t NMEA_floatStrToInt( const char *s, int32_t power1 );
int32_t NMEA_calcLatitude( const char *s, const char *NS);
int32_t NMEA_calcLongitude( const char *s, const char *WE);
void NMEA_getTime( const char *s);
 
// READER functions: retrieving results, call isdataready() first
bool NMEA_isdataready();
int NMEA_getHour();
int NMEA_getMinute();
int NMEA_getSecond();
int NMEA_getDay();
int NMEA_getMonth();
int NMEA_getYear();
int32_t NMEA_getLatitude();
int32_t NMEA_getLongitude();
uint8_t NMEA_getSatellites();
uint8_t NMEA_getGPSfix();
int16_t NMEA_getHDOP();
int16_t NMEA_getAltitude();
float NMEA_getSpeed();
int16_t NMEA_getBearing();
uint32_t NMEA_getNMEAcounter();
uint32_t NMEA_getCRCerror();
// };
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/bluetooth/bluetooth.c
0,0 → 1,1760
/**
* source for the Bluetooth driver
* @file bluetooth.c
* @author Linus Lotz<lotz@in.tum.de>
* @author Salomon Sickert
*/
 
 
//############################################################################
//# HISTORY bluetooth.c
//#
//#
//# 02.08.2015 CB
//# - chg: bt_showsettings(), angepasst und vollendet, zur Zeit nur im Mastermodus des BTM222 nutzbar
//#
//# 30.06.2014 OG
//# - chg: bt_discover() wieder auf (berechnete) Progressbar umgestellt
//#
//# 26.06.2014 OG
//# - del: bt_receiveNMEA() - jetzt in gps/nmea.c
//# - chg: bt_discover(), bt_searchDevice() - stark geaendert; Timeout geht jetzt
//# nach Zeit und Abbruch durch Benutzer moeglich
//# - fix: BT-Devicesuche - wenn bei einer Suche Devices gefunden wurden und bei
//# einer nachfolgenden Suche weniger (z.B. weil ein Device ausgeschaltet wurde)
//# dann wurden zuviele Devices angezeigt; fixed
//#
//# 25.06.2014 OG
//# - chg: bt_discover(), bt_searchDevice()
//#
//# 22.06.2014 OG
//# - chg: Code-Formattierung
//#
//# 21.06.2014 CB
//# - fix: Fehler in "copy_DevName", zwei Leerzeichen am Anfang beendeten sofort den Namen, Namen war dann leer
//# - fix: Umbau der Timeoutfunktion bei der Devicesuche, wenn kein BT Device in Reichweite wurde die Suche nicht beendet
//# - add: Progressbar bei BT Device Suche
//#
//# 19.06.2014 OG
//# - chg: Code-Formattierung
//#
//# 16.06.2014 OG
//# - etliche Aenderungen und Funktionsumbenennungen - vorallem rund um den
//# Bereich BT-Init
//# - viel Code-Layout (noch nicht abgeschlossen)
//#
//# 08.06.2014 OG
//# - del: BT_New_Baudrate
//#
//# 30.01.2014 OG
//# - add: Unterstuetzung fuer USE_BLUETOOTH
//#
//# 2013 Cebra
//# - Erweiterung um BT Local-ID Abfrage
//#
//# 26.06.2013 Cebra
//# - chg: Modulumschaltung fuer WiFlypatch geaendert
//#
//# 24.06.2013 OG
//# - add: bt_fixname() - korrigiert ggf. fehlehaften BT-Namen in Config.bt_name
//#
//# 24.06.2013 OG
//# - chg: bt_init(): Code-Layout, Code-Struktur, ggf. Debug-Ausgaben
//# - chg: bt_searchmodul(): Code-Layout und Ausgabe
//# - chg: send_cmd(): Handling von BT_SET_NAME & Code-Layout
//# - add: define DEBUG_BT
//#
//# 23.05.2013 OG
//# - chg: Timeout reduziert in bt_disconnect() (trennen der BT-Verbindung)
//# - fix: copy_DevName() Range angepasst und 0 Terminierung
//#
//# 24.04.2013 OG
//# - chg: Auskommentiert: #define __DELAY_BACKWARD_COMPATIBLE__
//# das wird bereits vom Compiler-Symbol dieses PKT-Projektes definiert
//# und erzeugt nur zusaetzliche Warnings
//#
//# 03.04.2013 Cebra
//# - chg: Init Routinen BT überarbeitet, es kam zu falschen Baudrateneinstellungen
//# beim BTM-222 ohne Hinweis, mehr Displayinformationen beim Init
//############################################################################
 
 
#include <string.h>
#include "../cpu.h"
#include <util/delay.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <stdlib.h>
 
#include "bluetooth.h"
#include "../main.h"
 
 
//----------------------------------------------------------------------------
 
#ifdef USE_BLUETOOTH // 30.01.2014 OG
// brutal hier den Source ausklammern, damit man an anderen Stellen des PKT
// den BT-Code durch den Compiler entdeckt
// ansonsten kann es passieren, dass einiges an BT-Code unenddeckt einkompiliert wird
// -> bei den ersten Test's waren das immerhin ca. 10 KByte durch unenddeckten Code...
 
//----------------------------------------------------------------------------
 
//#define DEBUG_BT
//#ifdef HWVERSION3_9
 
#include "../uart/uart1.h"
#include "../uart/usart.h"
#include "../timer/timer.h"
#include "fifo.h"
#include "error.h"
#include "../lcd/lcd.h"
#include "../eeprom/eeprom.h"
#include "../setup/setup.h"
#include "bluetooth.h"
#include "../tracking/tracking.h"
#include "../utils/xutils.h"
 
#include "../messages.h"
#include "../pkt/pkt.h"
#include "../lipo/lipo.h"
#include "../utils/menuctrl.h"
#include "../utils/scrollbox.h"
 
//############################################################################
//############################################################################
 
 
//#define BT_CMD_TIMEOUT_MS 2000
#define BT_CMD_TIMEOUT_MS 500 // 15.06.2014 OG: Timeout reduziert von 2000 auf 500
 
 
static const char STR_BTM222INIT[] PROGMEM = "BTM222 Init";
 
 
//#define SaveMem
 
//
// Baudrate for the UART-connection to the BTM-222 on SQUIRREL
//
 
#define SQUIRREL
 
#ifdef SQUIRREL
#define UART_BAUD_RATE 19200
#endif
 
#ifdef NUT
#define UART_BAUD_RATE 19200
#endif
 
 
typedef enum {
BT_RAW,
BT_DATA,
BT_CMD,
BT_NOECHO,
BT_NOANSWER
} communication_mode_t;
 
 
 
typedef enum {
BT_TEST, // AT
BT_CONNECT, // ATA
BT_DISCONNECT, // ATH
BT_CLEAR_ADDRESS, // ATD0
BT_SET_ADDRESS, // ATD=_____
BT_GET_LOCALID, // ATB? Inquire the Local BD address
BT_FIND_DEVICES, // ATF?
BT_DISABLE_AUTOCONNECT, // ATO1
BT_ENABLE_AUTOCONNECT, // ATO0
BT_SET_MASTER, // ATR0
BT_SET_SLAVE, // ATR1
BT_SET_PIN, // ATP=1234
BT_SET_2400, // ATL* Baudrate 2400
BT_SET_4800, // ATL0 Baudrate 4800
BT_SET_9600, // ATL1 Baudrate 9600
BT_SET_19200, // ATL2 Baudrate 19200
BT_SET_38400, // ATL3 Baudrate 38400
BT_SET_57600, // ATL4 Baudrate 57600
BT_SET_115200, // ATL5 Baudrate 115200
BT_SET_NOANSWER, // ATQ1 Rückmeldungen aus
BT_SET_NOECHO, // ATE0 ECHO deaktivieren
BT_SET_ANSWER, // ATQ0 Rückmeldungen
BT_SET_ECHO, // ATE1 ECHO aktivieren
BT_SET_DEFAULT, // Defaultwerte setzen
BT_SET_NAME, // Devicename
BT_SET_DISPWRDOWN, // disable auto Powerdown
BT_SHOW_SETTINGS // ATI1 Listing all setting value
} bt_cmd_t;
 
 
//TODO: FIFO Groesse
#define IN_FIFO_SIZE 512
 
char localID[15]="12345678901234";
static uint8_t bt_buffer[IN_FIFO_SIZE];
fifo_t in_fifo;
 
char bt_rx_buffer[RXD_BUFFER_SIZE];
volatile uint8_t bt_rx_len;
volatile uint8_t bt_rx_ready = 0;
 
 
uint8_t EchoAnswerOn=false; //Merkzelle
static bt_mode_t bt_mode = BLUETOOTH_SLAVE;
static communication_mode_t comm_mode = BT_CMD;
 
uint8_t i = 0;
 
uint8_t bt_devicecount = 0;
 
uint8_t bt_rxerror = 0;
uint8_t bt_frameerror = 0;
uint8_t bt_overrun = 0;
uint8_t bt_bufferoverflow = 0;
 
 
device_info device_list[NUTS_LIST];
 
 
 
 
// Set a timeout of Y ms and a Conditon X, which have to be true while timeout
#define while_timeout(X, Y) for(uint16_t __timeout = 0; __timeout++ <= Y && (X); Delay_MS(Y ? 1 : 0))
 
 
//--------------------------------------------------------------
// entfernt ungueltige Zeichen und Leerzeichen (rechts) aus dem
// BT-Namen die evtl. durch Default's reingekommen sind.
// Falls ungueltige Zeichen ('.') wird der BT-Name auf "PKT"
// gesetzt.
//--------------------------------------------------------------
void bt_fixname(void)
{
char *p;
 
p = Config.bt_name;
while( *p!=0 && *p!='.' ) p++; // suche '.'
if( *p=='.' || Config.bt_name[0]==' ' || Config.bt_name[0]==0) // wenn '.' gefunden oder Anfang mit ' ' oder kein String
strcpy_P(Config.bt_name, PSTR("PKT")); // -> dann BT-Name auf "PKT" setzen
strrtrim( Config.bt_name ); // ggf. Leerzeichen rechts loeschen
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Delay_MS(int count)
{
for (int i = 0; i < count; i++)
_delay_ms(1);
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void bt_start(void)
{
if( Config.BTIsSlave == true ) EchoAnswerOn = false;
else EchoAnswerOn = true;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void uart_receive(void)
{
unsigned int uart_data;
 
while( !fifo_is_full(&in_fifo) )
{
uart_data = uart1_getc();
 
//USART_puts(".");
if (!(uart_data==UART_NO_DATA)) USART_putc(uart_data);
 
switch( uart_data & 0xFF00 )
{
// Framing Error detected, i.e no stop bit detected
case UART_FRAME_ERROR:
bt_rxerror++;
bt_frameerror++;
return;
 
// Overrun, a character already presend in the UART UDR register was
// not read by the interrupt handler before the next character arrived,
// one or more received characters have been dropped
//
case UART_OVERRUN_ERROR:
bt_rxerror++;
bt_overrun++;
return;
 
// We are not reading the receive buffer fast enough,
// one or more received character have been dropped
//
case UART_BUFFER_OVERFLOW:
bt_rxerror++;
bt_bufferoverflow++;
return;
 
// UART Inputbuffer empty, nothing to do
case UART_NO_DATA:
return;
 
default:
fifo_write( &in_fifo, uart_data);
}
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
static void uart_send(const char *data, const uint8_t length)
{
#ifdef SND_DEBUG
debug_pgm(PSTR("bt_uart_send"));
if (comm_mode == BT_CMD) debug_pgm(PSTR("bt_uart_send:BT_CMD")); else debug_pgm(PSTR("bt_uart_send:Wrong comm-mode"));
if (EchoAnswerOn == true) debug_pgm(PSTR("bt_uart_send:EchoAnswer ON")); else debug_pgm(PSTR("bt_uart_send:EchoAnswer OFF"));
#endif
 
char echo;
 
// lcd_printp_at (i++, 1, PSTR("."), 0);
for (uint8_t i = 0; i < length; i++)
{
 
#ifdef SND_DEBUG
USART_putc((data[i])); //test
#endif
// debug_pgm(PSTR("bt_init_S"));
 
if (uart1_putc(data[i]) == 0)
{
#ifdef SND_DEBUG
warn_pgm(PSTR("UART: Remote not ready"));
#endif
return;
}
 
if (comm_mode == BT_RAW)
_delay_ms(50);
 
if (comm_mode == BT_DATA)
_delay_ms(1);
 
 
if ((comm_mode == BT_CMD) && (EchoAnswerOn == true))
{
#ifdef SND_DEBUG
warn_pgm(PSTR ("UARTsend: get Echo"));
#endif
uint8_t x = 0;
for (; x < 3; x++)
{
 
while_timeout(fifo_is_empty(&in_fifo), 200)
// for(uint16_t __timeout = 0; __timeout++ <= 200 && (fifo_is_empty(&in_fifo)); _delay_ms(200 ? 1 : 0))
 
uart_receive();
 
 
fifo_read(&in_fifo, &echo);
 
if (echo != data[i]) {
if (uart1_putc(data[i]) == 0)
{
#ifdef SND_DEBUG
warn_pgm(PSTR ("UART: Remote not ready"));
#endif
return;
}
}
else
break;
}
#ifdef DEBUG
if (x == 3)
{
 
error_putc(data[i]);
 
error_pgm(PSTR("BT: WRONG ECHO"));
//_delay_ms(2000);
 
}
#endif
}
else
{
{
uart_receive();
fifo_read(&in_fifo, &echo);
 
}
 
#ifdef SND_DEBUG
warn_pgm(PSTR ("UARTsend: skip Echo"));
#endif
}
}
}
 
 
//--------------------------------------------------------------
// send_cmd( command, *data)
//--------------------------------------------------------------
static uint16_t send_cmd( const bt_cmd_t command, const char *data)
{
uint16_t CommandDelay; // nach BTM222 Kommandos verschiedene Verzögerungszeiten bevor es weitergehen kann
uint8_t i;
 
char full_command[20]; // Maximum command size
 
CommandDelay = 100; // Default = 100ms
 
switch( command )
{
case BT_SET_PIN: strcpy_P( full_command, PSTR("ATP="));
for( i = 0; i < bt_pin_length; i++)
{
full_command[i+4] = Config.bt_pin[i];
}
full_command[(bt_pin_length+4)] = 0;
break;
 
case BT_SET_DEFAULT: strcpy_P( full_command, PSTR("ATZ0"));
CommandDelay = 3000;
break;
 
 
case BT_SET_2400: strcpy_P( full_command, PSTR("ATL*"));
#ifdef DEBUG
debug_pgm(PSTR("ATL*"));
#endif
break;
 
case BT_SET_4800: strcpy_P( full_command, PSTR("ATL0"));
#ifdef DEBUG
debug_pgm(PSTR("ATL0"));
#endif
break;
 
case BT_SET_9600: strcpy_P( full_command, PSTR("ATL1"));
#ifdef DEBUG
debug_pgm(PSTR("ATL1"));
#endif
break;
 
case BT_SET_19200: strcpy_P( full_command, PSTR("ATL2"));
#ifdef DEBUG
debug_pgm(PSTR("ATL2"));
#endif
break;
 
case BT_SET_38400: strcpy_P( full_command, PSTR("ATL3"));
#ifdef DEBUG
debug_pgm(PSTR("ATL3"));
#endif
break;
 
case BT_SET_57600: strcpy_P( full_command, PSTR("ATL4"));
#ifdef DEBUG
debug_pgm(PSTR("ATL4"));
#endif
break;
 
case BT_SET_115200: strcpy_P( full_command, PSTR("ATL5"));
#ifdef DEBUG
debug_pgm(PSTR("ATL5"));
#endif
break;
 
case BT_SET_NOANSWER: strcpy_P( full_command, PSTR("ATQ1"));
#ifdef DEBUG
debug_pgm(PSTR("ATQ1"));
#endif
break;
 
case BT_SET_NOECHO: strcpy_P( full_command, PSTR("ATE0"));
#ifdef DEBUG
debug_pgm(PSTR("ATE0"));
#endif
break;
 
case BT_SET_ANSWER: strcpy_P( full_command, PSTR("ATQ0"));
#ifdef DEBUG
debug_pgm(PSTR("ATQ0"));
#endif
break;
 
case BT_SET_ECHO: strcpy_P( full_command, PSTR("ATE1"));
#ifdef DEBUG
debug_pgm(PSTR("ATE1"));
#endif
break;
 
case BT_TEST: strcpy_P( full_command, PSTR("AT"));
#ifdef DEBUG
debug_pgm(PSTR("AT"));
#endif
break;
 
case BT_CONNECT: strcpy_P( full_command, PSTR("ATA"));
#ifdef DEBUG
debug_pgm(PSTR("ATA"));
#endif
break;
 
case BT_DISCONNECT: strcpy_P( full_command, PSTR("ATH"));
#ifdef DEBUG
debug_pgm(PSTR("ATH"));
#endif
break;
 
case BT_CLEAR_ADDRESS: strcpy_P( full_command, PSTR("ATD0"));
break;
 
case BT_SET_ADDRESS: strcpy_P( full_command, PSTR("ATD="));
memcpy( (full_command + strlen(full_command)), data, 12);
full_command[16] = 0;
#ifdef DEBUG
debug_pgm(PSTR("ATLD="));
#endif
break;
 
case BT_FIND_DEVICES: strcpy_P( full_command, PSTR("ATF?"));
#ifdef DEBUG
debug_pgm(PSTR("ATF?"));
#endif
break;
 
case BT_DISABLE_AUTOCONNECT:
strcpy_P( full_command, PSTR("ATO1"));
CommandDelay = 3500;
#ifdef DEBUG
debug_pgm(PSTR("ATO1"));
#endif
break;
 
case BT_ENABLE_AUTOCONNECT:
strcpy_P( full_command, PSTR("ATO0"));
CommandDelay = 3500;
#ifdef DEBUG
debug_pgm(PSTR("ATO0"));
#endif
break;
 
case BT_SET_MASTER: strcpy_P( full_command, PSTR("ATR0"));
CommandDelay = 3000;
#ifdef DEBUG
debug_pgm(PSTR("ATR0"));
#endif
break;
 
case BT_SET_SLAVE: strcpy_P( full_command, PSTR("ATR1"));
CommandDelay = 3000;
#ifdef DEBUG
debug_pgm(PSTR("ATR1"));
#endif
break;
 
case BT_SET_NAME: strcpy_P( full_command, PSTR("ATN=") );
strcat( full_command, Config.bt_name);
//lcd_print_at( 0, 7, full_command, 0); // DEBUG
//lcdx_printf_at( 17, 7, MNORMAL, 0,0, "%3d", strlen(full_command) );
//_delay_ms(6000);
#ifdef DEBUG
debug_pgm(PSTR("ATN="));
#endif
break;
 
case BT_SET_DISPWRDOWN: strcpy_P(full_command, PSTR("ATS1"));
#ifdef DEBUG
debug_pgm(PSTR("ATS1"));
#endif
break;
 
case BT_GET_LOCALID: strcpy_P(full_command, PSTR("ATB?"));
#ifdef DEBUG
debug_pgm(PSTR("ATB?"));
#endif
break;
case BT_SHOW_SETTINGS: strcpy_P(full_command, PSTR("ATI1"));
break;
 
default: warn_pgm(PSTR("CMD UNK"));
CommandDelay = 0;
return false;
}
 
strcat_P( full_command, PSTR("\r") );
 
// throw away your television
uart_receive();
fifo_clear( &in_fifo );
 
// send command
uart_send( full_command, strlen(full_command));
 
// get response
#ifdef DEBUG
debug_pgm(PSTR("send_cmd:get Response"));
#endif
 
 
if( !EchoAnswerOn )
{
_delay_ms(CommandDelay);
uart1_flush();
fifo_clear(&in_fifo);
return true;
}
else
{
while_timeout(true, BT_CMD_TIMEOUT_MS)
{
uart_receive();
 
if( command == BT_GET_LOCALID )
{
_delay_ms(CommandDelay);
return bt_getID();
}
 
if( fifo_strstr_pgm( &in_fifo, PSTR("OK\r\n")) )
{
_delay_ms(CommandDelay);
return true;
}
 
if( fifo_strstr_pgm(&in_fifo, PSTR("ERROR\r\n")) )
{
return false;
}
} // end: while_timeout()
}
 
return false;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
static void clean_line(void)
{
while_timeout(true, 50)
uart_receive();
 
fifo_strstr_pgm( &in_fifo, PSTR("\r\n") );
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
static communication_mode_t update_comm_mode( uint16_t timeout_ms )
{
while_timeout(true, timeout_ms)
{
uart_receive();
 
if( fifo_strstr_pgm(&in_fifo, PSTR("DISCONNECT")) )
{
clean_line();
comm_mode = BT_CMD;
send_cmd(BT_TEST, NULL);
return comm_mode;
}
 
if( fifo_strstr_pgm(&in_fifo, PSTR("CONNECT")) )
{
_delay_ms(100); // don't delete this, else there will be no success!!!!!!!!!
comm_mode = BT_DATA;
return comm_mode;
}
 
if( fifo_strstr_pgm (&in_fifo, PSTR("Time out,Fail to connect!")) )
{
clean_line();
 
#ifdef DEBUG
debug_pgm(PSTR("CONNECT FAILED\n"));
#endif
 
send_cmd(BT_TEST, NULL);
comm_mode = BT_CMD;
return comm_mode;
}
}
 
return comm_mode;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void bt_set_EchoAnswer( uint8_t on )
{
comm_mode = BT_CMD; // Set comm_mode to CMD
EchoAnswerOn = false;
 
if( on )
{
send_cmd( BT_SET_ECHO , NULL);
send_cmd( BT_SET_ANSWER , NULL);
send_cmd( BT_TEST , NULL);
// EchoAnswerOn = true;
 
/*
if( !send_cmd( BT_TEST , NULL) )
{
//lcd_printp_at (0, 6, PSTR("Error set Echo"), MNORMAL);
//_delay_ms(3000);
}
*/
}
else
{
send_cmd( BT_SET_NOECHO , NULL);
send_cmd( BT_SET_NOANSWER, NULL);
// EchoAnswerOn = false;
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint16_t BTM222_SetBaud( uint8_t baudrate )
{
bt_cmd_t btcommand = BT_SET_57600;
uint8_t lOk = true;
 
 
comm_mode = BT_CMD; // Set comm_mode to CMD
uart1_flush();
fifo_clear( &in_fifo );
 
bt_set_EchoAnswer(true);
 
if( !send_cmd(BT_TEST, NULL) ) // Test mit PKT_Baudrate
{
return false;
}
else
{
switch( baudrate )
{
case Baud_2400: btcommand = BT_SET_2400; break;
case Baud_4800: btcommand = BT_SET_4800; break;
case Baud_9600: btcommand = BT_SET_9600; break;
case Baud_19200: btcommand = BT_SET_19200; break;
case Baud_38400: btcommand = BT_SET_38400; break;
case Baud_57600: btcommand = BT_SET_57600; break;
case Baud_115200: btcommand = BT_SET_115200; break;
}
 
if( !(send_cmd( btcommand, NULL)) ) lOk = false; // Fehler
 
SetBaudUart1( baudrate );
uart1_flush();
fifo_clear( &in_fifo );
send_cmd( BT_TEST, NULL);
 
if( !(send_cmd(BT_TEST, NULL)) ) lOk = false; // Fehler
 
bt_set_EchoAnswer(false);
}
 
return lOk;
}
 
 
 
//--------------------------------------------------------------
// foundbaud = BTM222_CheckBaud( Baudrate )
//
// suche BTM222 mit entsprechender Baudrate
//
// RUECKGABE:
// =0: Error (BTM222 not found at given Baud)
// >0: Baudrate
//
// INFO: Baudrate
// Baud_9600 1
// Baud_19200 2
// Baud_38400 3
// Baud_57600 4
// Baud_115200 5
// Baud_4800 6
// Baud_2400 7
//--------------------------------------------------------------
uint8_t BTM222_CheckBaud( uint8_t Baudrate )
{
//lcdx_cls_row( y, mode, yoffs )
lcdx_cls_row( 2, MNORMAL, 1 ); // Zeile loeschen
lcdx_printf_center_P( 2, MNORMAL, 0,1, PSTR("%S %lu Baud"), strGet(STR_SEARCH), Baud_to_uint32(Baudrate) ); // "suche nnn Baud"
 
comm_mode = BT_CMD; // Set comm_mode to CMD
SetBaudUart1( Baudrate );
 
uart1_flush();
fifo_clear( &in_fifo );
 
EchoAnswerOn = false;
 
send_cmd( BT_TEST , NULL);
send_cmd( BT_SET_ANSWER, NULL);
send_cmd( BT_SET_ECHO , NULL);
 
EchoAnswerOn = true;
 
 
if( send_cmd(BT_TEST, NULL) )
{
return Baudrate; // BTM222 Baudrate gefunden
}
 
return 0; // 0 = nicht gefunden
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void BTM222_Initalize( void )
{
uint8_t foundbaud = 0;
uint8_t nError = 0;
 
// ggf. rechte Leerzeichen oder ungueltige Zeichen
// von bt_name entfernen
bt_fixname();
 
 
//----------------------------
// 1. Frage: initialisieren?
//----------------------------
// Text1: "Kopter ausschalten!"
// Text2: NULL
// Head : "* ACHTUNG *"
// Titel: "Wi.232 Init"
 
if( !PKT_Ask_P( ASK_CANCEL_OK, PSTR("initialisieren?"), NULL, STR_BTM222INIT, STR_BTM222INIT) )
{
return;
}
 
 
 
//------------------------------------
// 2. BTM222 suchen
//------------------------------------
PKT_Title_P( STR_BTM222INIT, true, true ); // Titel - mit ShowLipo und clearscreen
lcdx_printf_center_P( 2, MNORMAL, 0,1, PSTR("%S %lu Baud"), strGet(STR_SEARCH), Baud_to_uint32(Old_Baudrate) ); // "suche nnn Baud"
 
set_Modul_On( Bluetooth );
EchoAnswerOn = false;
 
fifo_init( &in_fifo, bt_buffer, IN_FIFO_SIZE);
 
if( !foundbaud ) foundbaud = BTM222_CheckBaud( Old_Baudrate ); // versuche zuerst mit der 'alten' Baudrate (hohe Trefferwahrscheinlichkeit)
if( !foundbaud ) foundbaud = BTM222_CheckBaud( Baud_2400 );
if( !foundbaud ) foundbaud = BTM222_CheckBaud( Baud_9600 );
if( !foundbaud ) foundbaud = BTM222_CheckBaud( Baud_19200 );
if( !foundbaud ) foundbaud = BTM222_CheckBaud( Baud_38400 );
if( !foundbaud ) foundbaud = BTM222_CheckBaud( Baud_57600 );
if( !foundbaud ) foundbaud = BTM222_CheckBaud( Baud_115200 );
 
if( !foundbaud )
{
//PKT_Message_P( text, error, timeout, beep, clearscreen)
PKT_Message_P( PSTR("BTM222 not found!"), true, 2000, true, true); // ERROR: max. 20 Sekunden anzeigen
Config.UseBT = false; // Modul in Konfig sperren, verhindert Init beim Start
}
 
 
//------------------------------------
// 2. Initialisieren
//------------------------------------
if( foundbaud > 0 )
{
PKT_Title_P( STR_BTM222INIT, true, true ); // Titel: mit ShowLipo und clearscreen
lcdx_printf_center_P( 2, MNORMAL, 0,1, STR_BTM222INIT ); // Headline
 
//PKT_Progress_Init( max, yoffs, width, height);
PKT_Progress_Init( 7, 0, 0,0); // 7 Progress Steps
 
comm_mode = BT_CMD; // Set comm_mode to CMD
 
if( !nError && PKT_Progress_Next() && !send_cmd( BT_CLEAR_ADDRESS, NULL) ) nError = 1; // Clear remote address
if( !nError && PKT_Progress_Next() && !send_cmd( BT_SET_SLAVE, NULL) ) nError = 2; // Set BTM to SLAVE
if( !nError && PKT_Progress_Next() && !send_cmd( BT_SET_PIN, NULL) ) nError = 3; // Set BTM PIN
if( !nError && PKT_Progress_Next() && !send_cmd( BT_SET_NAME, NULL) ) nError = 4; // Set BTM Name
if( !nError && PKT_Progress_Next() && !send_cmd( BT_SET_DISPWRDOWN, NULL) ) nError = 5;
if( !nError && PKT_Progress_Next() && !send_cmd( BT_GET_LOCALID, NULL) ) nError = 6; // MAC ermitteln
//if( !nError && PKT_Progress_Next() && !send_cmd( BT_SET_ANSWER, NULL) ) nError = 7;
 
if( !nError && PKT_Progress_Next() && !BTM222_SetBaud( Config.PKT_Baudrate)) nError = 8; // Set BTM Baudrate
//if( !nError && PKT_Progress_Next() && !BTM222_SetBaud( Baud_38400)) nError = 8; // * TEST/DEBUG * Set BTM Baudrate
 
 
SetBaudUart1( Config.PKT_Baudrate ); // PKT wieder auf Original Baudrate setzen
 
if( !nError )
{
bt_set_EchoAnswer( false );
bt_mode = BLUETOOTH_SLAVE;
 
WriteBTInitFlag(); // Init merken
WriteBTSlaveFlag();
 
bt_start();
set_Modul_On( USB );
 
//PKT_Message_P( text, error, timeout, beep, clearscreen)
PKT_Message_P( PSTR("BTM222 Init OK!"), false, 1000, true, true); // OK: 1000 = max. 10 Sekunden anzeigen
return;
}
else
{
set_Modul_On(USB);
 
//PKT_Message( text, error, timeout, beep, clearscreen)
PKT_Message( buffered_sprintf_P(PSTR("BTM Error: %d"),nError), true, 2000, true, true); // ERROR: 2000 = max. 20 Sekunden anzeigen
return;
}
}
 
SetBaudUart1( Config.PKT_Baudrate ); // die richtige UART Baudrate wiederherstellen !!
set_Modul_On( USB );
clear_key_all();
 
return;
}
 
 
 
//######################################################################################
//######################################################################################
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t bt_set_mode( const bt_mode_t mode )
{
#ifdef DEBUG
debug_pgm(PSTR("bt_setmode: set Mode"));
#endif
 
//if (update_comm_mode(0) == BT_DATA) // 30.1.2012 CB
// return false;
 
if( mode == bt_mode )
return true;
 
if( mode == BLUETOOTH_MASTER )
{
comm_mode = BT_CMD;
bt_set_EchoAnswer(true);
 
if( send_cmd(BT_SET_MASTER, NULL) )
{
bt_mode = BLUETOOTH_MASTER;
send_cmd(BT_DISABLE_AUTOCONNECT, NULL);
WriteBTMasterFlag();
 
#ifdef DEBUG
debug_pgm(PSTR("bt_setmode: Master is set"));
#endif
}
}
 
if( mode == BLUETOOTH_SLAVE )
{
comm_mode = BT_CMD;
bt_set_EchoAnswer(true);
 
if( send_cmd(BT_ENABLE_AUTOCONNECT, NULL) )
{
bt_mode = BLUETOOTH_SLAVE;
send_cmd(BT_SET_SLAVE, NULL);
WriteBTSlaveFlag();
bt_set_EchoAnswer(false);
comm_mode = BT_CMD;
 
#ifdef DEBUG
debug_pgm(PSTR("bt_setmode: Slave is set"));
#endif
}
}
 
// if (bt_mode == BLUETOOTH_MASTER) debug_pgm(PSTR("bt_mode:BLUETOOTH_MASTER "));
// if (bt_mode == BLUETOOTH_SLAVE) debug_pgm(PSTR("bt_mode:BLUETOOTH_SLAVE"));
// if (mode == BLUETOOTH_MASTER) debug_pgm(PSTR("mode:BLUETOOTH_MASTER "));
// if (mode == BLUETOOTH_SLAVE) debug_pgm(PSTR("mode:BLUETOOTH_SLAVE"));
 
return (mode == bt_mode);
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint16_t bt_receive( void *data, uint8_t length, uint16_t timeout_ms )
{
uint8_t rec_length = 0;
uint8_t i = 0;
 
//while_timeout(true, timeout_ms);
for( uint16_t __timeout = 0; __timeout++ <= true && (timeout_ms); _delay_ms(true ? 1 : 0))
{
if( i == length )
return true;
 
uart_receive();
 
if( fifo_is_empty(&in_fifo) )
continue;
 
if( update_comm_mode(0) != BT_DATA)
{
#ifdef DEBUG
debug_pgm(PSTR("not connected"));
#endif
 
return false;
}
 
 
if( timeout_ms == 0 ) // We have a connection
timeout_ms += 2000;
 
if( fifo_is_empty(&in_fifo) )
continue;
 
 
if( !rec_length ) // Find starting point of packet
{
fifo_read( &in_fifo, (char *)&rec_length);
 
if( rec_length != length )
{
rec_length = 0;
}
else
{
timeout_ms += 2000;
}
}
else
{
fifo_read( &in_fifo, (char *)data + i);
i++;
}
}
return false;
}
 
 
 
 
#ifndef SaveMem
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint16_t bt_send( void *data, const uint8_t length )
{
if (update_comm_mode(0) == BT_CMD)
return false;
 
uart_send((const char *)&length, 1);
uart_send((char *)data, length);
return (update_comm_mode(0) == BT_DATA);
}
 
 
#ifdef SQUIRREL
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint16_t bt_connect( const char *address )
{
fifo_init(&in_fifo, bt_buffer, IN_FIFO_SIZE);
uart_receive();
fifo_clear(&in_fifo);
 
// Maybe we already disconnected???
if (BT_DATA == update_comm_mode(0))
{
#ifdef DEBUG
debug_pgm(PSTR("We are still connected..."));
#endif
return false;
}
 
// send_cmd(BT_TEST, NULL);
 
 
/*
if (!send_cmd(BT_DISABLE_AUTOCONNECT, address))
return false;
*/
 
send_cmd(BT_TEST, NULL);
 
#ifdef DEBUG
debug_pgm (PSTR ("SET_ADD"));
#endif
 
if (!send_cmd(BT_SET_ADDRESS, address))
return false;
 
send_cmd(BT_TEST, NULL);
 
#ifdef DEBUG
debug_pgm (PSTR ("CONNECT"));
#endif
 
if (!send_cmd(BT_CONNECT, NULL))
return false;
 
#ifdef DEBUG
debug_pgm (PSTR ("WAIT FOR COMM"));
#endif
 
return (BT_DATA == update_comm_mode(20000));
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint16_t bt_disconnect(void)
{
uint8_t RetVal = false;
 
for( uint8_t i = 0; i < 4; i++) // Switch to online cmd mode
{
const char plus = '+';
uart_send(&plus, 1);
_delay_ms(1000);
}
 
comm_mode = BT_CMD;
EchoAnswerOn = true;
uart1_flush(); // noch nicht verarbeitete Daten löschen
fifo_clear(&in_fifo);
 
 
if( !send_cmd(BT_DISCONNECT, NULL) )
RetVal = false;
 
if( BT_CMD == update_comm_mode(2000) ) // neue Position um Disconnect-Antwort zu finden
{
fifo_clear(&in_fifo);
RetVal = true;
}
 
if( !send_cmd(BT_CLEAR_ADDRESS, NULL) )
RetVal = false;
 
 
// if( BT_CMD == update_comm_mode(2000) ) // 31.7.2015 CB ursprüngliche Position, wurde verschoben
// {
// fifo_clear(&in_fifo);
// return true;
// }
 
#ifdef DEBUG
debug_pgm(PSTR("Still in DATA??"));
#endif
 
return RetVal;
}
 
 
 
/*
BTM-222 Softwareversion 4.35
Inquiry Results:
111111111222222222233333333334
01234567890123456789012345678901234567890
 
1 LE091452 0024-2C-BEB0CA
2 E71 c 0024-7C-3EC9B9
 
BTM-222 Softwareversion 6.26
Inquiry Results:
1 E71 c 0024-7C-3EC9B9 N.A.
2 LE091452 0024-2C-BEB0CA N.A.
 
*/
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void copy_mac(const char *src, char *dst)
{
uint8_t off = 0;
 
for (uint8_t i = 0; i < 40; i++)
{
if (src[i] == '-')
if (src[i+3] == '-')// MAC Adresse suchen
{
off = i-4;
break;
}
}
 
for (uint8_t i = 0; i < 14; i++)
{
if (src[i + off] == '-')
off++;
 
dst[i] = src[i + off];
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void copy_localID(const char *src, char *dst)
{
uint8_t off = 0;
 
//for (uint8_t i = 0; i < 40; i++)
//{
// if (src[i] == '-') if (src[i+3] == '-')// MAC Adresse suchen
// {
// off = i-4;
// break;
// }
//}
 
for (uint8_t i = 0; i < 14; i++)
{
if (src[i + off] == '-')
off++;
 
dst[i] = src[i + off];
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void copy_DevName(const char *src, char *dst)
{
uint8_t off = 0;
uint8_t i = 0;
 
for (i = 0; i < 18; i++)
{
if (src[i] == ' ' && src[i+1] == ' ')
{
dst[i] = 0; //Stringende
break; // nach zwei Leerzeichen ist der Name zuende
}
dst[i] = src[i + off];
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t bt_discover( void )
{
char buffer[255]; //oversized, but who cares?
char *bufferhead = buffer;
uint16_t devcount = 0;
uint16_t Timeout = 10000;
uint8_t progress = 0;
uint8_t keyesc = false;
 
 
#define BT_SEARCHTIME 7500 // = 75 Sekunden BT-Geraete suchen (60 werden vom BTM222 min. dafuer veranschlagt + 15 Sekunden Sicherheit)
#define PROGRESSUPDATE 100 // = 1 Sekunde - jede Sekunde die Progressbar updaten bei BT-Inquiry
 
 
//PKT_Progress_Init( max, yoffs, width,height)
PKT_Progress_Init( 4 + ((BT_SEARCHTIME/PROGRESSUPDATE)+1), 0, 0,0); // Anzahl der gesamten Progress Steps
 
 
PKT_Progress_Next(); // Progressbar: Extra 1
 
//------------------------
//------------------------
if( !bt_set_mode( BLUETOOTH_MASTER) )
return 0;
 
PKT_Progress_Next(); // Progressbar: Extra 2
 
send_cmd( BT_TEST, NULL);
 
fifo_clear( &in_fifo );
 
if( !send_cmd( BT_FIND_DEVICES, NULL) )
return 0;
 
PKT_Progress_Next(); // Progressbar: Extra 3
 
//------------------------
//------------------------
do
{
uart_receive();
Timeout--;
 
_delay_ms(1);
 
//write_ndigit_number_u( 0,7,fifo_getcount( &in_fifo) ,5,0,0);
 
if( fifo_is_full(&in_fifo) )
break;
 
if( get_key_short(1 << KEY_ESC) ) // 3. Taste
{
keyesc = true;
break;
}
 
} while( (Timeout != 0) && (!fifo_strstr_pgm(&in_fifo, PSTR("Inquiry Results:\r\n"))) );
 
 
fifo_clear( &in_fifo );
 
 
//------------------------
//------------------------
if( Timeout!=0 && !keyesc )
{
// 25.06.2014 OG: umgestellt auf zeitliches Timeout anstatt einer Zaehlschleife
 
timer3 = BT_SEARCHTIME; // 75 Sekunden BT Device suchen
 
while( timer3 && (!fifo_search( &in_fifo, PSTR("Inquiry End"))))
{
if( (timer3 / PROGRESSUPDATE) != progress ) // Progressbar: next step
{
progress = (timer3 / PROGRESSUPDATE);
PKT_Progress_Next();
}
 
uart_receive();
_delay_ms(2); // 25.06.2014 OG: diese Verzoegerung muss aktuell sein - sonst werden scheinbar keine Geraete gefunden :-(
 
if( get_key_short(1 << KEY_ESC) ) // 3. Taste
{
//keyesc = true;
break;
}
}
}
 
 
PKT_Progress_Next(); // Progressbar: Extra 4
 
 
//set_beep( 300, 0xffff, BeepNormal ); _delay_ms(3000); // Test um das Ende der Progressbar zu ueberpruefen
 
 
//------------------------
//------------------------
while( !fifo_is_empty( &in_fifo) )
{
while( !fifo_cmp_pgm( &in_fifo, PSTR("\r\n")) ) // Get next line
{
fifo_read( &in_fifo, bufferhead);
bufferhead++;
}
 
*bufferhead = 0; // terminate string
 
bufferhead = buffer; // reset bufferhead
 
// write_ndigit_number_u( 0,6,devcount ,5,0,0);
// set_beep( 300, 0xffff, BeepNormal );
// _delay_ms(1000);
 
 
if( strlen(buffer) == 0 ) // the empty line before end of inquiry
continue;
 
if( strstr_P( buffer, PSTR("Inquiry End")))
{
break;
}
 
copy_DevName( &buffer[3], device_list[devcount].DevName);
copy_mac( &buffer[3], device_list[devcount].mac);
 
devcount++;
 
 
if( devcount >= NUTS_LIST )
{
break;
}
 
} // end: while( !fifo_is_empty(&in_fifo) )
 
clear_key_all();
 
return devcount;
}
 
 
//--------------------------------------------------------------
uint8_t bt_showsettings( void )
{
char buffer[512]; //oversized, but who cares?
char *bufferhead = buffer;
uint16_t Timeout = 100;
bt_rxerror = 0;
 
fifo_init( &in_fifo, bt_buffer, IN_FIFO_SIZE);
uart1_flush();
 
PKT_Progress_Init( 4 , 0, 0,0); // Anzahl der gesamten Progress Steps
PKT_Progress_Next(); // Progressbar: Extra 1
 
if( !bt_set_mode( BLUETOOTH_MASTER) )
return 0;
 
// if (EchoAnswerOn) ScrollBox_Push_P( MNORMAL, PSTR("1 E A on") ); else ScrollBox_Push_P( MNORMAL, PSTR("1 E A off") );
 
PKT_Progress_Next(); // Progressbar: Extra 2
 
EchoAnswerOn = true;
if( !send_cmd( BT_SHOW_SETTINGS, NULL) )
ScrollBox_Push_P( MNORMAL, PSTR("Command Error") );
 
PKT_Progress_Next(); // Progressbar: Extra 3
 
do
{
uart_receive();
// write_ndigit_number_u( 0,6,fifo_getcount( &in_fifo) ,5,0,0);
Timeout--;
_delay_ms(2);
if( fifo_is_full(&in_fifo) )
{
ScrollBox_Push_P( MNORMAL, PSTR("Fifo is full") );
break;
}
 
} while(Timeout != 0 );
// } while( (Timeout != 0) && (!fifo_search(&in_fifo, PSTR("+++"))) );
 
PKT_Progress_Next(); // Progressbar: Extra 4
 
while( !fifo_is_empty( &in_fifo) )
{
while( !fifo_cmp_pgm( &in_fifo, PSTR("\r\n")) ) // Get next line
{
fifo_read( &in_fifo, bufferhead);
bufferhead++;
}
*bufferhead = 0; // terminate string
bufferhead = buffer; // reset bufferhead
if( strlen(buffer) == 0 ) // the empty line before end of inquiry
continue;
ScrollBox_Push( MNORMAL, buffer );
 
} // end: while( !fifo_is_empty(&in_fifo) )
clear_key_all();
// if (EchoAnswerOn) ScrollBox_Push_P( MNORMAL, PSTR("2 E A on") ); else ScrollBox_Push_P( MNORMAL, PSTR("2 E A off") );
 
return true;
}
 
 
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
/*
uint16_t bt_discover_OLD( char result[8][12] )
{
char buffer[255]; //oversized, but who cares?
char *bufferhead = buffer;
uint16_t pos = 0;
uint16_t Timeout = 10000;
uint16_t posC = 0;
uint8_t Result=false;
 
PKT_Progress_Init( 25, 0, 0,0); // 25 Progress Steps
 
if (!bt_set_mode(BLUETOOTH_MASTER)) Result = false;
PKT_Progress_Next(); // Progressbar
 
send_cmd(BT_TEST, NULL);
if( !send_cmd(BT_FIND_DEVICES, NULL)) Result = false;
PKT_Progress_Next(); // Progressbar
 
do
{
uart_receive();
Timeout--;
 
posC++;
_delay_ms(1);
write_ndigit_number_u(0,5,fifo_getcount(&in_fifo),5,0,0);
if (posC ==1000)
{
PKT_Progress_Next(); // Progressbar
posC = 0;
}
 
if (fifo_is_full(&in_fifo)) break;
 
} while( (Timeout != 0) && (!fifo_strstr_pgm(&in_fifo, PSTR("Inquiry Results:\r\n"))) );
 
 
if (Timeout==0)
{
Result = false;
}
else
{
for (uint16_t i = 0; i < 40000; i++)
{
if( (i % 2000) == 0 )
PKT_Progress_Next(); // Progressbar
uart_receive();
write_ndigit_number_u( 0,5,fifo_getcount(&in_fifo),5,0,0);
_delay_ms(1);
}
}
 
 
while( !fifo_is_empty(&in_fifo) )
{
// Get next line
while (!fifo_cmp_pgm(&in_fifo, PSTR("\r\n")))
{
fifo_read(&in_fifo, bufferhead);
bufferhead++;
}
// terminate string
*bufferhead = 0;
 
//reset bufferhead
bufferhead = buffer;
 
if (strlen(buffer) == 0)
continue; //the empty line before end of inquiry
 
if( strstr_P(buffer, PSTR("Inquiry End")))
//if (searchend)
{
fifo_clear(&in_fifo);
return true;
}
 
copy_DevName(&buffer[3],device_list[pos].DevName);
copy_mac(&buffer[3], device_list[pos].mac);
pos++;
 
} // end: while( !fifo_is_empty(&in_fifo) )
 
return Result;
}
*/
 
 
 
 
 
 
//--------------------------------------------------------------
// ermittelt die MAC vom BTM2222
//--------------------------------------------------------------
uint8_t bt_getID( void )
{
//char buffer[255]; //oversized, but who cares?
char buffer[80]; //oversized, but who cares?
char *bufferhead = buffer;
uint8_t i;
 
 
while_timeout( !fifo_strstr_pgm(&in_fifo, PSTR("r\n")), 2000)
uart_receive();
 
 
while( !fifo_is_empty(&in_fifo) )
{
while( !fifo_cmp_pgm( &in_fifo, PSTR("\r\n")) ) // Get next line
{
fifo_read( &in_fifo, bufferhead);
bufferhead++;
}
 
*bufferhead = 0; // terminate string
 
bufferhead = buffer; // reset bufferhead
 
if( strlen(buffer) == 0 )
continue; // the empty line before end of inquiry
 
copy_localID( &buffer[0], &localID[0] );
 
for( i = 0; i < 13; i++)
{
//lcd_putc (i, 6, localID[i],0);
Config.bt_Mac[i] = localID[i];
}
 
 
if( fifo_strstr_pgm(&in_fifo, PSTR("OK")) )
{
fifo_clear( &in_fifo );
return true;
}
else
{
return false;
}
 
} // end: if( !fifo_is_empty(&in_fifo) )
 
return false;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void bt_downlink_init(void)
{
fifo_init( &in_fifo, bt_buffer, IN_FIFO_SIZE);
_delay_ms(100);
// debug_pgm(PSTR("bt_downlink_init"));
uart_receive();
fifo_clear(&in_fifo);
// send_cmd(BT_TEST, NULL);
 
#ifdef DEBUG
debug_pgm(PSTR("downlink_init Start"));
#endif
 
if( Config.BTIsSlave == true ) // nur Init wenn BT ist Slave
{
#ifdef DEBUG
debug_pgm(PSTR("downlink_init:try to set Master"));
#endif
 
//comm_mode = BT_NOECHO;
//
//if (!send_cmd (BT_SET_ECHO,NULL))
//{
// #ifdef DEBUG
// debug_pgm(PSTR("downlink_init:Couldn't set Echo!"));
// #endif
//}
//
//comm_mode = BT_NOANSWER;
//if (!send_cmd(BT_SET_ANSWER,NULL))
//{
// #ifdef DEBUG
// debug_pgm(PSTR("downlink_init:Couldn't set Answer!"));
// #endif
//
//}
 
comm_mode = BT_CMD;
//send_cmd(BT_TEST, NULL);
 
bt_set_EchoAnswer(true);
 
if( !bt_set_mode(BLUETOOTH_MASTER) )
{
#ifdef DEBUG
debug_pgm(PSTR("downlink_init:Couldn't set master!"));
#endif
 
return;
}
 
#ifdef DEBUG
debug_pgm(PSTR("downlink_init:master is set "));
#endif
 
//WriteBTMasterFlag(); // Master merken
comm_mode = BT_CMD;
}
else
{
#ifdef DEBUG
debug_pgm(PSTR("downlink_init:Master was set"));
#endif
 
comm_mode = BT_CMD;
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void bt_searchDevice( void ) //Bluetoothgeräte suchen
{
bt_devicecount = bt_discover();
}
 
 
 
 
//
////--------------------------------------------------------------
//uint16_t bt_receiveNMEA2(void)
//{
//
// char received;
// static uint8_t line_flag = 1;
// static char* ptr_write = bt_rx_buffer;
// uint16_t timeout_ms=2000;
//
//// while_timeout(true, timeout_ms) {
//while(1){
//
// uart_receive();
// if (fifo_is_empty(&in_fifo))
// continue;
// fifo_read(&in_fifo, &received);
// USART_putc(received);
//// _delay_ms(1);
// }
////
//return true;
//}
 
 
 
#endif
#endif
//#endif
 
 
#endif // end: #ifdef USE_BLUETOOTH
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/bluetooth/bluetooth.h
0,0 → 1,182
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY bluetooth.h
//#
//# 25.06.2014 OG
//# - chg: bt_discover() Parameter
//#
//# 16.06.2014 OG
//# - add: BTM222_Initalize()
//# - del: bt_init()
//#
//# 08.06.2014 OG
//# - del: BT_New_Baudrate
//#
//# 24.06.2013 OG
//# - add: bt_fixname()
//############################################################################
 
 
#ifndef _BLUETOOTH_H_
#define _BLUETOOTH_H_
 
#include <avr/io.h>
//#include <common.h>
#include "fifo.h"
 
 
#define SQUIRREL
#define NUTS_LIST 16
#define EXTENSIONS_LIST 16
#define RXD_BUFFER_SIZE 150
//void InitBT(void);
 
extern char bt_rx_buffer[RXD_BUFFER_SIZE];
extern volatile uint8_t bt_rx_len;
extern volatile uint8_t bt_rx_ready;
 
 
//extern char data_decode[RXD_BUFFER_SIZE];
 
extern uint8_t bt_rxerror;
extern uint8_t bt_frameerror;
extern uint8_t bt_overrun;
extern uint8_t bt_bufferoverflow;
 
extern fifo_t in_fifo;
 
 
typedef struct _device_info device_info;
 
// device info struct, holds mac , class and extensions + values of a device
struct _device_info
{
char DevName[20];
char mac[14];
 
// uint8_t class;
// uint8_t extension_types[EXTENSIONS_LIST];
// uint16_t values_cache[EXTENSIONS_LIST];
};
extern uint8_t bt_devicecount;
extern device_info device_list[NUTS_LIST];
extern char localID[15];
#define valid(num) (num < NUTS_LIST && (device_list[num].mac[0] != 0 || device_list[num].mac[1] != 0 || device_list[num].mac[2] != 0 || device_list[num].mac[3] != 0 || device_list[num].mac[4] != 0 || device_list[num].mac[5] != 0 || device_list[num].mac[6] != 0 || device_list[num].mac[7] != 0 || device_list[num].mac[8] != 0 || device_list[num].mac[9] != 0 || device_list[num].mac[10] != 0 || device_list[num].mac[11] != 0))
 
 
extern void bt_start(void); // EchoAnswervariable setzen
void bt_set_EchoAnswer (uint8_t onoff);
 
extern uint8_t bt_getID (void);
 
//extern static communication_mode_t update_comm_mode(uint16_t timeout_ms);
 
// Bluetooth mode ENUM
typedef enum
{
BLUETOOTH_MASTER, // < Master Mode (to create outgoinng connections).
BLUETOOTH_SLAVE // < Slave Mode (to wait for incoming connections).
} bt_mode_t;
 
// set baudrate bluetooth
// @return true = ok
// false = error
//extern uint16_t bt_setbaud (uint8_t baudrate);
uint16_t bt_setbaud(uint8_t baudrate);
 
// init bluetooth driver
// @return always true
//
//extern uint16_t bt_init (void (*upate_percentage) (uint16_t));
//extern uint16_t bt_init (void);
 
// Set the Bluetooth mode
// @param mode bt_mode_t Bluetooth Mode ENUM (BLUETOOTH_MASTER or BLUETOOTH_SLAVE)
// @return true if mode change was succesful, false if not
//
extern uint8_t bt_set_mode (const bt_mode_t mode);
 
// recieve data over bluetooth
// @param data pointer to memory for data storage
// @param length value of length after call holds the actual recived data length
// @param timeout_ms timeout in ms after the recive function aborts and returns with false
// @return false if recived length > length parameter or it timeouted, true otherwise
//
extern uint16_t bt_receive (void * data, uint8_t length, uint16_t timeout_ms);
 
// send data over bluetooth
// @param data pointer to the data to send
// @param length length of the data to be send
// @return true if sendingn was successful, false otherwise
//
extern uint16_t bt_send (void * data, const uint8_t length);
 
// squirrelt only functions
#ifdef SQUIRREL
 
// open bluetoot connection (only one at a time possible)
// @param address connection is opened to this device mac address
// @return true if connection was established, false otherwise
//
extern uint16_t bt_connect (const char *address);
 
// closes bluetooth connection
// @return false if failed, true otherwise
//
extern uint16_t bt_disconnect (void);
 
// discover bluetooth devices
// @param result in a 2 dimensional array first index are devicecs (max 8) second is mac address string
// @param update_callback to inform of progress (in % from 0 to 100)
// @return true if successful, false if error occured
//
//extern uint16_t bt_discover(void);
//extern uint16_t bt_discover (char result[8][12], void (*update_callback)(const uint16_t progress));
 
extern void bt_downlink_init(void); // Auf Master stellen für Devicesuche und GPS Empfang
 
extern void bt_searchDevice(void); //Bluetoothgeräte suchen
 
#endif // SQUIRREL
 
 
void uart_receive(void);
void bt_fixname(void);
void BTM222_Initalize( void );
uint8_t bt_showsettings( void );
 
 
#endif
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/bluetooth/error.c
0,0 → 1,218
/*
___ ___ ___ ___ _____
/ /\ /__/\ / /\ /__/\ / /::\
/ /::\ | |::\ / /::\ \ \:\ / /:/\:\
/ /:/\:\ ___ ___ | |:|:\ / /:/\:\ \ \:\ / /:/ \:\
/ /:/~/::\ /__/\ / /\ __|__|:|\:\ / /:/ \:\ _____\__\:\ /__/:/ \__\:|
/__/:/ /:/\:\ \ \:\ / /:/ /__/::::| \:\ /__/:/ \__\:\ /__/::::::::\ \ \:\ / /:/
\ \:\/:/__\/ \ \:\ /:/ \ \:\~~\__\/ \ \:\ / /:/ \ \:\~~\~~\/ \ \:\ /:/
\ \::/ \ \:\/:/ \ \:\ \ \:\ /:/ \ \:\ ~~~ \ \:\/:/
\ \:\ \ \::/ \ \:\ \ \:\/:/ \ \:\ \ \::/
\ \:\ \__\/ \ \:\ \ \::/ \ \:\ \__\/
\__\/ \__\/ \__\/ \__\/
___ ___ ___ ___ ___ ___
/ /\ / /\ /__/\ /__/\ / /\ /__/\
/ /:/ / /::\ | |::\ | |::\ / /::\ \ \:\
/ /:/ / /:/\:\ | |:|:\ | |:|:\ / /:/\:\ \ \:\
/ /:/ ___ / /:/ \:\ __|__|:|\:\ __|__|:|\:\ / /:/ \:\ _____\__\:\
/__/:/ / /\ /__/:/ \__\:\ /__/::::| \:\ /__/::::| \:\ /__/:/ \__\:\ /__/::::::::\
\ \:\ / /:/ \ \:\ / /:/ \ \:\~~\__\/ \ \:\~~\__\/ \ \:\ / /:/ \ \:\~~\~~\/
\ \:\ /:/ \ \:\ /:/ \ \:\ \ \:\ \ \:\ /:/ \ \:\ ~~~
\ \:\/:/ \ \:\/:/ \ \:\ \ \:\ \ \:\/:/ \ \:\
\ \::/ \ \::/ \ \:\ \ \:\ \ \::/ \ \:\
\__\/ \__\/ \__\/ \__\/ \__\/ \__\/
 
 
**
* Error handling functions
*/
 
//############################################################################
//# HISTORY error.c
//#
//# 16.04.2013 Cebra
//# - chg: PROGMEM angepasst auf neue avr-libc und GCC, prog_char depreciated
//#
//##########################################################################
 
 
 
#include <stdbool.h>
#include <avr/pgmspace.h>
#include "error_driver.h"
#include "../main.h"
#ifdef DEBUG
//--------------------------------------------------------------
inline void _send_msg(const char *msg)
{
for (uint8_t i=0; i<255 && msg[i]!='\0'; i++)
{
errordriver_write_c(msg[i]);
}
errordriver_write_c('\n');
}
 
 
//--------------------------------------------------------------
void send_pgm(const char *msg)
{
uint8_t myByte;
myByte = pgm_read_byte(msg);
for(int i = 1; myByte != '\0'; i++)
{
errordriver_write_c(myByte);
myByte = pgm_read_byte(msg+i);
}
}
 
 
 
 
//--------------------------------------------------------------
void error_init(void)
{
error_driver_Init();
}
 
 
//--------------------------------------------------------------
void error_putc(const char c)
{
errordriver_write_c(c);
}
 
 
//--------------------------------------------------------------
void assert (bool condition, const char *msg)
{
if (!condition)
{
send_pgm(PSTR("ASS:"));
_send_msg(msg);
}
}
 
 
//--------------------------------------------------------------
void info (const char *msg)
{
send_pgm(PSTR("INF:"));
_send_msg(msg);
}
 
 
//--------------------------------------------------------------
void warn (const char *msg)
{
send_pgm(PSTR("WARN:"));
_send_msg(msg);
}
 
 
//--------------------------------------------------------------
void debug (const char *msg)
{
send_pgm(PSTR("DBG:"));
_send_msg(msg);
}
 
 
//--------------------------------------------------------------
void Error (const char *msg)
{
send_pgm(PSTR("ERR:"));
_send_msg(msg);
}
#endif
 
#ifdef DEBUG
 
//--------------------------------------------------------------
void assert_pgm(bool condition, const prog_char *msg)
{
if (condition) {
send_pgm(PSTR("ASS:"));
send_pgm(msg);
errordriver_write_c('\n');
}
}
 
 
//--------------------------------------------------------------
void info_pgm(const prog_char *msg)
{
send_pgm(PSTR("INF:"));
send_pgm(msg);
errordriver_write_c('\n');
}
 
 
//--------------------------------------------------------------
void warn_pgm(const prog_char *msg)
{
send_pgm(PSTR("WARN:"));
send_pgm(msg);
errordriver_write_c('\n');
errordriver_write_c('\r');
}
 
 
//--------------------------------------------------------------
void error_pgm(const prog_char *msg)
{
send_pgm(PSTR("ERR:"));
send_pgm(msg);
errordriver_write_c('\n');
errordriver_write_c('\r');
}
 
 
//--------------------------------------------------------------
void debug_pgm(const prog_char *msg)
{
send_pgm(PSTR("DBG:"));
send_pgm(msg);
errordriver_write_c('\n');
errordriver_write_c('\r');
}
 
 
////--------------------------------------------------------------
//void print_hex(uint8_t num)
//{
// if (num<10)
// error_putc(num+48);
// else
// {
// switch (num)
// {
// case 10:
// error_putc('A'); break;
// case 11:
// error_putc('B'); break;
// case 12:
// error_putc('C'); break;
// case 13:
// error_putc('D'); break;
// case 14:
// error_putc('E'); break;
// case 15:
// error_putc('F'); break;
// default:
// error_putc('#'); break;
// }
// }
//}
//
//
////--------------------------------------------------------------
//void byte_to_hex(uint8_t byte)
//{
// uint8_t b2 = (byte & 0x0F);
// uint8_t b1 = ((byte & 0xF0)>>4);
// print_hex(b1);
// print_hex(b2);
//}
 
#endif
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/bluetooth/error.h
0,0 → 1,79
/*
___ ___ ___ ___ _____
/ /\ /__/\ / /\ /__/\ / /::\
/ /::\ | |::\ / /::\ \ \:\ / /:/\:\
/ /:/\:\ ___ ___ | |:|:\ / /:/\:\ \ \:\ / /:/ \:\
/ /:/~/::\ /__/\ / /\ __|__|:|\:\ / /:/ \:\ _____\__\:\ /__/:/ \__\:|
/__/:/ /:/\:\ \ \:\ / /:/ /__/::::| \:\ /__/:/ \__\:\ /__/::::::::\ \ \:\ / /:/
\ \:\/:/__\/ \ \:\ /:/ \ \:\~~\__\/ \ \:\ / /:/ \ \:\~~\~~\/ \ \:\ /:/
\ \::/ \ \:\/:/ \ \:\ \ \:\ /:/ \ \:\ ~~~ \ \:\/:/
\ \:\ \ \::/ \ \:\ \ \:\/:/ \ \:\ \ \::/
\ \:\ \__\/ \ \:\ \ \::/ \ \:\ \__\/
\__\/ \__\/ \__\/ \__\/
___ ___ ___ ___ ___ ___
/ /\ / /\ /__/\ /__/\ / /\ /__/\
/ /:/ / /::\ | |::\ | |::\ / /::\ \ \:\
/ /:/ / /:/\:\ | |:|:\ | |:|:\ / /:/\:\ \ \:\
/ /:/ ___ / /:/ \:\ __|__|:|\:\ __|__|:|\:\ / /:/ \:\ _____\__\:\
/__/:/ / /\ /__/:/ \__\:\ /__/::::| \:\ /__/::::| \:\ /__/:/ \__\:\ /__/::::::::\
\ \:\ / /:/ \ \:\ / /:/ \ \:\~~\__\/ \ \:\~~\__\/ \ \:\ / /:/ \ \:\~~\~~\/
\ \:\ /:/ \ \:\ /:/ \ \:\ \ \:\ \ \:\ /:/ \ \:\ ~~~
\ \:\/:/ \ \:\/:/ \ \:\ \ \:\ \ \:\/:/ \ \:\
\ \::/ \ \::/ \ \:\ \ \:\ \ \::/ \ \:\
\__\/ \__\/ \__\/ \__\/ \__\/ \__\/
 
 
*
* Error handling functions.
*/
 
#ifndef __ERROR__
#define __ERROR__
 
#include <avr/pgmspace.h>
#include <stdbool.h>
#include "../main.h"
 
 
#ifdef DEBUG
 
void error_init(void);
 
void error_putc(const char c);
 
void assert (bool condition, const char *msg);
void info (const char *msg);
void warn(const char *msg);
void debug(const char *msg);
void Error(const char *msg);
 
void assert_pgm(bool condition, const prog_char *msg);
void info_pgm (const prog_char *msg);
void warn_pgm(const prog_char *msg);
void debug_pgm(const prog_char *msg);
void error_pgm(const prog_char *msg);
 
void byte_to_hex(uint8_t byte);
 
#else
 
#define error_init() {}
 
 
#define error_putc(c) {}
 
#define assert(cond, msg) {}
#define info(msg) {}
#define warn(msg) {}
#define debug(msg) {}
#define error(msg) {}
 
#define assert_pgm(cond, msg) {}
#define info_pgm(msg) {}
#define warn_pgm(msg) {}
#define debug_pgm(msg) {}
#define error_pgm(msg) {}
#define byte_to_hex(byte) {}
#endif
 
#endif //__ERROR__
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/bluetooth/error_driver.c
0,0 → 1,27
 
 
#include <avr/pgmspace.h>
#include <stdbool.h>
//#include "cpu.h"
#include "error_driver.h"
#include "../main.h"
 
#ifdef DEBUG
 
#include "../uart/usart.h"
#include "../uart/uart1.h"
 
 
void errordriver_write_c(char c)
 
 
{
USART_putc(c);
}
 
void error_driver_Init(void)
{
// USART_Init(UART_BAUD_SELECT(USART_BAUD,F_CPU));
}
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/bluetooth/error_driver.h
0,0 → 1,22
/*
* Functions to write error message to FTDI or USART
*/
 
#ifndef __ERROR_DRIVER__
#define __ERROR_DRIVER__
 
#include <avr/io.h>
#include "../main.h"
 
 
 
#ifdef DEBUG
extern void errordriver_write_c(char c);
extern void error_driver_Init(void);
#else
#define errordriver_write_c(c) {}
#define error_driver_init() {}
#endif
 
 
#endif //__ERROR_DRIVER__
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/bluetooth/fifo.c
0,0 → 1,197
/**
* a simple Fifo
* @file fifo.c
* @author Pascal Schnurr
*/
 
//############################################################################
//# HISTORY fifo.c
//#
//# 26.06.2014 OG
//# - add: fifo_isstr()
//#
//# 16.04.2013 Cebra
//# - chg: PROGMEM angepasst auf neue avr-libc und GCC, prog_char depreciated
//#
//############################################################################
 
 
#include <string.h>
#include "fifo.h"
//#if defined HWVERSION1_3W || defined HWVERSION3_9 || defined HWVERSION1_2W
 
 
//--------------------------------------------------------------
void fifo_init (fifo_t * fifo, uint8_t * buffer, uint16_t size)
{
fifo->size = size;
fifo->buffer = buffer;
fifo->head = 0;
fifo->count = 0;
}
//--------------------------------------------------------------
uint16_t fifo_getcount (const fifo_t * fifo)
{
 
return fifo->count;
}
//--------------------------------------------------------------
bool fifo_is_empty (const fifo_t * fifo)
{
return (fifo->count == 0);
}
 
//--------------------------------------------------------------
bool fifo_is_full (const fifo_t * fifo)
{
return (fifo->size - fifo->count == 0);
}
 
//--------------------------------------------------------------
bool fifo_read (fifo_t * fifo, char *data)
{
if (fifo_is_empty (fifo))
return false;
 
uint8_t *head = fifo->buffer + fifo->head;
 
*data = (char) * head;
 
fifo->head = ( (fifo->head + 1) % fifo->size);
 
fifo->count--;
 
return true;
}
 
//--------------------------------------------------------------
bool fifo_write (fifo_t * fifo, const char data)
{
if (fifo_is_full (fifo))
return false;
 
uint8_t *end = fifo->buffer + ( (fifo->head + fifo->count) % fifo->size);
 
*end = (uint8_t) data;
 
fifo->count++;
 
return true;
}
 
//--------------------------------------------------------------
bool fifo_clear (fifo_t * fifo)
{
fifo->count = 0;
fifo->head = 0;
return true;
}
 
//--------------------------------------------------------------
static bool fifo_cmp_pgm_at (fifo_t * fifo, const char * pgm, const uint16_t index)
{
uint16_t i;
uint8_t fifo_byte;
uint8_t pgm_byte;
 
for (i = 0; pgm_read_byte (pgm + i) != 0; i++)
{
if (fifo->count <= (i + index))
return false;
 
pgm_byte = pgm_read_byte (pgm + i);
 
fifo_byte = * (fifo->buffer + ( (fifo->head + i + index) % fifo->size));
 
if (fifo_byte != pgm_byte)
return false;
}
 
// We found the string, lets move the pointer
fifo->head = ( (fifo->head + i + index) % fifo->size);
 
fifo->count -= (i + index);
 
return true;
}
//--------------------------------------------------------------
bool fifo_search (fifo_t * fifo, const char * pgm)
{
uint16_t i;
uint8_t fifo_byte;
uint8_t pgm_byte;
 
for (i = 0; pgm_read_byte (pgm + i) != 0; i++)
{
if (fifo->count <= i)
return false;
 
pgm_byte = pgm_read_byte (pgm + i);
 
fifo_byte = * (fifo->buffer + ( (fifo->head + i) % fifo->size));
 
if (fifo_byte != pgm_byte)
return false;
}
 
// // We found the string, lets move the pointer
// fifo->head = ( (fifo->head + i + index) % fifo->size);
//
// fifo->count -= (i + index);
 
return true;
}
//--------------------------------------------------------------
/** \brief searches a string in the whole fifo
* starts at the beginning and searches for the pgm string in the fifo,
*
* @param fifo pointer to your initialized fifo_t structure
* @param pgm a prog_char with the search string
* @return true if found, false otherwise
*/
 
bool fifo_cmp_pgm (fifo_t * fifo, const char * pgm)
{
return fifo_cmp_pgm_at (fifo, pgm, 0);
}
//--------------------------------------------------------------
/** \brief searches a string in the whole fifo
* starts at the beginning and searches for the pgm string in the fifo,
* if they are found previous entrys and the string are removed from the fifo
* @param fifo pointer to your initialized fifo_t structure
* @param pgm a prog_char with the search string
* @return true if found, false otherwise
*/
 
bool fifo_strstr_pgm (fifo_t * fifo, const char * pgm)
{
for (uint16_t i = 0; i < fifo->count; i++)
{
if (fifo_cmp_pgm_at (fifo, pgm, i))
return true;
}
 
return false;
}
 
 
 
//--------------------------------------------------------------
// Idee: buffer nach str durchsuchen ohne die fifo Zeiger zu aendern
// ungetestet
//--------------------------------------------------------------
bool fifo_isstr( fifo_t * fifo, const char * str)
{
/*
void *memmem(const void *s1,
size_t len1,
const void *s2,
size_t len2);
The memmem() function finds the start of the first occurrence of the substring s2 of length len2 in the memory area s1 of length len1.
*/
 
return memmem( fifo->buffer + fifo->head, fifo->count, str, strlen(str) ) != NULL;
}
 
 
//#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/bluetooth/fifo.h
0,0 → 1,107
/**
* a simple Fifo
* @file fifo.h
* @author Pascal Schnurr
*/
 
//############################################################################
//# HISTORY fifo.c
//#
//# 26.06.2014 OG
//# - add: fifo_isstr()
//#
//# 16.04.2013 Cebra
//# - chg: PROGMEM angepasst auf neue avr-libc und GCC, prog_char depreciated
//############################################################################
 
 
#include <avr/pgmspace.h>
#include <stdbool.h>
#ifndef _FIFO_H_
#define _FIFO_H_
 
/**
*fifo data structure all vital fifo information
*/
typedef struct
{
uint16_t count; /**< current number of elements */
uint16_t head; /**< position of the head element */
uint16_t size; /**< size equals max number of entrys*/
uint8_t* buffer; /**< pointer to memory area where the fifo is to be saved */
} fifo_t;
 
uint16_t fifo_getcount (const fifo_t * fifo);
 
/** \brief initialize of a fifo
* sets all the information in your given fifo structure
* @param fifo pointer to an allocated fifo_t structure
* @param buffer pointer to an a allocated memory space for the fifo of size = sizeof(uint8_t) * size
* @param size max number of entrys the fifo will hold
*/
void fifo_init (fifo_t *fifo, uint8_t *buffer, uint16_t size);
 
/** \brief checks if fifo is empty
* @param fifo pointer to your initialized fifo_t structure
* @return true if empty otherwise false
*/
bool fifo_is_empty (const fifo_t *fifo);
 
/** \brief checks if fifo is full
* @param fifo pointer to your initialized fifo_t structure
* @return true if full otherwise false
*/
bool fifo_is_full (const fifo_t *fifo);
 
/** \brief clears the fifo
* resets your fifo structure to 0 elements
* @param fifo pointer to your initialized fifo_t structure
* @return always true (never fails)
*/
bool fifo_clear (fifo_t *fifo);
 
/** \brief reads head of fifo
* reads the first element and removes it
* @param fifo pointer to your initialized fifo_t structure
* @return false if fifo is empty false otherwise
*/
bool fifo_read (fifo_t *fifo, char *data);
 
/** \brief inserts a char into the fifo
* adds a char to the end of the fifo
* @param fifo pointer to your initialized fifo_t structure
* @param data the char data to be inserted
* @return false if fifo is full true otherwise
*/
bool fifo_write (fifo_t *fifo, const char data);
 
/** \brief compares first elements with prog_char string
* if pgm equals the first elements of the fifo these elements are removed
* @param fifo pointer to your initialized fifo_t structure
* @param pgm a prog_char string for comparison
* @return true if pgm is equal to the first entrys in the fifo, false otherwise
*/
bool fifo_cmp_pgm (fifo_t* fifo, const char* pgm);
 
/** \brief searches a string in the whole fifo
* starts at the beginning and searches for the pgm string in the fifo,
*
* @param fifo pointer to your initialized fifo_t structure
* @param pgm a prog_char with the search string
* @return true if found, false otherwise
*/
bool fifo_search (fifo_t * fifo, const char * pgm);
 
/** \brief searches a string in the whole fifo
* starts at the beginning and searches for the pgm string in the fifo,
* if they are found previous entrys and the string are removed from the fifo
* @param fifo pointer to your initialized fifo_t structure
* @param pgm a prog_char with the search string
* @return true if found, false otherwise
*/
bool fifo_strstr_pgm (fifo_t *fifo, const char *pgm);
 
 
bool fifo_isstr( fifo_t * fifo, const char * str);
 
#endif /* _FIFO_H_ */
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/bluetooth
Property changes:
Added: svn:ignore
+_doc
+
+_old_source
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/connect.c
0,0 → 1,436
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY connect.c
//#
//# 10.06.2014 OG
//# - del: Port_USB2CFG_Wi() - jetzt in Wi232.c als Wi232_ConfigPC()
//#
//# 13.04.2014 OG
//# - add: Baud_to_uint32()
//#
//# 10.04.2014 OG
//# - del: Port_FC2CFG_WL()
//#
//# 01.04.2014 OG
//# - add: wait_and_restore() redundanten Code einsparen
//# - add: Port_BLE2Wi() (Bluetooth 4 Low Energy Modul an SV2)
//#
//# 28.02.2014 OG
//# - chg: alle Anzeigescreens von 'PKT Connect' auf Connect_Screen() umgestellt
//# - add: Connect_Screen()
//#
//# 12.02.2014 OG
//# - chg: Port_WiFly2Wi() Auskommentiert: "unused variable 'i'"
//#
//# 15.07.2013 Cebra
//# - chg: Port_FC2CFG_WL, Konfiguration Wlan Modul mit PC, Texte geändert
//#
//# 02.07.2013 Cebra
//# - add: Port_FC2CFG_WL, Konfiguration Wlan Modul mit PC
//#
//# 26.06.2013 Cebra
//# - chg: Modulumschaltung für WiFlypatch geändert
//# - add: Port_WiFly2Wi, Wlan-Wi232 Verbindung
//#
//# 24.6.2013 Cebra
//# - fix: Fehler beim UART1 bei der Rückschaltung von USB2FC,USB2WI,BT2FC,BT2WI
//#
//# 19.06.2013 OG
//# - chg: Screen-Layout von Port_BT2Wi(), Port_USB2Wi()
//############################################################################
 
 
#include "cpu.h"
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <string.h>
 
#include "lcd/lcd.h"
#include "timer/timer.h"
#include "eeprom/eeprom.h"
#include "messages.h"
#include "lipo/lipo.h"
#include "main.h"
#include "bluetooth/bluetooth.h"
#include "wifly/PKT_WiFlyHQ.h"
#include "uart/uart1.h"
#include "utils/xutils.h"
 
 
//#if defined HWVERSION3_9
//--------------------------------------------------------------
void Change_Output(uint8_t UartMode) // Schaltet die Rx/Tx Richtungen
{
// hiermit werden die 74HTC125 (IC5) Gatter geschaltet
clr_USB2FC(); // PC2 aus IC5 A/D
clr_USB2Wi(); // PB0 aus IC5 B/C
clr_Uart02FC(); // PC6 aus IC4 C/D
clr_Uart02Wi(); // PC5 aus IC4 A/B
 
 
switch (UartMode)
{
case USB2FC:
UCSR1B &= ~(1<<RXEN1);
UCSR1B &= ~(1<<TXEN1);
UCSR1B &= ~(1<<RXCIE1);
 
DDRD &= ~(1<<DDD2); // Pins auf Eingang setzen
DDRD &= ~(1<<DDD3);
PORTD &= ~(1<<PD2); // Pullup aus
PORTD &= ~(1<<PD3);
 
set_USB2FC();
break;
 
case Uart02Wi:
set_Uart02Wi();
break;
 
case Uart02FC:
set_Uart02FC();
break;
 
case USB2Wi:
UCSR1B &= ~(1<<RXEN1);
UCSR1B &= ~(1<<TXEN1);
UCSR1B &= ~(1<<RXCIE1);
 
DDRD &= ~(1<<DDD2); // Pins auf Eingang setzen
DDRD &= ~(1<<DDD3);
PORTD &= ~(1<<PD2); // Pullup aus
PORTD &= ~(1<<PD3);
 
set_USB2Wi();
break;
}
}
 
 
 
//--------------------------------------------------------------
// gibt eine uebergebene Baud-Rate als uint32_t zurueck
//--------------------------------------------------------------
uint32_t Baud_to_uint32( uint8_t baud )
{
switch( baud )
{
case Baud_2400: return( 2400 );
case Baud_4800: return( 4800 );
case Baud_9600: return( 9600 );
case Baud_19200: return( 19200 );
case Baud_38400: return( 38400 );
case Baud_57600: return( 57600 );
case Baud_115200: return( 115200 );
}
return( 0 );
}
 
 
 
//--------------------------------------------------------------
// Connect_Screen(
//
// Parameter:
// title : PROGMEM
// message : RAM oder PROGMEM je nach msg_progmem
// msg_progmem: true/false
// true = message im PROGMEM
// false = message im RAM
//--------------------------------------------------------------
void Connect_Screen( const char *title, const char *message, uint8_t msg_progmem )
{
lcd_cls ();
 
lcd_frect( 0, 0, 127, 7, 1); // Titel: Invers
lcd_printp_at( 1, 0, title, MINVERS); // Titel
show_Lipo();
 
lcdx_printp_center( 2, title , MNORMAL, 0,-3); //
lcdx_printp_center( 3, strGet(STR_ACTIVE), MNORMAL, 0,1); // "AKTIV!"
 
if( (!msg_progmem && strlen(message)>0) || (msg_progmem && strlen_P(message)>0) )
{
if( msg_progmem )
lcdx_printp_center( 5, message, MNORMAL, 0,1);
else
lcdx_print_center( 5, (unsigned char *) message, MNORMAL, 0,1);
 
lcd_rect_round( 0, 5*7+2, 127, 8+6, 1, R2); // Rahmen
}
 
lcd_printp_at(12, 7, strGet(ENDE) , MNORMAL); // Keyline
}
 
 
 
//--------------------------------------------------------------
// INTERN
//
// _port_wait_and_restore()
//
// Wartet bis der Benutzer beendet und restauriert Einstellungen
//
// gemeinsamer Code um Speicherplatz zu sparen
//--------------------------------------------------------------
void wait_and_restore( void )
{
while( !get_key_press(1 << KEY_ESC) )
{
show_Lipo();
}
 
uart1_init( UART_BAUD_SELECT(57600,F_CPU) );
 
SetBaudUart1( Config.PKT_Baudrate );
 
if( Config.U02SV2 == 1 )
Change_Output( Uart02FC );
else
Change_Output( Uart02Wi );
 
set_Modul_On( USB );
}
 
 
 
//--------------------------------------------------------------
// Function: BT2FC()
// Purpose: Connect BT direct to FC-Kabel (SV2 as MKUSB)
// Returns:
//--------------------------------------------------------------
void Port_BT2FC(void)
{
/*
// mit Anzeige von 'Baud'
// verbraucht einige Bytes mehr...
char *message;
uint32_t baud;
 
switch( Config.PKT_Baudrate )
{
case Baud_2400: baud = 2400; break;
case Baud_4800: baud = 4800; break;
case Baud_9600: baud = 9600; break;
case Baud_19200: baud = 19200; break;
case Baud_38400: baud = 38400; break;
case Baud_57600: baud = 57600; break;
case Baud_115200: baud = 115200; break;
}
message = buffered_sprintf_P( PSTR("%lu Baud"), baud);
Connect_Screen( PSTR("BT -> SV2 Kabel"), message, false );
*/
 
// ohne Anzeige von 'Baud'
Connect_Screen( PSTR("BT -> SV2 Kabel"), "", false );
 
// set_BTOn();
set_Modul_On(Bluetooth);
_delay_ms(1000);
//_delay_ms(2000);
 
if( !Config.BTIsSlave==true )
bt_set_mode(BLUETOOTH_SLAVE);
 
Change_Output(USB2FC);
wait_and_restore();
}
 
 
 
//--------------------------------------------------------------
// Function: BT2Wi()
// Purpose: Connect BT direct to Wi.232
// Returns:
//--------------------------------------------------------------
void Port_BT2Wi( void )
{
char *message = "RE-ID: 0000";
 
strcpy( &message[7], Config.RE_ID);
Connect_Screen( PSTR("BT Extender"), message, false );
 
set_Modul_On( Bluetooth ); // set_BTOn();
_delay_ms(1500);
if( !Config.BTIsSlave==true ) bt_set_mode(BLUETOOTH_SLAVE);
 
Change_Output(USB2Wi);
wait_and_restore();
}
 
 
 
 
//--------------------------------------------------------------
// Function: WiFly2Wi()
// Purpose: Connect WiFly direct to Wi.232
// Hinweis: SV2 RxTx Patch erforderlich!
// Returns:
//--------------------------------------------------------------
void Port_WiFly2Wi( void )
{
Connect_Screen( PSTR("WLAN Extender"), PSTR("169.254.1.1:2000"), true );
 
set_Modul_On( Wlan );
Change_Output( USB2Wi );
wait_and_restore();
}
 
 
 
//--------------------------------------------------------------
// Function: BLE2Wi()
// Purpose: Connect BLE direct to Wi.232
// Hinweis: SV2 RxTx Patch erforderlich!
// Returns:
//--------------------------------------------------------------
void Port_BLE2Wi( void )
{
Connect_Screen( PSTR("BLE Extender"), "", false );
 
set_Modul_On(Wlan); // verwendet wie Wlan/WiFly SV2
Change_Output(USB2Wi);
wait_and_restore();
}
 
 
 
//--------------------------------------------------------------
// Function: FC2CFG_BT()
// Purpose: Connect FC (Tx1 Pin3, Rx1 Pin4) direct to BT
// Returns:
//--------------------------------------------------------------
void Port_FC2CFG_BT(void)
{
lcd_cls ();
lcd_printp_at (0, 0, PSTR("BTM-222 Konfigurieren"), 2);
lcd_printp_at (0, 1, PSTR("FC > MK-USB > BTM-222"), 2);
lcd_printp_at (0, 3, PSTR("MK-USB an PC anschl. "), 0);
lcd_printp_at (0, 4, PSTR("Zwischen MK-USB und "), 0);
lcd_printp_at (0, 5, PSTR("PKT ein gekreuztes "), 0);
lcd_printp_at (0, 6, PSTR("Kabel anschliessen. "), 0);
lcd_printp_at(12, 7, strGet(ESC), 0);
 
// set_BTOn();
set_Modul_On(Bluetooth);
Change_Output(USB2FC);
 
while(!get_key_press (1 << KEY_ESC));
 
if (Config.U02SV2 == 1)
Change_Output(Uart02FC);
else
Change_Output(Uart02Wi);
set_Modul_On(USB);
// set_BTOff();
return;
}
 
 
 
//--------------------------------------------------------------
// Function: USB2FC()
// Purpose: Connect USB direct to FC-Kabel (SV2 as MKUSB)
// Returns:
//--------------------------------------------------------------
void Port_USB2FC(void)
{
Connect_Screen( PSTR("USB -> SV2 Kabel"), PSTR("MK-USB"), true );
 
Change_Output(USB2FC);
wait_and_restore();
 
/*
//------
// 01.04.2014 OG: ersetzt durch: wait_and_restore()
// Unterschied: zum Schluss wird bei wait_and_restore()
// noch ein set_Modul_On(USB) gemacht - ist das relevant?
//------
do
{
show_Lipo();
} while(!get_key_press (1 << KEY_ESC));
 
get_key_press(KEY_ALL);
uart1_init (UART_BAUD_SELECT(57600,F_CPU));
SetBaudUart1(Config.PKT_Baudrate);
 
if (Config.U02SV2 == 1)
Change_Output(Uart02FC);
else
Change_Output(Uart02Wi);
 
return;
*/
}
 
 
 
//--------------------------------------------------------------
// Function: USB2Wi()
// Purpose: Connect USB direct to Wi.232
// Returns:
//--------------------------------------------------------------
void Port_USB2Wi(void)
{
Connect_Screen( PSTR("USB -> Wi.232"), "", false );
 
Change_Output(USB2Wi);
wait_and_restore();
 
/*
//------
// 01.04.2014 OG: ersetzt durch: wait_and_restore()
// Unterschied: zum Schluss wird bei wait_and_restore()
// noch ein set_Modul_On(USB) gemacht - ist das relevant?
//------
do
{
show_Lipo();
}
while( !get_key_press(1 << KEY_ESC) );
 
if( Config.U02SV2 == 1 )
Change_Output(Uart02FC);
else
Change_Output(Uart02Wi);
 
get_key_press(KEY_ALL);
return;
*/
}
 
 
//#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/connect.h
0,0 → 1,68
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY connect.h
//#
//# 10.06.2014 OG
//# - del: Port_USB2CFG_Wi() - jetzt in Wi232.c als Wi232_ConfigPC()
//#
//# 13.04.2014 OG
//# - add: Baud_to_uint32()
//#
//# 10.04.2014 OG
//# - del: Port_FC2CFG_WL()
//#
//# 01.04.2014 OG
//# - add: Port_BLE2Wi()
//# - add: Source-History ergaenzt
//############################################################################
 
 
#ifndef _CONNECT_H
#define _CONNECT_H
 
void Change_Output(uint8_t UartMode);
 
void Port_BT2Wi(void);
void Port_BT2FC(void);
void Port_WiFly2Wi( void );
void Port_FC2CFG_BT(void);
 
void Port_USB2FC(void);
void Port_USB2Wi(void);
void Port_BLE2Wi( void );
 
uint32_t Baud_to_uint32( uint8_t baud );
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/cpu.h
0,0 → 1,41
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
 
#ifndef _CPU_H
#define _CPU_H
 
// Quarz Frequenz in Hz
#define F_CPU 20000000UL
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/eeprom/eeprom.c
0,0 → 1,827
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2013 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
//############################################################################
//# HISTORY eeprom.c
//#
//# 03.08.2015 CB
//# - chg: Obsolete Parameter geändert und für FollowMe verwendet, EEprom Version bleibt gleich
//# Parameter FM_Refresh in FM_Azimuth geändert
//# Parameter hyst_u_min in FM_Distance geändert
//# Initialisierung der neuen Parameter hinzugefügt
//#
//# 17.06.2014 OG
//# - chg: ReadParameter() - Updatecode auf 139
//#
//# 13.06.2014 OG
//# - chg: Delete_EEPROM(() Unterstuetzung Config.PKTOffTimeout (ehemals LCD_DisplayMode)
//#
//# 30.05.2014 OG
//# - chg: Delete_EEPROM() Config.Lipo_UOffset auf 10000 gesetzt (vorher 8500)
//#
//# 26.05.2014 OG
//# - chg: Config.LCD_DisplayMode als "OBSOLETE" markiert
//#
//# 14.05.2014 OG
//# - chg: include "../mk/paramset.h" geaendert auf "../mksettings/paramset.h"
//#
//# 07.05.2014 OG
//# - chg: EEpromversion erhoeht auf 138
//# -> keine neuen Parameter, neue Version nur fuer geanderte
//# Initialisierung von MKParam_Favs
//# - fix: ReadParameter() - Vorbelegung von Config.MKParam_Favs von 255 auf 0 geaendert
//# ab EEprom-Version 138
//# - fix: Delete_EEPROM() - Vorbelegung von Config.MKParam_Favs von 255 auf 0 geaendert
//# - fix: ReadParameter() - Kommentare zu Version 136 und 137 korrigiert
//# bzgl. der PKT-Versionsangabe und Datum ergaenzt
//#
//# 06.04.2014 OG
//# - chg: ReadParameter(): umgestellt auf lcdx_printp_center()
//# - chg: EEpromversion erhoeht auf 137
//# - add: ReadParameter(): upgrade Config.Wlan_HomeSSID, Config.Wlan_HomePassword
//# - add: ReadParameter(): upgrade Config.UseBLE, Config.MKParam_Favs
//# - add: Delete_EEPROM(): init von Config.Wlan_HomeSSID, Config.Wlan_HomePassword
//#
//# 01.04.2014 OG
//# - add: Delete_EEPROM(): init von Config.UseBLE
//# - add: Delete_EEPROM(): init von Config.MKParam_Favs
//#
//# 27.03.2014 OG
//# - chg: ReadParameter() Niederländisch wird auf Englisch umgeschaltet
//# -> Vorbereitung zum entfernen der Niederländischen Sprache
//#
//# 11.02.2014 Cebra
//# - add: Delete EEProm: Config.OSD_ShowCellU = false;
//#
//# 03.02.2014 OG
//# - add: Config.OSD_ShowCellU in ReadParameter (EEpromversion 0x87)
//#
//# 30.01.2014 OG
//# - add: Unterstuetzung fuer USE_BLUETOOTH
//#
//# 07.07.2013 OG
//# - chg: Strings fuer WLan gekuerzt
//#
//# 04.07.2013 Cebra
//# - add: neue Parameter fuer Wlan; EEpromversion erhoeht auf 0x85
//#
//# 04.07.2013 OG
//# - add: Config.OSD_UseScreen; Epromversion erhoeht auf 0x84
//#
//# 03.07.2013 OG
//# - chg: ReadParameter() - PKT-Upgrade restrukturiert bzgl. inkrementelle
//# Updates vorheriger Versionen
//#
//# 02.07.2013 Cebra
//# - add: neue Parameter fuer Wlan; EEpromversion erhoeht auf 83
//#
//# 02.07.2013 OG
//# - chg: frei geworden: Config.OSD_HomeMKView (nicht mehr benoetigt)
//#
//# 26.06.2013 OG
//# - chg: frei geworden: Config.PKT_StartInfo (nicht mehr benoetigt)
//#
//# 24.06.2013 OG
//# - fix: ReadParameter(): ergaenzt um bt_fixname() um ggf. ungueltige
//# Zeichen im Bluetooth-Namen zu eliminieren
//#
//# 23.06.2013 OG
//# - chg: Delete_EEPROM(): Default von Config.Lipo_UOffset von 6000 auf 8500 gesetzt
//# - chg: Delete_EEPROM(): Default von Config.bt_name auf "PKT" gekuerzt
//# - chg: Delete_EEPROM(): Config.bt_name -> nicht mehr mit Leerzeichen auffuellen!
//#
//# 20.06.2013 CB
//# - chg: EEPROM Versionsänderung auf 82 wegen Wechsel LCD_Orientation zu OSD_ShowMKSetting
//#
//# 15.06.2013 OG
//# - chg: Config.LCD_ORIENTATION zu Config.OSD_ShowMKSetting
//#
//# 13.06.2013 OG
//# - fix: Config.PKT_Accutyp hinzugefuegt in Delete_EEPROM()
//# - chg: Default GPS-LastPosition auf 0/0 gesetzt in Delete_EEPROM()
//# - chg: Default Config.PKT_StartInfo auf false gesetzt in Delete_EEPROM()
//# - chg: Code Layout
//#
//# 31.05.2013 CB
//# - chg: EEPROM Strukturänderung auf Version 81, Versionsanpassung angepasst
//#
//# 05.05.2013 Cebra
//# - add: PKT Zeitsetup EEPROM Parameter
//# 28.03.2013 CB
//# - add: save and upgrade OSD_Statistic, GPS_User, MKErr_Log in EEProm structure variable
//############################################################################
 
#include "../cpu.h"
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <stdarg.h>
#include <avr/interrupt.h>
#include <avr/eeprom.h>
#include <stdbool.h>
#include <avr/wdt.h>
#include "../lcd/lcd.h"
#include "../main.h"
#include "../timer/timer.h"
#include "eeprom.h"
#include "../wi232/Wi232.h"
#include "../setup/setup.h"
#include "../bluetooth/bluetooth.h"
#include "../mk-data-structs.h"
#include "../connect.h"
#include "../tracking/ng_servo.h"
#include "../tracking/tracking.h"
#include "../osd/osd.h"
#include "../uart/uart1.h"
#include "../messages.h"
#include "../osd/osddata.h"
#include "../mksettings/paramset.h"
 
//------------------------------------------------------------------------------------------
 
ST EEMEM EEStruct;
 
ST Config;
 
 
//#############################################################
// ANMERKUNG OG:
//
// es ware besser wenn die gesamte Config-struct zum PC
// gesendet wird anstatt aufbreitete Textlines. Das spart
// Speicher im PKT (der ist limitiert).
//
// Die Aufbereitung der Daten (Umrechnungen) kann dann auf
// der PC Seite erfolgen.
//
// Nachteil dabei: wenn sich die Config-struct des PKT
// ändert muss auch das PKT-Tool auf dem PC angepasst werden.
//
//CB: deshalb ist das auch jetzt auskommentiert
//
//#############################################################
 
 
//char printbuff[100];
 
//void print_data_int8( const char *text, int8_t *variable)
//{
// sprintf(printbuff, "%d", *variable);
// uart1_puts_p(text); uart1_puts(printbuff); uart1_puts("\r\n");
//}
////
////
//void print_data_uint8( const char *text, uint8_t *variable)
//{
// sprintf(printbuff, "%d", *variable);
// uart1_puts_p(text); uart1_puts(printbuff); uart1_puts("\r\n");
//}
//
//
//void print_data_uint16( const char *text, uint16_t *variable)
//{
// sprintf(printbuff, "%d", *variable);
// uart1_puts_p(text); uart1_puts(printbuff); uart1_puts("\r\n");
//}
//
//
//void print_data_int16( const char *text, int16_t *variable)
//{
// sprintf(printbuff, "%d", *variable);
// uart1_puts_p(text); uart1_puts(printbuff); uart1_puts("\r\n");
//}
//
//
//void print_data_char( const char *text, char *variable, uint8_t length)
//{
// uart1_puts_p(text);
// uart1_puts(variable);
// uart1_puts("\r\n");
//}
//
//
//void print_time( const char *text, PKTdatetime_t variable)
//{
// uart1_puts_p(text);
// sprintf(printbuff, "%d", variable.day);
// uart1_puts(printbuff);
// uart1_puts(".");
// sprintf(printbuff, "%d", variable.month);
// uart1_puts(printbuff);
// uart1_puts(".");
// sprintf(printbuff, "%d", variable.year);
// uart1_puts(printbuff);
//// uart1_puts(" ");
//// sprintf(printbuff, "%d", variable.seconds);
//// uart1_puts(printbuff);
// uart1_puts("\r\n");
//}
//
//
//
//void print_OSD_Statistic(void)
//{
// print_time (PSTR("begin_StatTime:"),Config.OSD_Statistic.begin_StatTime);
// print_time (PSTR("end_StatTime:"),Config.OSD_Statistic.end_StatTime);
// print_data_uint16 (PSTR("total_FlyTime:"),&Config.OSD_Statistic.total_FlyTime);
// print_data_uint16 (PSTR("last_FlyTime:"),&Config.OSD_Statistic.last_FlyTime);
// print_data_uint16 (PSTR("count_Errorcode:"),&Config.OSD_Statistic.count_Errorcode);
// print_data_int16 (PSTR("max_Altimeter:"),&Config.OSD_Statistic.max_Altimeter);
// print_data_uint16 (PSTR("max_GroundSpeed:"),&Config.OSD_Statistic.max_GroundSpeed);
// print_data_uint16 (PSTR("max_Distance:"),&Config.OSD_Statistic.max_Distance);
// print_data_uint16 (PSTR("max_Current:"),&Config.OSD_Statistic.max_Current);
// print_data_uint16 (PSTR("max_Capacity:"),&Config.OSD_Statistic.max_Capacity);
// print_data_int16 (PSTR("max_Variometer:"),&Config.OSD_Statistic.max_Variometer);
// print_data_int8 (PSTR("max_AngleNick:"),&Config.OSD_Statistic.max_AngleNick);
// print_data_int8 (PSTR("max_AngleRoll:"),&Config.OSD_Statistic.max_AngleRoll);
// print_data_uint8 (PSTR("RC Quality:"),&Config.OSD_Statistic.max_RCQuality);
// print_data_int16 (PSTR("max_TopSpeed:"),&Config.OSD_Statistic.max_TopSpeed);
// print_data_int8 (PSTR("min_AngleNick:"),&Config.OSD_Statistic.min_AngleNick);
// print_data_int8 (PSTR("min_AngleRoll:"),&Config.OSD_Statistic.min_AngleRoll);
// print_data_uint8 (PSTR("min_RCQuality:"),&Config.OSD_Statistic.min_RCQuality);
// print_data_uint8 (PSTR("min_UBat:"),&Config.OSD_Statistic.min_UBat);
// print_data_uint8 (PSTR("LiPoCells:"),&Config.OSD_Statistic.LiPoCells);
// print_data_uint8 (PSTR("BL_Count:"),&Config.OSD_Statistic.BL_Count);
//}
 
 
 
//void SendConfigData(void)
//{
 
// print_data_uint8 (strGet(START_VERSIONCHECK),&Config.Version );
// print_data_uint8 (strGet(LOWBAT),&Config.MK_LowBat );
// print_data_uint8 (strGet(LOWBAT),&Config.DisplayTimeout );
// print_data_uint8 (strGet(LOWBAT),&Config.DisplayLanguage );
// print_data_uint8 (strGet(WITXRX),&Config.WiTXRXChannel);
// print_data_uint8 (strGet(WINETWG),&Config.WiNetworkGroup);
// print_data_uint8 (strGet(WINETWM),&Config.WiNetworkMode);
// print_data_uint8 (strGet(WITIMEOUT),&Config.WiTXTO);
// print_data_uint8 (strGet(WIUART),&Config.WiUartMTU);
// print_data_uint8 (strGet(DISPLAY8),&Config.OSD_ShowMKSetting);
// print_data_uint8 (strGet(DISPLAY7),&Config.LCD_DisplayMode);
// print_data_uint8 (strGet(DISPLAY6),&Config.LCD_Kontrast);
// print_data_uint8 (strGet(DISPLAY5),&Config.LCD_Helligkeit);
// print_data_uint8 (PSTR("USB-Betrieb:"),&Config.USBBT);
// print_data_uint8 (PSTR("Uart-FC/Wi:"),&Config.U02SV2);
// print_data_uint8 (PSTR("PKT-Debug:"),&Config.Debug);
// print_data_uint8 (PSTR("Wi232 eingebaut:"),&Config.UseWi);
// print_data_uint8 (PSTR("BTM222 eingebaut:"),&Config.UseBT);
// print_data_uint8 (PSTR("Wi232 ok:"),&Config.WiIsSet);
// print_data_uint8 (PSTR("BTM222 ok:"),&Config.BTIsSet);
// print_data_uint8 (PSTR("BTM222 Slave:"),&Config.BTIsSlave);
//
// print_data_char (PSTR("BTM222 Pin:"),&Config.bt_pin[0],bt_pin_length );
// print_data_char (PSTR("BTM222 Name:"),&Config.bt_name[0],bt_name_length);
// print_data_char (PSTR("BTM222 REID:"),&Config.RE_ID[0],RE_ID_length );
// print_data_char (PSTR("BTM222 MAC:"),&Config.bt_Mac[0],bt_mac_length);
// print_data_char (PSTR("GPS DevName:"),&Config.gps_UsedDevName[0],20);
// print_data_char (PSTR("GPS MAC:"),&Config.gps_UsedMac[0],14);
//
// print_data_int32 (PSTR("LastLongitude:"),&Config.LastLongitude);
//// print_data_int32(PSTR("LastLatitude:"),&Config.LastLatitude);
//
// print_data_uint8 (PSTR("PKT_IdleBeep:"),&Config.PKT_IdleBeep);
// print_data_uint8 (strGet(DISPLAY2),&Config.PKT_StartInfo);
// print_data_uint16 (strGet(LIPO3),&Config.Lipo_UOffset);
// print_data_uint8 (strGet(LIPO2),&Config.PKT_Accutyp);
// print_data_uint8 (strGet(DISPLAY9),&Config.OSD_RCErrorbeep);
// print_data_uint8 (strGet(OSD_Invert_Out),&Config.OSD_InvertOut);
// print_data_uint8 (strGet(OSD_LED_Form),&Config.OSD_LEDform);
// print_data_uint8 (strGet(OSD_Send_OSD),&Config.OSD_SendOSD);
// print_data_uint8 (strGet(FALLSPEED),&Config.OSD_Fallspeed);
// print_data_uint8 (strGet(OSD_VARIOBEEP),&Config.OSD_VarioBeep);
// print_data_uint8 (strGet(OSD_HOMEMKVIEW),&Config.OSD_HomeMKView);
// print_data_uint16 (strGet(OSD_MAHWARNING),&Config.OSD_mAh_Warning);
// print_data_uint8 (strGet(OSD_SCREENMODE),&Config.OSD_ScreenMode);
// print_data_uint8 (strGet(OSD_LIPOBAR),&Config.OSD_LipoBar);
// print_data_uint8 (strGet(PKT_BAUDRATE),&Config.PKT_Baudrate);
// print_data_uint16 (strGet(FOLLOWME_1),&Config.FM_Refresh);
// print_data_uint16 (strGet(FOLLOWME_2),&Config.FM_Speed);
// print_data_uint16 (strGet(FOLLOWME_3),&Config.FM_Radius);
// print_data_uint8 (strGet(HWSOUND),&Config.HWSound);
// print_data_uint8 (strGet(HWBEEPER),&Config.HWBeeper);
// print_data_uint8 (PSTR("sIdxSteps:"),&Config.sIdxSteps);
// print_data_uint8 (strGet(SV_TEST3),&Config.servo_frame);
// print_data_uint8 (strGet(SV_SINGLESTEP),&Config.single_step);
// print_data_uint8 (strGet(SV_COUNTTEST),&Config.repeat);
// print_data_uint8 (strGet(SV_PAUSEEND),&Config.pause);
// print_data_uint8 (strGet(SV_PAUSEINC),&Config.pause_step);
//// print_data_int8 (,&Config.tracking);
//// print_data_int8 (,&Config.track_tx);
// print_data_uint16 (PSTR("Stick1_min:"),&Config.stick_min[0]);
// print_data_uint16 (PSTR("Stick2_min:"),&Config.stick_min[1]);
// print_data_uint16 (PSTR("Stick3_min:"),&Config.stick_min[2]);
// print_data_uint16 (PSTR("Stick4_min:"),&Config.stick_min[3]);
// print_data_uint16 (PSTR("Stick5_min:"),&Config.stick_min[4]);
// print_data_uint16 (PSTR("Stick1_max:"),&Config.stick_max[0]);
// print_data_uint16 (PSTR("Stick2_max:"),&Config.stick_max[1]);
// print_data_uint16 (PSTR("Stick3_max:"),&Config.stick_max[2]);
// print_data_uint16 (PSTR("Stick4_max:"),&Config.stick_max[3]);
// print_data_uint16 (PSTR("Stick5_max:"),&Config.stick_max[4]);
// print_data_uint8 (PSTR("Stick1_typ:"),&Config.stick_typ[0]);
// print_data_uint8 (PSTR("Stick2_typ:"),&Config.stick_typ[1]);
// print_data_uint8 (PSTR("Stick3_typ:"),&Config.stick_typ[2]);
// print_data_uint8 (PSTR("Stick4_typ:"),&Config.stick_typ[3]);
// print_data_uint8 (PSTR("Stick5_typ:"),&Config.stick_typ[4]);
// print_data_uint8 (PSTR("Stick1_neutral:"),&Config.stick_neutral[0]);
// print_data_uint8 (PSTR("Stick2_neutral"),&Config.stick_neutral[1]);
// print_data_uint8 (PSTR("Stick3_neutral:"),&Config.stick_neutral[2]);
// print_data_uint8 (PSTR("Stick4_neutral:"),&Config.stick_neutral[3]);
// print_data_uint8 (PSTR("Stick5_neutral:"),&Config.stick_neutral[4]);
// print_data_uint8 (strGet(LIPO_MESSUNG),&Config.Lipomessung);
// print_OSD_Statistic();
//}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void WriteWiInitFlag(void)
{
Config.WiIsSet = true;
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void WriteBTInitFlag(void)
{
Config.BTIsSet = true;
}
//--------------------------------------------------------------
//--------------------------------------------------------------
void WriteWLInitFlag(void)
{
Config.WLIsSet = true;
}
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void WriteBTSlaveFlag(void)
{
Config.BTIsSlave = true;
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void WriteBTMasterFlag(void)
{
Config.BTIsSlave = false;
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void WriteLastPosition( uint32_t ELongitude, uint32_t ELatitude)
 
{
Config.LastLongitude = ELongitude;
Config.LastLatitude = ELatitude;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void ReadParameter( void )
{
eeprom_read_block( (void*)&Config, (const void*)&EEStruct, sizeof(ST) );
 
// DEBUG !!
//Config.Version = 0x82;
//WriteParameter();
//return;
 
 
//-------------------
// ggf. ungueltige Zeichen aus dem
// Bluetooth-Namen eliminieren
//-------------------
#ifdef USE_BLUETOOTH
bt_fixname();
#endif
 
//-------------------
// 27.03.2014 OG
// Als Vorbereitung die Niederländische Sprache
// zu entfernen wird hier ggf. Niederländisch
// auf Englisch umgeschaltet
//-------------------
if( Config.DisplayLanguage == 2 ) // 2 = ehemals Niederländisch
Config.DisplayLanguage = 1; // -> wird zu 1 = Englisch
 
//-------------------
// 0. EEprom-Version nicht geaendert
//-------------------
if( Config.Version == EEpromVersion ) // nichts zu tun...
{
return; // !!! EXIT !!!
}
 
 
//-------------------
// 1. PKT-Upgrade NICHT Update faehig
// ODER Downgrade
//
// 0x77 = PKT Version 3.6.6a
//-------------------
if( (Config.Version < 0x77) || (Config.Version > EEpromVersion) )
{
Delete_EEPROM();
return; // !!! EXIT !!!
}
 
 
//-------------------
// 2. PKT-Upgrade
//-------------------
 
//++++++++++++++++++++++++++++
// bei Eeprom-Versionwechsel
// IMMER loeschen
//++++++++++++++++++++++++++++
#ifdef USE_WAYPOINTS
PointList_Clear(); // Init Waypoints
#endif
STAT_Init(); // Init OSD Statistik
GPS_User_Init(); // Init GPS Positionen
MKErr_Log_Init(); // Init MK Errorlog
 
 
//++++++++++++++++++++++++++++
// inkrementelle Updates
//++++++++++++++++++++++++++++
 
//-----------------------------
//--- ab PKT v3.6.9bX6
//-----------------------------
if( Config.Version < 0x81 )
{
Config.timezone = 1;
Config.summertime = 1;
}
 
//-----------------------------
//--- ab PKT v3.7.0b
//-----------------------------
if( Config.Version < 0x82 )
{
Config.OSD_ShowMKSetting = true;
}
 
//-----------------------------
//--- ab PKT v3.7.0e
//-----------------------------
if( Config.Version < 0x83 )
{
Config.UseWL = false;
Config.WLIsSet = false;
strcpy_P( Config.Wlan_SSID , PSTR("PKT")); // Wlan
strcpy_P( Config.Wlan_Password, PSTR("12345678")); // Wlan
}
 
//-----------------------------
//--- ab PKT v3.7.0eX1
//-----------------------------
if( Config.Version < 0x84 )
{
Config.OSD_UseScreen = 0xffffffff; // alle verfuegbaren OSD-Screens eingeschaltet
}
 
//-----------------------------
//--- ab PKT v3.7.0f
//-----------------------------
if( Config.Version < 0x85 )
{
Config.Wlan_DHCP = 0;
Config.Wlan_WPA = 0;
Config.Wlan_Adhoc = true;
Config.Wlan_Channel = 1;
strcpy_P( Config.Wlan_IP , PSTR("169.254.001.001"));
strcpy_P( Config.Wlan_Netmask, PSTR("255.255.000.000"));
strcpy_P( Config.Wlan_Gateway, PSTR("169.254.001.001"));
}
 
//-----------------------------
//--- ab PKT v3.7.3cX5
//-----------------------------
if( Config.Version < 0x87 )
{
Config.OSD_ShowCellU = false; //
}
 
 
//-----------------------------
//--- 01.04.2014 OG
//--- ab PKT v3.7.4aX7
//-----------------------------
if( Config.Version < 136 )
{
Config.UseBLE = false; // Bluetooth 4 LowPower wird genutzt (RedBearLab BLE Mini) wird an SV2 genutzt (SV2 Patch erforderlich)
memset( Config.MKParam_Favs, param_EOF, MAX_MKPARAM_FAVORITES ); // Array von MK-Parameter Favoriten des Benutzers
}
 
 
//-----------------------------
//--- 06.04.2014 OG
//--- ab PKT v3.7.4aX8
//-----------------------------
if( Config.Version < 137 )
{
strcpy_P( Config.Wlan_HomeSSID , PSTR("")); // WiFly Home-Wlan: SSID (Home-WLAN)
strcpy_P( Config.Wlan_HomePassword, PSTR("")); // WiFly Home-Wlan: Passwort (Home-WLAN)
}
 
 
//-----------------------------
//--- 07.05.2014 OG
//--- ab PKT v3.80bX3
//-----------------------------
if( Config.Version < 138 )
{
memset( Config.MKParam_Favs, 0, MAX_MKPARAM_FAVORITES ); // Array von MK-Parameter Favoriten des Benutzers (Vorbelegung jetzt 0)
}
 
 
//-----------------------------
//--- 17.06.2014 OG
//--- ab PKT v3.80cX5
//-----------------------------
if( Config.Version < 139 )
{
Config.PKTOffTimeout = 0; // autom. PKT ausschalten nach n Minuten (0=immer an)
}
 
 
 
//-------------------
// 3. Update Message
//-------------------
Config.Version = EEpromVersion; // Update EEPROM version number
sei();
 
lcd_cls();
lcdx_printp_center( 2, PSTR("EEProm updated to"), MNORMAL, 0,0);
lcdx_printp_center( 3, PSTR("new Version") , MNORMAL, 0,0);
lcdx_printp_center( 5, PSTR("check settings!") , MNORMAL, 0,0);
lcd_printp_at (18, 7, PSTR("OK") , MNORMAL); // Keyline
 
while( !get_key_press(1 << KEY_ENTER) );
WriteParameter();
cli();
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void WriteParameter( void )
{
copy_line(7);
lcd_printp_at( 0, 7, PSTR(" Write EEPROM "), MNORMAL);
eeprom_update_block( (const void*)&Config, (void*)&EEStruct, sizeof(ST) );
paste_line(7);
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Delete_EEPROM( void )
{
uint8_t i;
 
// EEPROM auf Default setzen
 
lcd_cls();
lcd_printp_at( 0, 0, PSTR(" EEPROM Parameter "), MINVERS);
lcd_printp_at( 0, 1, PSTR("werden auf") , MNORMAL);
lcd_printp_at( 0, 2, PSTR("Standardwerte gesetzt"), MNORMAL);
 
Config.MK_LowBat = 137; // 13,7V
Config.DisplayTimeout = 0; // Display immer an (autom. LCD ausschalten nach n Minuten)
Config.DisplayLanguage = 5; // default undefined
Config.WiTXRXChannel = 1; // Kanal 1 MK Standard
Config.WiNetworkGroup = 66; // Gruppe 66 MK Standard
Config.WiNetworkMode = NetMode_Normal; // MK Standard
Config.WiTXTO = TWaitTime16; // MK Standard
Config.WiUartMTU = UartMTU64; // MK Standard
Config.OSD_ShowMKSetting= true; // Anzeige MK-Setting beim OSD Start
Config.PKTOffTimeout = 0; // PKT immer an (autom. PKT ausschalten nach n Minuten)
Config.LCD_Kontrast = 20; // Kontrast normal
Config.LCD_Helligkeit = 100; // Helligkeit in %
Config.USBBT = 0; // USB Betrieb
Config.U02SV2 = 0; // SV2 (Kabel) Standard
Config.Debug = 0; // kein Debug
Config.UseWi = false; // Wi.232 eingebaut?
Config.UseBT = false; // BT-222 eingebaut?
Config.WiIsSet = false; // Flag für die Initialisierung Wi232
Config.BTIsSet = false; // Flag für die Initialisierung Bluetooth
Config.BTIsSlave = true; // Slave Flag setzen
Config.PKT_IdleBeep = 0; // kein Piepsen bei Inaktivität
Config.PKT_StartInfo = false; // * FREI * (ehemals: PKT Startinfo anzeigen)
Config.OSD_RCErrorbeep = true; // OSD Receiveerrorbeep
Config.OSD_InvertOut = false; // LED Anzeige invertiren
Config.OSD_LEDform = 1; // Form der Anzeige ( + oder schwarz)
Config.OSD_SendOSD = false; // OSD Daten an SV2
Config.OSD_Fallspeed = 40; // maximale Sinkrate
Config.OSD_VarioBeep = 1; // Vario Beep ein
Config.OSD_HomeMKView = true; // * FREI * (ehemals: Home Circle from MK View)
Config.OSD_mAh_Warning = 10000; // mAh Warnschwelle
Config.OSD_ScreenMode = 0; // Variante des OSD Screen
Config.OSD_LipoBar = 0; // Bargraphanzeige für MK Lipo
Config.PKT_Baudrate = Baud_57600; // Baudrate für BT und Wi232
Config.PKT_Accutyp = true; // verwendeter Akkutyp (true=Lipo, false=LiON)
Config.Lipo_UOffset = 10000; // Offset für PKT-Lipomessung
Config.FM_Azimuth = 0; // FollowMe Azimuth
Config.FM_Distance = 0; // FollowMe Distance
Config.FM_Speed = 30; // FollowMe Speed in m/s *0.1
Config.FM_Radius = 5; // Waypoint Tolerance Radius in meter
Config.HWSound = 0; // Hardware Sounderweiterung an PD7
Config.HWBeeper = 1; // Hardware Beeper an PC7
Config.Volume = 0; // Lautstaerke
Config.LastLongitude = 0x00000000;
Config.LastLatitude = 0x00000000;
 
strcpy_P(Config.bt_pin , PSTR("0000"));
strcpy_P(Config.bt_name, PSTR("PKT")); // Bluetooth-Name max. 10 Zeichen! - NICHT mit Leerzeichen auffüllen (bt_name_length)
strcpy_P(Config.bt_Mac , PSTR("0000-00-000000"));
strcpy_P(Config.RE_ID , PSTR("0000"));
 
for( i = 0; i < 20; i++)
{
Config.gps_UsedDevName[i] = 0; // benutztes GPS Device Name
}
for( i = 0; i < 14; i++)
{
Config.gps_UsedMac[i] = '0'; // benutztes GPS Device Mac Adresse
}
Config.gps_UseGPS = false; // ist GPS aktiv?
Config.gps_UsedGPSMouse = GPS_Bluetoothmouse1;
 
//Config.WiIsSet = false; // 15.07.2013 CB doppelt drin
//Config.BTIsSet = false;
Config.Version = EEpromVersion;
Config.sIdxSteps = STEPS_255;
Config.servo[0].rev = SERVO_REV;
Config.servo[0].min = SERVO_I0_RIGHT;
Config.servo[0].max = SERVO_I0_LEFT;
Config.servo[0].mid = SERVO_I0_MIDDLE;
Config.servo[1].rev = SERVO_REV;
Config.servo[1].min = SERVO_I0_RIGHT;
Config.servo[1].max = SERVO_I0_LEFT;
Config.servo[1].mid = SERVO_I0_MIDDLE;
Config.servo_frame = SERVO_PERIODE;
Config.single_step = SINGLE_STEP; // nur bei Test-Servo
Config.repeat = REPEAT; // nur bei Test-Servo
Config.pause = PAUSE; // nur bei Test-Servo
Config.pause_step = PAUSE_STEP; // nur bei Test-Servo
Config.tracking = TRACKING_MIN;
Config.track_hyst = TRACKING_HYSTERESE;
Config.track_tx = 0;
 
for( i=0; i<5; i++)
{
Config.stick_min[i] = 30+i; // Joystick
Config.stick_max[i] = 270+i; // Joystick
Config.stick_typ[i] = 0; // Joystick
Config.stick_dir[i] = 0; // Joystick
Config.stick_neutral[i] = 0; // Joystick
}
 
Config.Lipomessung = true;
 
Config.timezone = 1;
Config.summertime = 1;
 
strcpy_P( Config.Wlan_SSID , PSTR("PKT")); // Wlan
strcpy_P( Config.Wlan_Password, PSTR("12345678")); // Wlan
Config.WLIsSet = false; // Wlan
Config.UseWL = false;
Config.OSD_UseScreen = 0xffffffff; // alle OSD-Screens eingeschaltet
Config.Wlan_DHCP = 0; // kein DHCP
Config.Wlan_WPA = 0; // 0 = adhoc 1= WPA2
Config.Wlan_Adhoc = true; // Adhoc
Config.Wlan_Channel = 1; // Wlan Channel
strcpy_P( Config.Wlan_IP , PSTR("169.254.001.001"));
strcpy_P( Config.Wlan_Netmask, PSTR("255.255.000.000"));
strcpy_P( Config.Wlan_Gateway, PSTR("169.254.001.001"));
Config.OSD_ShowCellU = false;
Config.UseBLE = false;
 
memset( Config.MKParam_Favs, 0, MAX_MKPARAM_FAVORITES ); // Favoriten MK-Parameter (Anzahl: MAX_MKPARAM_FAVORITES = 10)
 
strcpy_P( Config.Wlan_HomeSSID , PSTR("")); // WiFly Home-Wlan: SSID (Home-WLAN)
strcpy_P( Config.Wlan_HomePassword, PSTR("")); // WiFly Home-Wlan: Passwort (Home-WLAN)
 
//-------------------------------------------------
//-------------------------------------------------
#ifdef USE_WAYPOINTS
PointList_Clear();
#endif
STAT_Init(); // Init OSD Statistik
GPS_User_Init(); // Init GPS Positionen
MKErr_Log_Init(); // Init MK Errorlog
 
WriteParameter();
 
//lcd_printp_at (0, 4, PSTR("Waypoints loeschen"), 0);
//EEWayPointList_Clear();
 
lcd_printp_at( 0, 6, PSTR("!!Check Parameter!! "), MNORMAL);
lcd_printp_at(18, 7, PSTR("OK") , MNORMAL);
sei();
set_beep( 200, 0x0080, BeepNormal);
 
while( !get_key_press (1 << KEY_ENTER) );
 
 
//#if defined HWVERSION3_9
clr_V_On();
//#else
//
// wdt_enable( WDTO_250MS );
// while (1)
// {;}
//#endif
}
 
 
//--------------------------------------------------------------
//
//void EEWayPointList_Clear(void) // löschen der Waypointliste im EEProm
//{
// uint8_t i;
// PKTWayPoint.Waypoint.Position.Latitude = 0;
// PKTWayPoint.Waypoint.Position.Longitude = 0;
// PKTWayPoint.Waypoint.Position.Altitude = 0;
// PKTWayPoint.Waypoint.Heading = 361;
 
// for(i = 0; i < MAX_WPLIST_LEN; i++)
// {
// PKTWayPointDirectory.WPList.WPDirectory[i] = 0;
// }
 
// for(i = 0; i < NumberOfWaypoints; i++)
// {
// lcd_printp (PSTR("."), 0);
// eeprom_write_byte (&EEWayPointList[i].WPIndex, i);
// eeprom_write_byte (&EEWayPointList[i].Waypoint.Position.Status, INVALID);
// eeprom_write_block ((const void*)&PKTWayPoint.Waypoint.Position.Latitude, (void*)&EEWayPointList[i].Waypoint.Position.Latitude, sizeof(EEWayPointList[i].Waypoint.Position.Latitude));
// eeprom_write_block ((const void*)&PKTWayPoint.Waypoint.Position.Longitude, (void*)&EEWayPointList[i].Waypoint.Position.Longitude, sizeof(EEWayPointList[i].Waypoint.Position.Longitude));
// eeprom_write_block ((const void*)&PKTWayPoint.Waypoint.Position.Altitude, (void*)&EEWayPointList[i].Waypoint.Position.Altitude, sizeof(EEWayPointList[i].Waypoint.Position.Altitude));
// eeprom_write_block ((const void*)&PKTWayPoint.Waypoint.Heading, (void*)&EEWayPointList[i].Waypoint.Heading, sizeof(EEWayPointList[i].Waypoint.Heading));
//
// eeprom_write_byte (&EEWayPointList[i].Waypoint.ToleranceRadius, 0); // in meters, if the MK is within that range around the target, then the next target is triggered
// eeprom_write_byte (&EEWayPointList[i].Waypoint.HoldTime, 0); // in seconds, if the was once in the tolerance area around a WP, this time defines the delay before the next WP is triggered
// eeprom_write_byte (&EEWayPointList[i].Waypoint.Type, POINT_TYPE_INVALID);
// eeprom_write_byte (&EEWayPointList[i].Waypoint.Event_Flag, 0); // future implementation
// eeprom_write_byte (&EEWayPointList[i].Waypoint.AltitudeRate, 0); // no change of setpoint
// }
 
// for(i = 0; i < NumberOfWPLists; i++)
// {
// lcd_printp (PSTR("."), 0);
// eeprom_write_byte (&EEWPDirectory[i].WPList.WPListnumber, i);
// eeprom_write_byte (&EEWPDirectory[i].WPList.WPListAktiv, false);
// eeprom_write_byte (&EEWPDirectory[i].WPList.POI_CAM_NICK_CTR, 0);
// eeprom_write_byte (&EEWPDirectory[i].WPList.UsePOI, 0);
// eeprom_write_block ((const void*)&PKTWayPointDirectory.WPList.WPDirectory, (void*)&EEWPDirectory[i].WPList.WPDirectory, sizeof(EEWPDirectory[i].WPList.WPDirectory));
//
// }
// lcd_printp (PSTR("\r\n"), 0);
 
//}
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/eeprom/eeprom.h
0,0 → 1,333
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2013 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
//############################################################################
//# HISTORY eeprom.h
//#
//# 03.08.2015 CB
//# - chg: Obsolete Parameter geändert und für FollowMe verwendet, EEprom Version bleibt gleich
//# Parameter FM_Refresh in FM_Azimuth geändert
//# Parameter hyst_u_min in FM_Distance geändert
//#
//# 25.06.2014 OG
//# - chg: Kommentare der eeprom Struct aktualisert bzgl. FollowMe und Tracking
//#
//# 17.06.2014 OG
//# - chg: EEpromversion erhoeht auf 139
//#
//# 13.06.2014 OG
//# - chg: LCD_DisplayMode (Obsolete) geaendert zu PKTOffTimeout
//#
//# 31.05.2014 OG
//# - Recherche welche Config-Werte ueberahupt noch im PKT-Code verwendet werden
//# und ggf. "OBSOLETE" Anmerkung in der Config-Struct
//# - Config-Struct wurde um etliche Kommentare ergaenzt bzgl. Verwendungszweck
//#
//# 30.05.2014 OG
//# - chg: Kommentare geaendert
//#
//# 26.05.2014 OG
//# - chg: Config.LCD_DisplayMode als "OBSOLETE" markiert
//#
//# 07.05.2014 OG
//# - chg: EEpromversion erhoeht auf 138
//# -> keine neuen Parameter, neue Version nur fuer geanderte
//# Initialisierung von MKParam_Favs
//#
//# 06.04.2014 OG
//# - chg: EEpromversion erhoeht auf 137
//# - add: Config.UseBLE
//# - add: Config.MKParam_Favs
//#
//# 01.04.2014 OG
//# - chg: EEpromversion erhoeht auf 136
//# - chg: ACHTUNG! EEpromversion umgestellt von HEX auf DEZIMAL: 0x87 => 135
//# - add: Config.UseBLE
//# - add: Config.MKParam_Favs
//# - add: MAX_MKPARAM_FAVORITES
//#
//# 03.02.2014 OG
//# - add: Config.OSD_ShowCellU; EEpromversion erhoeht auf 0x87
//#
//# 28.08.2013 Cebra
//# - chg: LastLatitude war uint32_t, auf int32_t korrigiert
//#
//# 04.07.2013 Cebra
//# - add: neue Parameter fuer Wlan; EEpromversion erhoeht auf 85
//#
//# 04.07.2013 OG
//# - add: Config.OSD_UseScreen; Epromversion erhoeht auf 84
//#
//# 02.07.2013 Cebra
//# - add: neue Parameter fuer Wlan; EEpromversion erhoeht auf 83
//#
//# 20.06.2013 CB
//# - chg: EEPROM Versionsänderung auf 82 wegen Wechsel LCD_Orientation zu OSD_ShowMKSetting
//#
//# 15.06.2013 OG
//# - chg: Config.LCD_ORIENTATION zu Config.OSD_ShowMKSetting
//#
//# 31.05.2013 CB
//# - chg: EEPROM Strukturänderung, Listen/Statistik ganz ans Ende gesetzt
//#
//# 31.05.2013 OG
//# - chg: Eeprom Version auf 81 wegen Erweiterungen der Statistik-Daten
//# - chg: Code-Layout
//#
//# 12.04.2013 CB
//# - chg: Kommentarergänzung U02SV2
//#
//# 28.03.2013 CB
//# - add: save and upgrade OSD_Statistic, GPS_User, MKErr_Log in EEProm structure variable
//############################################################################
 
#ifndef _EEPROM_H
#define _EEPROM_H
 
#include <stdbool.h>
#include "../mk-data-structs.h"
#include "../connect.h"
#include "../tracking/ng_servo.h"
#include "../waypoints/waypoints.h"
#include "../osd/osd.h"
 
 
 
 
//[General]
//FileVersion = 2
//NumberOfWaypoints = 15
//UsePOI = 0
//POI_CAM_NICK_CTRL = 0
 
//[POI]
//Altitude = 1
//Latitude = 46.7140763
//Longitude = 19.2507334
 
//[Waypoint1]
//Latitude = 46.7145686
//Longitude = 19.2515702
//Radius = 10
//Altitude = 15
//ClimbRate = 0
//DelayTime = 4
//WP_Event_Channel_Value = 96
//Heading = 180
 
 
#define EEpromVersion 139 // wird nach jeder Parametererweiterung hochgezählt
// Anmerkung 01.04.2014 OG: umgestellt auf DEZIMALE schreibweise (wiso war das vorher Hex?)
 
#define NumberOfWaypoints 55 // Anzahl der Waypoints in der EEPromliste
#define NumberOfWPLists 5 // Anzahl WP Listen im PKT
#define MAX_LIST_LEN 31 // Länge Waypointlist
 
#define MAX_MKPARAM_FAVORITES 10 // Anzahl der MK-Parameter Favoriten (nicht aendern!)
 
#define bt_pin_length 4
#define RE_ID_length 4 // Länge der RE-ID
#define bt_name_length 10
#define bt_mac_length 14
#define GPS_Bluetoothmouse1 0 // NMEA BT-Mouse
#define GPS_Mikrokopter 1 // GPS Daten vom MK für Tracking
 
#define wlan_password_length 10 // Länge Wlan-Passwort
#define wlan_ssid_length 10 // Länge Wlan-SSID
#define wlan_ip_length 15
#define wlan_netmask_length 15
#define wlan_gateway_length 15
 
#define POINT_TYPE_INVALID 255
#define POINT_TYPE_WP 0
#define POINT_TYPE_POI 1
#define INVALID 0x00
#define MAX_WPLIST_LEN 31
 
 
 
 
//typedef struct {
// uint8_t rev;
// uint16_t min;
// uint16_t max;
// uint16_t mid;
//} servo_t;
 
 
typedef struct
{
uint8_t WPIndex; // Index in der EEpromliste
Point_t Waypoint; // Waypoint
} WayPoints;
 
typedef struct
{
uint8_t WPListnumber; // Nummer der WP Liste im PKT
uint8_t WPListAktiv; // Liste aktiv
uint8_t WPDirectory[31]; // Enthält die Indexe der Waypoints im EEPROM
uint8_t UsePOI;
uint8_t POI_CAM_NICK_CTR;
 
} WPListHeader;
 
typedef struct
{
WPListHeader WPList; // Waypointliste im PKT
} WPListDirectory;
 
 
 
typedef struct SStructure
{
uint8_t Version; // PKT-Eeprom Version!
uint8_t MK_LowBat; // MK-LowBat Warnung u.a. fuer osd.c
uint8_t DisplayTimeout; // autom. LCD ausschalten nach n Minuten
uint8_t DisplayLanguage; // eingestellte Sprache
uint8_t WiTXRXChannel; // Wi.232:
uint8_t WiNetworkGroup; // Wi.232:
uint8_t WiNetworkMode; // Wi.232:
uint8_t WiTXTO; // Wi.232:
uint8_t WiUartMTU; // Wi.232:
uint8_t OSD_ShowMKSetting; // Anzeige MK-Setting beim OSD Start
uint8_t PKTOffTimeout; // autom. PKT ausschalten nach n Minuten
uint8_t LCD_Kontrast; // LCD-Kontrast
uint8_t LCD_Helligkeit; // LCD-Helligkeit - Aktuell nicht mehr verfuegbar weil auskommentiert! (mit HW 3.9x geht das sowiso nicht mehr!)
uint8_t USBBT; // ## OBSOLETE ## 31.05.2014 OG: wird nicht verwendet! (wofuer war da in der Vergangenheit?)
uint8_t U02SV2; // 0=Wi232-Verbindung zum MK, 1 = Kabelverbindung zum MK
uint8_t Debug; // ??? OBSOLETE ??? 31.05.2014 OG: wird eigentlich nicht mehr verwendet (war zum debuggen vom PKT)
uint8_t UseWi; // Wi232 wird genutzt
uint8_t UseBT; // BT wird genutzt
 
uint8_t WiIsSet; // Wi232 ist initialisiert
uint8_t BTIsSet; // BT ist initialisiert
uint8_t BTIsSlave; // Slave Flag
char bt_pin[bt_pin_length + 1]; // BT Pinnummer
char bt_name[bt_name_length + 1]; // BT Name
char RE_ID[RE_ID_length + 1]; // RE-ID
char bt_Mac[bt_mac_length + 1]; // MAC-Adresse BTM222
 
char gps_UsedDevName[20]; // benutztes GPS Device Name
char gps_UsedMac[14]; // benutztes GPS Device Mac Adresse
uint8_t gps_UseGPS; // ## GGF. OBSOLETE ## 25.06.2014 OG: siehe setup.c/Setup_GPSMouse() - "ist GPS aktiv?"
uint8_t gps_UsedGPSMouse; // ## GGF. OBSOLETE ## 25.06.2014 OG: siehe setup.c/Setup_GPSMouse() und tracking.c/PKT_tracking() - "GPS Maustyp"
 
int32_t LastLongitude; // Letzte Position
int32_t LastLatitude; // Letzte Position
uint8_t PKT_IdleBeep; // ## OBSOLETE ## 31.05.2014 OG: wurde das jemals verwendet?
uint8_t PKT_StartInfo; // ## OBSOLETE ## 26.06.2013 OG: ehemals "PKT Startinfo anzeigen"
uint16_t Lipo_UOffset; // Offset für die Lipospannugsmessung
uint8_t PKT_Accutyp; // verwendeter Akkutyp
uint8_t OSD_RCErrorbeep; // Empfangsausffallwarnung im OSD Screen
uint8_t OSD_InvertOut; // Out1/2 invertiert anzeigen
uint8_t OSD_LEDform; // Form der Anzeige ( + oder schwarz)
uint8_t OSD_SendOSD; // OSD Daten an SV2 senden
uint8_t OSD_Fallspeed; // maximale Sinkrate
uint8_t OSD_VarioBeep; // Vario Beep im OSD Screen
uint8_t OSD_HomeMKView; // ## OBSOLETE ## 02.07.2013 OG: ehemals "Home Circle from MK-View"
uint16_t OSD_mAh_Warning; // mAh Warnschwelle
uint8_t OSD_ScreenMode; // Variante des OSD-Screen
uint8_t OSD_LipoBar; // Bargraphanzeige für MK Lipo
uint8_t PKT_Baudrate; // Baudrate für BT und Wi232
uint16_t FM_Azimuth; // Azimuth für FollowMe 4.8.2015 CB
uint16_t FM_Speed; // FollowMe Speed in m/s *0.1
uint16_t FM_Radius; // Waypoint Tolerance Radius in meter
uint8_t HWSound; // Hardware Sounderweiterung an PD7
uint8_t HWBeeper; // Hardware Beeper an PC7
uint8_t Volume; // Lautstärke
servo_t servo[2]; // Tracking:
uint8_t sIdxSteps; // Tracking:
uint16_t FM_Distance; // Distance für FollowMe 4.8.2015 CB
uint8_t servo_frame; // Tracking:
uint8_t single_step; // Tracking:
uint8_t repeat; // Tracking:
uint8_t pause; // Tracking:
uint8_t pause_step; // Tracking:
uint8_t tracking; // ## OBSOLETE ## 31.05.2014 OG: das wird nirgendwo verwendet!
uint8_t track_hyst; // ## OBSOLETE ## 31.05.2014 OG: das wird nirgendwo verwendet!
uint8_t track_tx; // ## OBSOLETE ## 31.05.2014 OG: das wird nirgendwo verwendet!
 
uint16_t stick_min[5]; // Joystick: Stickparameter
uint16_t stick_max[5]; // Joystick:
uint8_t stick_typ[5]; // Joystick:
uint8_t stick_dir[5]; // Joystick:
uint8_t stick_neutral[5]; // Joystick: Stick neutralisierend: ja/nein
uint8_t Lipomessung; // wenn Lipomessung deaktiviert(Lötbrücke öffnen), kann der Kanal als Stick verwendet werden
int8_t timezone; // Einstellbereich -12 .. 0 .. 12 Defaultwert: 1 (entspricht unserer Zeitzone)
uint8_t summertime; // Einstellung: 0 oder 1 (0=Winterzeit, 1=Sommerzeit) Defaultwert: 1 (entspricht unserer Sommerzeit in D)
uint8_t UseWL; // WLAN (WiFly) wird an SV2 genutzt (SV2 Patch erforderlich)
char Wlan_SSID[wlan_ssid_length+1]; // Wlan SSID
char Wlan_Password[wlan_password_length+1]; // Wlan Passwort
uint8_t WLIsSet; // ## OBSOLETE ## 31.05.2014 OG: ehemals "Wlan ist initialisiert"
uint32_t OSD_UseScreen; // welche OSD-Screens nutzen (Bit-codiert)
uint8_t Wlan_DHCP; // ## OBSOLETE ## 31.05.2014 OG: ehemals "0-4"
uint8_t Wlan_WPA; // ## OBSOLETE ## 31.05.2014 OG: ehemals "0-8"
uint8_t Wlan_Adhoc; // ## OBSOLETE ## 31.05.2014 OG: ehemals "false = AP , true = Adhoc"
uint8_t Wlan_Channel; // 0-13
char Wlan_IP[wlan_ip_length+1]; // ## OBSOLETE ## 31.05.2014 OG: ehemals "IP-Adresse" (16 Bytes!)
char Wlan_Netmask[wlan_netmask_length+1]; // ## OBSOLETE ## 31.05.2014 OG: ehemals "SubnetMask" (16 Bytes!)
char Wlan_Gateway[wlan_gateway_length+1]; // ## OBSOLETE ## 31.05.2014 OG: ehemals "Defaultgateway" (16 Bytes!)
uint8_t OSD_ShowCellU; // OSD Azeige: Anzeige UBat als Einzelzellenspannung (ja/nein)
uint8_t UseBLE; // Bluetooth 4 LowPower wird genutzt (RedBearLab BLE Mini) wird an SV2 genutzt (SV2 Patch erforderlich)
unsigned char MKParam_Favs[MAX_MKPARAM_FAVORITES]; // Array von MK-Parameter Favoriten des Benutzers
 
char Wlan_HomeSSID[wlan_ssid_length+1]; // Wlan SSID (Home-WLAN)
char Wlan_HomePassword[wlan_password_length+1]; // Wlan Passwort (Home-WLAN)
 
 
//!!!neue Parameter ab hier anfügen!!!!!!
 
 
// ab hier werden die Parameter bei EEPROMversionsänderungen gelöscht
Point_t PointList[MAX_LIST_LEN]; // ab EEPROM Version 78
osd_statistic_t OSD_Statistic; // ab EEPROM Version 79 & 81 OSD Statistiken
pkt_gpspos_t GPS_User[MAX_GPS_USER]; // ab EEPROM Version 79 speichert Benutzer GPS-Positionen
mkerror_t MKErr_Log[MAX_MKERR_LOG]; // ab EEPROM Version 79 speichert auftretende ErrorCode's vom MK
 
} ST;
 
extern ST Config;
 
void ReadParameter (void);
void WriteParameter (void);
void ReadLastPosition(void);
void WriteLastPosition(uint32_t ELongitude,uint32_t ELatitude);
void WriteWiInitFlag(void);
void WriteBTInitFlag(void);
void WriteWLInitFlag(void);
void WriteBTSlaveFlag(void);
void WriteBTMasterFlag(void);
void Delete_EEPROM(void);
void SendConfigData(void);
//void EEWayPointList_Clear(void); // l�schen der Waypointliste im EEProm
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/followme/followme.c
0,0 → 1,673
/*
* FollowMe.c
*
* Created on: 18.05.2012
* Author: cebra
*/
/*****************************************************************************
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
//############################################################################
//# HISTORY followme.c
//#
//# 20.09.2015 Starter
//# FollowMeStep2 erweitert auf aktuelle GPS-Daten und followme_calculate_offset(...)
//#
//# 03.08.2015 Cebra
//# - add: void Debug_GPS (void) hinzugefügt zur Test der GPS Berechnung FollowMe
//#
//# 20.07.2015 CB
//# - chg: FollowMe Datensatz an NC.211 angepasst
//#
//# 27.06.2014 OG
//# - chg: Anzeige von Satfix und Satanzahl auf MINVERSX, MNORMALX
//#
//# 26.06.2014 OG
//# - chg: angepasst auf neue NMEA-Datenstruktur (gps_nmea.h)
//#
//# 24.06.2014 OG
//# - chg: FollowMe() angepasst auf geaendertes GPSMouse_ShowData()
//#
//# 22.06.2014 OG
//# - chg: FollowMe() umgestellt auf GPSMouse_ShowData() (in gps/gpsmouse.c)
//# - del: Variable CheckGPS
//#
//# 21.06.2014 OG
//# - chg: verschiedene Layoutaenderungen am Anzeigescreen und Anzeige der
//# Entfernung zwischen Kopter und Target
//# - chg: MK-Timeoutout Erkennung verbessert/angepasst
//#
//# 19.06.2014 OG
//# - erster Prototyp der Follow Me zum Kopter sendet
//# - etliche Aenderungen im Codeaufbau
//#
//# 01.06.2014 OG
//# - chg: FollowMe() - verschiedene Anzeigefunktionen auskommentiert und
//# als DEPRICATED Klassifiziert wegen Cleanup der alten OSD Screens
//# - chg: FollowMe() - Check bzgl. NC-Hardware entfernt da das bereits durch das
//# Hauptmenue erledigt wird
//#
//# 13.05.2014 OG
//# - chg: FollowMe() - Variable 'flag' auskommentiert
//# wegen Warning: variable set but not used
//# - chg: FollowMe() - Variable 'old_FCFlags' auskommentiert
//# wegen Warning: variable set but not used
//# - chg: FollowMe() - den Bereich in dem FC-Settings geladen werdeb
//# auskommentiert weil man das a) vorallem nicht benoetigt
//# und b) die load_setting() so nicht mehr existiert
//# (der Codebereich kann meines erachtens geloescht werden)
//# - del: verschiedene Verweise auf 'mk_param_struct' entfernt, weil es
//# das a) nicht mehr gibt und b) hier gar nicht benoetigt wird
//# - chg: FollowMe() - OSD_Timeout() entfernt (weil es das nicht mehr gibt)
//# und erstmal durch ein PKT_Message_P() ersetzt
//# * ACHTUNG: UNGETESTET! * (bei Bedarf anpassen, followme hat niedrige Prio)
//# - add: #include "../pkt/pkt.h"
//#
//# 05.05.2013 Cebra
//# - chg: #ifdef USE_FOLLOWME
//#
//############################################################################
 
#include "../cpu.h"
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
 
#include <string.h>
#include <stdarg.h>
#include <stdio.h>
 
#include "../main.h"
 
#ifdef USE_FOLLOWME
 
#include "../followme/followme.h"
#include "../osd/osd.h"
#include "../lcd/lcd.h"
#include "../timer/timer.h"
#include "../uart/usart.h"
#include "../eeprom/eeprom.h"
#include "../messages.h"
#include "../bluetooth/bluetooth.h"
#include "../setup/setup.h"
#include "../uart/uart1.h"
#include "../mk-data-structs.h"
#include "../pkt/pkt.h"
#include "../gps/gps.h"
//#include "../gps/gps_nmea.h"
#include "../avr-nmea-gps-library/nmea.h"
#include "../gps/gpsmouse.h"
 
 
//#######################################################################################################################
 
 
//--------------------
// Timings
//--------------------
//#define MK_TIMEOUT 300 // MK-Verbindungsfehler wenn fuer n Zeit keine gueltigen Daten hereinkommen (3 sec)
#define MK_TIMEOUT 400 // MK-Verbindungsfehler wenn fuer n Zeit keine gueltigen Daten hereinkommen (4 sec)
 
 
 
//--------------------
#define COSD_WASFLYING 4
 
// global definitions and global vars
NaviData_t *naviData;
unsigned char Element;
uint16_t heading_home;
 
// Hier Höhenanzeigefehler Korrigieren
#define AltimeterAdjust 1.5
 
 
 
// Flags
//uint8_t COSD_FLAGS2 = 0;
//
//GPS_Pos_t last5pos[7];
uint8_t FM_error = 0;
 
 
//---------------------
// Waypoint Types
// TODO OG: verschieben nach: mk-data-structs.h
//---------------------
#define POINT_TYPE_INVALID 255
#define POINT_TYPE_WP 0
#define POINT_TYPE_POI 1
 
 
//---------------------
// Status
// GPS_Pos_t
// aus MK source
//
// TODO OG: verschieben nach: mk-data-structs.h
//---------------------
#define INVALID 0x00
#define NEWDATA 0x01
#define PROCESSED 0x02
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void FollowMe( void )
{
//uint8_t status;
GPS_Pos_t currpos;
uint8_t tmp_dat;
uint8_t redraw;
uint8_t drawmode;
uint32_t NMEA_GPGGA_counter_old; // Merker: zaehlt empfangene GPGGA-Pakete
uint32_t send_followme_counter;
 
int8_t ok;
int8_t xoffs;
int8_t yoffs;
Point_t FollowMe;
uint8_t mktimeout = false;
 
 
 
GPS_PosDev_t targetdev;
 
 
//---------------------
// 1. Daten GPS-Maus
//---------------------
ok = GPSMouse_ShowData( GPSMOUSE_SHOW_WAITSATFIX, 500 ); // 500 = 5 Sekunden Verzoegerung nach Satfix
if( ok <= 0 )
{
return; // Fehler bzgl. BT GPS-Maus -> exit
}
 
 
 
//---------------------
// 2. Follow Me
//---------------------
set_beep( 25, 0xffff, BeepNormal ); // kurzer Bestaetigungs-Beep
 
lcd_cls ();
 
SwitchToNC();
 
mode = 'O';
 
// disable debug...
// RS232_request_mk_data (0, 'd', 0);
tmp_dat = 0;
SendOutData ('d', ADDRESS_ANY, 1, &tmp_dat, 1);
 
// request OSD Data from NC every 100ms
// RS232_request_mk_data (1, 'o', 100);
tmp_dat = 10;
SendOutData ('o', ADDRESS_NC, 1, &tmp_dat, 1);
 
//OSD_active = true; // benötigt für Navidata Ausgabe an SV2
 
//-------------------------
// Init: Timer & Flags
//-------------------------
timer_mk_timeout = MK_TIMEOUT;
 
abo_timer = ABO_TIMEOUT;
 
 
MKLiPoCells_Init();
 
redraw = true;
 
NMEA.Counter = 0;
NMEA_GPGGA_counter_old = 0;
send_followme_counter = 0;
 
 
while( (receiveNMEA) )
{
//-----------------------------------------
// Screen redraw
//-----------------------------------------
if( redraw )
{
lcd_cls();
 
lcdx_printf_center_P( 0, MNORMAL, 1,0, PSTR("FollowMe") ); // Titel: oben, mitte
 
lcd_line( (6*6-3), 0, (6*6-3), 11, 1); // Linie Vertikal links
lcd_line( (15*6+5), 0, (15*6+5), 11, 1); // Linie Vertikal rechts
lcd_line( 0, 12, 127, 12, 1); // Linie Horizontal
 
//lcd_line( 0, 39, 127, 39, 1); // Linie Horizontal Mitte
lcd_line( 66, 39, 127, 39, 1); // Linie Horizontal Mitte
 
lcd_rect_round( 0, 33, 66, 12, 1, R1); // Rahmen fuer "Di" (Distance)
 
lcdx_printf_at_P( 3, 2, MNORMAL, 3,-1, PSTR("Al:") ); // Label: "Al:"
 
draw_icon_mk( 1, 18);
draw_icon_target_round( 1, 50);
 
redraw = false;
}
 
 
 
//-----------------------------------------
// neue MK Daten vorhanden
//-----------------------------------------
if( rxd_buffer_locked ) // neue MK Daten
{
Decode64 ();
naviData = (NaviData_t *) pRxData;
 
if( mktimeout ) redraw = true;
mktimeout = false;
 
FM_error = 0; // noch benoetigt?
 
currpos.Latitude = naviData->CurrentPosition.Latitude;
currpos.Longitude = naviData->CurrentPosition.Longitude;
 
//----------------------------------
// speichere letzte GPS-Positionen
//----------------------------------
Config.LastLatitude = naviData->CurrentPosition.Latitude; // speichere letzte Position in Config
Config.LastLongitude = naviData->CurrentPosition.Longitude; // speichere letzte Position in Config
 
 
//----------------------------------
// LiPo Cell Check
//----------------------------------
MKLiPoCells_Check(); // ggf. Zellenzahl ermitteln
 
 
//#################
//# MK
//#################
 
//-----------------
// Oben: MK-Batt Level (Volt)
//-----------------
OSD_Element_BattLevel2( 0, 0, 0,0 );
 
//-----------------
// Oben: Batt Level Bar
//-----------------
OSD_Element_Battery_Bar( 0, 9, 30, 1, ORIENTATION_H);
 
//-----------------
// Oben: MK-Flugzeit
//-----------------
writex_time(16, 0, naviData->FlyingTime, MNORMAL, 2,0);
 
//-----------------
// Hoehe
//-----------------
xoffs = 3;
yoffs = -1;
writex_altimeter( 7, 2, naviData->Altimeter, MNORMAL, xoffs,yoffs );
 
//-----------------
// MK: Sat Anzahl
//-----------------
yoffs = -27;
if( naviData->SatsInUse > 5 ) drawmode = MNORMALX;
else drawmode = MINVERSX;
writex_ndigit_number_u( 17, 5, naviData->SatsInUse, 2, 0,drawmode, 3,2+yoffs);
draw_icon_satmini( 116+3, 42+yoffs);
 
 
//-----------------
// MK: GPS
//-----------------
writex_gpspos( 3, 4, currpos.Latitude , MNORMAL,-3,-8 ); // Line 4 L: Latitude
writex_gpspos(12, 4, currpos.Longitude, MNORMAL, 1,-8 ); // Line 4 R: Longitude
// lcdx_printf_at_P( 1, 4, MNORMAL, -3,-8 , PSTR("%d"), NMEA.Latitude);
// lcdx_printf_at_P( 10, 4, MNORMAL, -1,-8 , PSTR("%d"), NMEA.Longitude);
 
 
 
//#################
//# DISTANCE TO TARGET
//#################
 
//-----------------
// Target: Distance to Target
//-----------------
xoffs = 7;
yoffs = 4;
//GPS_PosDev_t gps_Deviation( GPS_Pos_t pos1, GPS_Pos_t pos2 )
targetdev = gps_Deviation( FollowMe.Position, naviData->CurrentPosition);
lcdx_printf_at_P( 0, 4, MNORMAL, xoffs,yoffs , PSTR("Di: %3d m"), (targetdev.Distance / 10) );
 
 
//#################
//# TARGET (GPS Maus)
//#################
 
yoffs = 8;
 
//-----------------
// Send Counter
//-----------------
//lcdx_printf_at_P(4, 5, MNORMAL, 0,5, PSTR("S: %ld"), send_followme_counter ); // Anzahl gesendeter Target-Positionen
lcdx_printf_at_P( 4, 5, MNORMAL, -3,yoffs, PSTR("Tx:%5ld"), send_followme_counter ); // Anzahl gesendeter Target-Positionen
 
 
//-----------------
// Target: Fix
//-----------------
if( NMEA.SatFix == 1 || NMEA.SatFix == 2 )
drawmode = MNORMALX;
else
drawmode = MINVERSX;
 
lcdx_printf_at_P( 14, 5, drawmode, 1,yoffs, PSTR("F:%1d"), NMEA.SatFix ); // GPS-Maus: Satfix
 
 
//-----------------
// Target: Sat Anzahl
//-----------------
if( NMEA.SatsInUse > 5 )
drawmode = MNORMALX;
else
drawmode = MINVERSX;
 
writex_ndigit_number_u( 17, 5, NMEA.SatsInUse, 2, 0,drawmode, 4,yoffs);
draw_icon_satmini( 116+4, 40+yoffs);
 
 
//-----------------
// Target: Lat / Long
//-----------------
writex_gpspos( 3, 7, NMEA.Latitude , MNORMAL,-3,1 ); // GPS-Maus: Latitude
writex_gpspos(12, 7, NMEA.Longitude, MNORMAL, 1,1 ); // GPS-Maus: Longitude
 
 
rxd_buffer_locked = FALSE;
 
timer_mk_timeout = MK_TIMEOUT;
}
 
//-----------------------------------------
// if( !NMEA_receiveBT() )
// {
// receiveNMEA = false;
// }
// else
// {
// NMEA_GetNewData();
// }
 
 
 
// Sourcecode aus NaviCtrl/V2.10e/uart1.c
// FOLLOW_ME
// else if(CheckDelay(UART1_FollowMe_Timer) && (UART1_tx_buffer.Locked == FALSE))
// {
// if((GPSData.Status != INVALID) && (GPSData.SatFix == SATFIX_3D) && (GPSData.Flags & FLAG_GPSFIXOK) && (GPSData.NumOfSats >= 4))
// {
// TransmitAlsoToFC = 1;
// // update FollowMe content
// FollowMe.Position.Longitude = GPSData.Position.Longitude;
// FollowMe.Position.Latitude = GPSData.Position.Latitude;
// FollowMe.Position.Status = NEWDATA;
// FollowMe.Position.Altitude = 1;
// // 0 -> no Orientation
// // 1-360 -> CompassCourse Setpoint
// // -1 -> points to WP1 -> itself
// FollowMe.Heading = -1;
// FollowMe.ToleranceRadius = 1;
// FollowMe.HoldTime = 60;
// FollowMe.Event_Flag = 1;
// FollowMe.Index = 1; // 0 = Delete List, 1 place at first entry in the list
// FollowMe.Type = POINT_TYPE_WP;
// FollowMe.WP_EventChannelValue = 100; // set servo value
// FollowMe.AltitudeRate = 0; // do not change height
// FollowMe.Speed = 0; // rate to change the Position (0 = max)
// FollowMe.CamAngle = 255; // Camera servo angle in degree (255 -> POI-Automatic)
// FollowMe.Name[0] = 'F'; // Name of that point (ASCII)
// FollowMe.Name[1] = 'O'; // Name of that point (ASCII)
// FollowMe.Name[2] = 'L'; // Name of that point (ASCII)
// FollowMe.Name[3] = 'L'; // Name of that point (ASCII)
// FollowMe.reserve[0] = 0; // reserve
// FollowMe.reserve[1] = 0; // reserve
// MKProtocol_CreateSerialFrame(&UART1_tx_buffer, 's', NC_ADDRESS, 1, (u8 *)&FollowMe, sizeof(FollowMe));
// }
// UART1_FollowMe_Timer = SetDelay(FOLLOW_ME_INTERVAL); // set new update time
// }
//
 
 
 
 
 
//-----------------------------------------
// neue NMEA Daten?
//-----------------------------------------
if(NMEA_isdataready() && receiveNMEA)
{
if( NMEA.Counter > NMEA_GPGGA_counter_old )
{
if( (NMEA.SatsInUse > 5) && (NMEA.SatFix == 1 || NMEA.SatFix == 2) )
{
//Config.FM_Refresh
 
FollowMe.Position.Status = NEWDATA;
FollowMe.Position.Longitude = NMEA.Longitude;
FollowMe.Position.Latitude = NMEA.Latitude;
FollowMe.Position.Altitude = 1; // 20.7.2015 CB
// FollowMe.Position.Altitude = NMEA.Altitude; // ist das wirklich ok? NEIN C.B.
 
FollowMe.Heading = -1; // invalid heading
FollowMe.ToleranceRadius = Config.FM_Radius; // 5 meter default
FollowMe.HoldTime = 60; // ????? go home after 60s without any update ??????
// FollowMe.Event_Flag = 0; // no event
FollowMe.Event_Flag = 1; // 20.7.2015 CB
FollowMe.Index = 1; // 2st wp, 0 = Delete List, 1 place at first entry in the list
FollowMe.Type = POINT_TYPE_WP; // Typ des Wegpunktes
FollowMe.Name[0] = 'F'; // Name des Wegpunktes (ASCII)
FollowMe.Name[1] = 'O';
FollowMe.Name[2] = 'L';
FollowMe.Name[3] = 'L';
// FollowMe.WP_EventChannelValue = 0; // Will be transferred to the FC and can be used as Poti value there
FollowMe.WP_EventChannelValue = 100; // set servo value 20.7.2015
FollowMe.AltitudeRate = 0; // rate to change the Aetpoint
FollowMe.Speed = Config.FM_Speed; // rate to change the Position
FollowMe.CamAngle = 255; // Camera servo angle in degree (255 -> POI-Automatic)
FollowMe.reserve[0] = 0; // reserve
FollowMe.reserve[1] = 0; // reserve
 
SendOutData( 's', ADDRESS_NC, 1, &FollowMe, sizeof(FollowMe) ); //'s' = target Position 'w' = Waypoint
send_followme_counter++;
 
//void SendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...) // uint8_t *pdata, uint8_t len, ...
// SendOutData ('d', ADDRESS_ANY, 1, &tmp_dat, 1);
//SendOutData( 's', NC_ADDRESS, 1, (uint8_t *)&FollowMe, sizeof(FollowMe)); //'s' = target Position 'w' = Waypoint
 
}
 
NMEA_GPGGA_counter_old = NMEA.Counter;
}
}
 
//-----------------------------------------
// TASTEN
//-----------------------------------------
if( get_key_press(1 << KEY_ESC) )
{
break;
}
 
if( get_key_press(1 << KEY_ENTER) )
{
break;
}
 
 
//-----------------------------------------
//-----------------------------------------
if( !abo_timer )
{
// renew abo every 3 sec
// request OSD Data from NC every 100ms
// RS232_request_mk_data (1, 'o', 100);
tmp_dat = 10;
SendOutData ( 'o', ADDRESS_NC, 1, &tmp_dat, 1);
 
abo_timer = ABO_TIMEOUT;
}
 
 
 
//--------------------------
// Daten Timeout vom MK?
//--------------------------
if( timer_mk_timeout == 0 )
{
if( !mktimeout ) OSD_MK_ShowTimeout(); // nur anzeigen wenn noch nicht im mktimeout-Modus
set_beep ( 200, 0x0080, BeepNormal); // Beep
mktimeout = true;
timer_mk_timeout = MK_TIMEOUT;
//OSDScreenRefresh = OSD_SCREEN_REDRAW;
// OSD_MK_Connect( MK_CONNECT );
}
 
} // end: while( (receiveNMEA) );
 
 
 
//---------------------
// BEENDEN
//---------------------
OSD_active = false;
 
 
//---------------------
// GPS beenden
//---------------------
GPSMouse_Disconnect();
}
 
 
 
 
 
//
#ifdef USE_FOLLOWME_STEP2
void Debug_GPS (void)
{
uint8_t redraw;
 
set_beep( 25, 0xffff, BeepNormal ); // kurzer Bestaetigungs-Beep
redraw = true;
 
 
int retcode = GPSMouse_Connect(); // Abfrage der GPS-Daten zum testen Quick an Dirty ;-)
if( retcode <= 0 )
{
return;
}
 
 
while( true )
{
 
//######## Quell Koordinaten ##############################
 
NMEApos.lat = NMEA.Latitude;
NMEApos.lon = NMEA.Longitude;
 
//#########################################################
 
 
//-----------------------------------------
// Screen redraw
//-----------------------------------------
if( redraw )
{
lcd_cls();
 
lcdx_printf_center_P( 0, MNORMAL, 1,0, PSTR("FollowMeStep2") ); // Titel: oben, mitte
lcdx_printf_center_P( 1, MNORMAL, 1,0, PSTR(" Source Lat/Lon") );
lcdx_printf_center_P( 3, MNORMAL, 1,0, PSTR(" Target Lat/Lon") );
 
redraw = false;
}
 
//#################
//# DISTANCE TO TARGET
//#################
 
//lcdx_printf_at_P( 0, 1, MNORMAL,0,0, PSTR("Distance: %3d Meter"), Config.FM_Distance );
 
//#################
//# TARGET Azimuth
//#################
//lcdx_printf_at_P( 0, 2, MNORMAL, 0,0, PSTR(" Azimuth: %3d Grad"), Config.FM_Azimuth);
 
 
writex_gpspos( 1, 2, NMEApos.lat , MNORMAL,0,0 ); // GPS-Maus: Latitude
writex_gpspos(10, 2, NMEApos.lon, MNORMAL, 0,0 ); // GPS-Maus: Longitude
 
followme_calculate_offset(&NMEApos, &NMEATarget, 10, 10);
 
writex_gpspos( 1, 4, (int32_t)NMEATarget.lat , MNORMAL, 0,0 ); // Ziel Latitude
writex_gpspos(10, 4, (int32_t)NMEATarget.lon , MNORMAL, 0,0 ); // Ziel Longitude
 
 
if( get_key_press(1 << KEY_ESC) )
{
GPSMouse_Disconnect();
break;
}
 
if( get_key_press(1 << KEY_ENTER) )
{
redraw = true;
// break;
}
}
}
 
 
 
 
 
#endif
 
#endif // #ifdef USE_FOLLOWME
 
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/followme/followme.h
0,0 → 1,14
/*
* FollowMe.h
*
* Created on: 18.05.2012
* Author: cebra
*/
 
#ifndef FOLLOWME_H_
#define FOLLOWME_H_
 
void FollowMe (void);
void Debug_GPS (void);
 
#endif /* FOLLOWME_H_ */
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/followme
Property changes:
Added: svn:ignore
+_old_source
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/gps/gps.c
0,0 → 1,274
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
//############################################################################
//# HISTORY gps.c
//#
//# 20.09.2015 Startet
//# - add Routine um einen Offset in Meter zu den aktuellen Koordinaten dazurechnen
//# followme_calculate_offset(...)
//#
//# 03.08.2015 cebra
//# - add: Routine um aus gegebenen Koordinaten mit Abstand und Winkel eine ZielKoordinate zu berechnen
//# int nmea_move_horz(
//# const nmeaPOS *start_pos, /**< Start position in radians */
//# nmeaPOS *end_pos, /**< Result position in radians */
//# double azimuth, /**< Azimuth (degree) [0, 359] */
//# double distance) /**< Distance (km) */
//#
//# 27.06.2014 OG - NEU
//# - chg: auf #include "../gps/mymath.h" angepasst
//#
//# 20.06.2014 OG - NEU
//############################################################################
 
 
#include "../cpu.h"
#include <string.h>
#include <util/delay.h>
#include <avr/interrupt.h>
#include <stdlib.h>
#include <math.h>
#include "../main.h"
 
#include "../mk-data-structs.h"
#include "../gps/mymath.h"
#include "gps.h"
 
 
/*
// definiert in: mk_data-stucts.h
typedef struct
{
u16 Distance; // distance to target in cm
s16 Bearing; // course to target in deg
} __attribute__((packed)) GPS_PosDev_t;
*/
 
/*
// definiert in: mk_data-stucts.h
typedef struct
{
s32 Longitude; // in 1E-7 deg
s32 Latitude; // in 1E-7 deg
s32 Altitude; // in mm
u8 Status; // validity of data
} __attribute__((packed)) GPS_Pos_t;
*/
 
 
//--------------------------------------------------------------
 
#define NMEA_PI (3.141592653589793) /**< PI value */
#define NMEA_PI180 (NMEA_PI / 180) /**< PI division by 180 */
#define NMEA_EARTHRADIUS_KM (6378) /**< Earth's mean radius in km */
#define R (6371)
#define NMEA_EARTHRADIUS_M (NMEA_EARTHRADIUS_KM * 1000) /**< Earth's mean radius in m */
#define NMEA_EARTH_SEMIMAJORAXIS_M (6378137.0) /**< Earth's semi-major axis in m according WGS84 */
#define NMEA_EARTH_SEMIMAJORAXIS_KM (NMEA_EARTHMAJORAXIS_KM / 1000) /**< Earth's semi-major axis in km according WGS 84 */
#define NMEA_EARTH_FLATTENING (1 / 298.257223563) /**< Earth's flattening according WGS 84 */
#define NMEA_DOP_FACTOR (5) /**< Factor for translating DOP to meters */
 
 
// Definitonen für FollowMeStep2
#define LONG_DIV 10000000
#define LAT_DIV LONG_DIV
#define FOLLOWME_M2DEG 111111
#define FOLLOWME_ROUND_100 100
 
 
# define NMEA_POSIX(x) x
 
 
 
/**
* \fn nmea_degree2radian
* \brief Convert degree to radian
*/
double nmea_degree2radian(double val)
{ return (val * NMEA_PI180); }
 
 
//------------------------------------------------------------------------------------------
nmeaPOS NMEApos;
nmeaPOS NMEATarget;
 
/**
* \brief Horizontal move of point position
*/
int nmea_move_horz(
const nmeaPOS *start_pos, /**< Start position in radians */
nmeaPOS *end_pos, /**< Result position in radians */
double azimuth, /**< Azimuth (degree) [0, 359] */
double distance /**< Distance (km) */
)
{
nmeaPOS p1 = *start_pos;
int RetVal = 1;
 
distance /= NMEA_EARTHRADIUS_KM; /* Angular distance covered on earth's surface */
azimuth = nmea_degree2radian(azimuth);
 
end_pos->lat = asin( sin(p1.lat) * cos(distance) + cos(p1.lat) * sin(distance) * cos(azimuth));
 
end_pos->lon = p1.lon + atan2( sin(azimuth) * sin(distance) * cos(p1.lat), cos(distance) - sin(p1.lat) * sin(end_pos->lat));
 
if(NMEA_POSIX(isnan)(end_pos->lat) || NMEA_POSIX(isnan)(end_pos->lon))
{
end_pos->lat = 0; end_pos->lon = 0;
RetVal = 0;
}
 
return RetVal;
}
 
 
// Berechnet die Position der Kopters für FollowMeStep2
// Momentan wird die gleich Position ausgegeben
// Benutzt die c_cos_8192 der FC
// TODO: move to followme.c
 
uint8_t followme_calculate_offset(
const nmeaPOS *pPktPos, /**< Start position in radians */
nmeaPOS *target_pos, /**< Result position in radians */
int d_lat, /**< Distance lat(m) */
int d_long /**< Distance long(m) */
)
{
nmeaPOS pktPos = *pPktPos;
target_pos->lat = pktPos.lat + ( d_lat * ( LAT_DIV / FOLLOWME_M2DEG ) );
target_pos->lon = pktPos.lon + ( d_long * ( LONG_DIV / FOLLOWME_M2DEG ) * 8192 ) / abs ( c_cos_8192( (int16_t)(pktPos.lat / LONG_DIV ) ) );
 
return 1;
}
 
 
//###############################################################################################
 
 
 
//--------------------------------------------------------------
GPS_PosDev_t gps_Deviation( GPS_Pos_t pos1, GPS_Pos_t pos2 )
{
int32_t lat1, lon1, lat2, lon2;
int32_t d1, dlat;
GPS_PosDev_t PosDev;
 
lon1 = pos1.Longitude;
lat1 = pos1.Latitude;
 
lon2 = pos2.Longitude;
lat2 = pos2.Latitude;
 
d1 = (1359 * (int32_t)(c_cos_8192((lat1 + lat2) / 20000000)) * ((lon1 - lon2)/10))/ 10000000;
dlat = (1113 * (lat1 - lat2) / 10000);
 
PosDev.Bearing = (my_atan2(d1, dlat) + 540) % 360; // 360 +180 besserer Vergleich mit MkCockpit
PosDev.Distance = sqrt32( d1 * d1 + dlat * dlat ); //
//PosDev.Distance = sqrt32( d1 * d1 + dlat * dlat ) * 10; // *10 um von dm auf cm zu kommen
 
return PosDev;
}
 
 
///**
// * \brief Calculate distance between two points
// * \return Distance in meters
// */
//int32_t nmea_distance(
// const nmeaPOS *from_pos, /**< From position in radians */
// const nmeaPOS *to_pos /**< To position in radians */
// )
//{
// int32_t dist = ((int32_t)NMEA_EARTHRADIUS_M) * acos(
// sin(to_pos->lat) * sin(from_pos->lat) +
// cos(to_pos->lat) * cos(from_pos->lat) * cos(to_pos->lon - from_pos->lon)
// );
// return dist;
//}
 
 
 
//// Berechnung von Distanz und Winkel aus GPS-Daten home(MK eingeschaltet)
//// zur aktuellen Position(nach Motorstart)
//geo_t calc_geo(HomePos_t *home, GPS_Pos_t *pos)
//{ double lat1, lon1, lat2, lon2, d1, dlat;
// geo_t geo;
//
// lon1 = MK_pos.Home_Lon;
// lat1 = MK_pos.Home_Lat;
// lon2 = (double)pos->Longitude / 10000000.0;
// lat2 = (double)pos->Latitude / 10000000.0;
//
// // Formel verwendet von http://www.kompf.de/gps/distcalc.html
// // 111.3 km = Abstand zweier Breitenkreise und/oder zweier Längenkreise am Äquator
// // es wird jedoch in Meter weiter gerechnet
// d1 = 111300 * (double)cos((double)(lat1 + lat2) / 2 * DEG_TO_RAD) * (lon1 - lon2);
// dlat = 111300 * (double)(lat1 - lat2);
// // returns a value in metres http://www.kompf.de/gps/distcalc.html
// geo.bearing = fmod((RAD_TO_DEG * (double)atan2(d1, dlat)) + 180, 360); // +180 besserer Vergleich mit MkCockpit
// if (geo.bearing > 360) geo.bearing -= 360; // bekam schon Werte über 400
// geo.distance = sqrt(d1 * d1 + dlat * dlat);
// return(geo);
//}
 
// Berechnung von Distanz und Winkel aus GPS-Daten home(MK eingeschaltet)
// zur aktuellen Position(nach Motorstart)
//--------------------------------------------------------------
//--------------------------------------------------------------
 
/*
geo_t calc_geo( HomePos_t *home, GPS_Pos_t *pos )
{
int32_t lat1, lon1, lat2, lon2;
int32_t d1, dlat;
geo_t geo;
 
lon1 = home->Home_Lon;
lat1 = home->Home_Lat;
lon2 = pos->Longitude;
lat2 = pos->Latitude;
 
if( !CheckGPS )
{
writex_gpspos( 0, 3, home->Home_Lat , MNORMAL, 0,0); // Anzeige: Breitengrad (Latitude)
writex_gpspos( 11, 3, home->Home_Lon , MNORMAL, 0,0); // Anzeige: Laengengrad (Longitude)
writex_gpspos( 0, 4, pos->Latitude , MNORMAL, 0,0); // Anzeige: Breitengrad (Latitude)
writex_gpspos( 11, 4, pos->Longitude , MNORMAL, 0,0); // Anzeige: Laengengrad (Longitude)
 
//lcd_puts_at (0, 3, my_itoa(home->Home_Lat, 10, 7, 7), 0); // 30.05.2014 OG: my_itoa() gibt es nicht mehr
//lcd_puts_at (11, 3, my_itoa(home->Home_Lon, 10, 7, 7), 0); // 30.05.2014 OG: my_itoa() gibt es nicht mehr
//lcd_puts_at (0, 4, my_itoa(pos->Latitude, 10, 7, 7), 0); // 30.05.2014 OG: my_itoa() gibt es nicht mehr
//lcd_puts_at (11, 4, my_itoa(pos->Longitude, 10, 7, 7), 0); // 30.05.2014 OG: my_itoa() gibt es nicht mehr
}
 
// Formel verwendet von http://www.kompf.de/gps/distcalc.html
// 111.3 km = Abstand zweier Breitenkreise und/oder zweier Langenkreise am Äquator
// es wird jedoch in dm Meter weiter gerechnet
// (tlon1 - tlon2)/10) sonst uint32_t-Überlauf bei cos(0) gleich 1
d1 = (1359 * (int32_t)(c_cos_8192((lat1 + lat2) / 20000000)) * ((lon1 - lon2)/10))/ 10000000;
dlat = 1113 * (lat1 - lat2) / 10000;
geo.bearing = (my_atan2(d1, dlat) + 540) % 360; // 360 +180 besserer Vergleich mit MkCockpit
geo.distance = sqrt32(d1 * d1 + dlat * dlat);
if( !CheckGPS )
{
lcd_printp_at (0, 5, PSTR("Bear:"), 0);
 
lcdx_printf_at_P( 5, 5, MNORMAL, 0,0, PSTR("%3d"), geo.bearing );
//lcd_puts_at (5, 5, my_itoa((uint32_t)geo.bearing, 3, 0, 0), 0); // 30.05.2014 OG: my_itoa() gibt es nicht mehr
 
lcd_printp_at (8, 5, PSTR("\x1e"), 0);
lcd_printp_at (9, 5, PSTR("Dist:"), 0);
 
lcdx_printf_at_P( 15, 5, MNORMAL, 0,0, PSTR("%3d"), geo.distance );
//lcd_puts_at (15, 5, my_itoa((uint32_t)geo.distance, 3, 1, 1), 0); // 30.05.2014 OG: my_itoa() gibt es nicht mehr
 
lcd_printp_at (20, 5, PSTR("m"), 0);
}
 
 
return(geo);
}
*/
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/gps/gps.h
0,0 → 1,57
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
//############################################################################
//# HISTORY gps.h
//#
//# 20.06.2014 OG - NEU
//############################################################################
 
 
#ifndef GPS_H_
#define GPS_H_
 
 
 
GPS_PosDev_t gps_Deviation( GPS_Pos_t pos1, GPS_Pos_t pos2 );
 
/**
* Position data in fractional degrees or radians
*/
typedef struct _nmeaPOS
{
int32_t lat; /**< Latitude */
int32_t lon; /**< Longitude */
 
} nmeaPOS;
 
extern nmeaPOS NMEApos;
extern nmeaPOS NMEATarget;
 
 
int nmea_move_horz(
const nmeaPOS *start_pos, /**< Start position in radians */
nmeaPOS *end_pos, /**< Result position in radians */
double azimuth, /**< Azimuth (degree) [0, 359] */
double distance /**< Distance (km) */
);
 
 
int nmea_move_horz1(
const nmeaPOS *start_pos, /**< Start position in radians */
nmeaPOS *end_pos, /**< Result position in radians */
double azimuth, /**< Azimuth (degree) [0, 359] */
double distance /**< Distance (km) */
);
 
 
uint8_t followme_calculate_offset(
const nmeaPOS *pkt_pos, /**< Start position in radians */
nmeaPOS *target_pos, /**< Result position in radians */
int d_lat, /**< Distance lat(m) */
int d_lon /**< Distance long(m) */
);
 
 
 
#endif // #define GPS_H_
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/gps/gpsmouse.c
0,0 → 1,532
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
//############################################################################
//# HISTORY gpsmouse.c
//#
//# 30.07.2015 CB
//# - add: Anzeige von CRC Fehlern im NMEA Datensatz in GPSMouse_ShowData
//#
//# 28.07.2015 CB
//# - fix: Überprüfung von führenden 00 in der MAC-Adresse der BT Maus abgeschaltet
//#
//# 28.06.2014 OG
//# - fix: GPSMouse_ShowData() - wenn BT-Datenverlust dann immer GPSMouse_Disconnect()
//# auch wenn waitsatfix Modus aktiv ist
//# - fix: GPSMouse_ShowData() - Rueckgabe von 0 wenn Verbindung bereits vorhanden war
//# und dabei aber ein Verbindungsverlust zur BT GPS-Maus auftrat
//#
//# 27.06.2014 OG
//# - chg: GPSMouse_Disconnect() - Anzeige von BT-Datenverlust optimiert
//# - chg: GPSMouse_ShowData() - nach GPSMouse_Connect ein clear_key_all() eingefuegt
//#
//# 24.06.2014 OG
//# - add: GPSMouse_Connect(), GPSMouse_Disconnect()
//#
//# 23.06.2014 OG
//# - chg: GPSMouse_ShowData() - neue Parameter und Return-Codes fuer
//# hoehere Flexibilitaet
//#
//# 22.06.2014 OG - NEU
//# ehemals BT_ShowGPSData() in setup.c
//############################################################################
 
#include "../cpu.h"
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <string.h>
#include <util/delay.h>
 
#include "../main.h"
#include "../lcd/lcd.h"
#include "../setup/setup.h"
#include "../eeprom/eeprom.h"
#include "../lipo/lipo.h"
#include "../timer/timer.h"
#include "../bluetooth/fifo.h"
#include "../bluetooth/bluetooth.h"
#include "../uart/uart1.h"
#include "../utils/menuctrl.h"
#include "../utils/xutils.h"
#include "../pkt/pkt.h"
#include "../messages.h"
//#include "../gps/gps_nmea.h"
#include "../avr-nmea-gps-library/nmea.h"
#include "../gps/gpsmouse.h"
 
 
static const char STR_FIX0[] PROGMEM = " no";
static const char STR_FIX1[] PROGMEM = " GPS";
static const char STR_FIX2[] PROGMEM = "DGPS";
static const char STR_FIX6[] PROGMEM = "esti";
static const char STR_FIX[] PROGMEM = " ---";
 
 
 
 
 
//--------------------------------------------------------------
// retcode = GPSMouse_Connect()
//
// RUECKGABE:
// -2: kein BTM222 eingebaut
// -1: keine GPS Maus konfiguriert
// 0: Fehler bei connect, kein connect durchgeführt (evtl. GPS Maus nicht eingeschaltet)
// 1: verbunden
//--------------------------------------------------------------
int8_t GPSMouse_Connect( void )
{
uint8_t status;
 
if( !BT_CheckBTM222() )
{
// PKT_Message_P( text, error, timeout, beep, clearscreen)
PKT_Message_P( strGet(STR_NOBTM222), true, 1000, true, true); // 1000 = max. 10 Sekunden anzeigen; "kein BTM222 vorh."
return -2; // -2: kein BTM222 eingebaut
}
 
// deaktiviert, MAC Adressen von Handys haben keine 00 in der MAC-Adresse
// if( (Config.gps_UsedMac[5] == '0') || (Config.gps_UsedMac[6] == '0') )
// {
// PKT_Message_P( text, error, timeout, beep, clearscreen)
// PKT_Message_P( strGet(STR_NOGPSMOUSE), true, 1000, true, true); // 1000 = max. 10 Sekunden anzeigen; "keine GPS-Maus!"
// return -1; // -1: keine GPS Maus konfiguriert
// }
 
 
//--------------------
// verbinde BT GPS-Maus
//--------------------
PKT_Title( Config.gps_UsedDevName, true, true); // PKT_Title( text, lShowLipo, clearscreen )
 
lcdx_printp_center( 2, strGet(STR_GPSMOUSECONNECT), MNORMAL, 0,1); // "suche GPS-Maus"
 
PKT_Gauge_Begin( 0 ); // Gauge: 0 = Default fuer y verwenden
 
set_BTOn();
 
if( Config.BTIsSlave )
{
bt_downlink_init();
}
 
status = bt_connect( Config.gps_UsedMac );
 
uart1_flush();
fifo_clear(&in_fifo);
 
UART1_receiveNMEA = true; // Uartflag setzen zur Erkennung der NMEA Datensätze
 
PKT_Gauge_End(); // Gauge: Ende
 
if( !status ) // keine Verbindung zum BT-Device
{
set_BTOff();
 
// PKT_Message_P( text, error, timeout, beep, clearscreen)
PKT_Message_P( strGet(STR_GPSMOUSECONNECTION), true, 1000, true, true); // 1000 = max. 10 Sekunden anzeigen; "GPS-Maus Verbindung"
return 0; // 0: Fehler bei connect, kein connect durchgeführt (evtl. GPS Maus nicht eingeschaltet)
}
 
return 1; // 1 = ok, Verbindung steht
}
 
 
 
//--------------------------------------------------------------
// GPSMouse_Disconnect()
//--------------------------------------------------------------
void GPSMouse_Disconnect( void )
{
PKT_Title( Config.gps_UsedDevName, true, true); //PKT_Title( text, lShowLipo, clearscreen )
 
//---------------------
// GPS beenden
//---------------------
UART1_receiveNMEA = false;
if( !receiveNMEA ) // ggf. anders implementieren, z.B. via Parameter; aber erstmal geht's auch so
{
//lcdx_cls_row( y, mode, yoffs )
lcdx_cls_row( 7, MINVERSX, 0 );
lcdx_printp_center( 7, strGet(STR_BT_LOSTDATA), MINVERSX, 0,0); // "BT Datenverlust"
set_beep( 600, 0xffff, BeepNormal);
}
 
lcdx_printp_center( 2, strGet(STR_GPSMOUSEDISCONNECT), MNORMAL, 0,1); // "trenne GPS-Maus"
 
PKT_Gauge_Begin( 0 ); // Gauge: 0 = Default fuer y verwenden
 
receiveNMEA = false; // Uartflag zurücksetzen, es kommen keine NMEA Datensätze mehr
 
if (!bt_disconnect());
{
// lcdx_printp_center( 2, PSTR("Error on disconnect"), MNORMAL, 0,1); // Fehler beim Disconncet aufgetreten
// _delay_ms(2000); // 09.08.2015 cebra, muss noch untersucht werden, ist aber jetzt kein Problem
}
 
set_BTOff();
 
PKT_Gauge_End(); // Gauge: Ende
}
 
 
 
//--------------------------------------------------------------
// retcode = GPSMouse_ShowData( mode, waitsatfix )
//
// zeigt GPS-Daten der aktuellen BT-Maus an
//
// PARAMETER:
// show:
// was soll in der 2. Zeile angezeigt werden
// GPSMOUSE_SHOW_TIME || GPSMOUSE_SHOW_WAITSATFIX
//
// waitsatifix:
// 0 = Verbindungsaufbau; Daten anzeigen und beenden der
// BT-Verbindung (fuer setup.c)
// n = Zeit (via timer) die nach einem erfolgreichen Satfix gewartet wird bis
// GPSMouse_ShowData() beendet wird - die Verbindung zur GPS-Maus bleibt erhalten
// und kann weiterverwendet werden! (z.B. in followme.c)
//
// RUECKGABE:
// -2: kein BTM222 eingebaut
// -1: keine GPS Maus konfiguriert
// 0: Fehler bei connect, kein connect durchgeführt (evtl. GPS Maus nicht eingeschaltet)
// 1: connect zur GPS Maus ok, Benutzer hat Anzeige beenden
// 2: connect zur GPS Maus ok, Satix hat Anzeige beendet
//
// zusammengefasst:
// >0 : Ok
// <=0: Fehler
//--------------------------------------------------------------
int8_t GPSMouse_ShowData( uint8_t show, uint16_t waitsatfix )
{
uint8_t redraw = true;
uint8_t state_posfix = 0;
const char *pStr;
int8_t yoffs;
int8_t retcode;
 
 
 
//--------------------
// BT GPS-Maus verbinden
//--------------------
retcode = GPSMouse_Connect();
if( retcode <= 0 )
{
return retcode;
}
timer_nmea_timeout = NMEA_TIMEOUT; // Timeout Timer setzen
clear_key_all();
 
 
 
//---------------------
// zeige GPS-Daten
//---------------------
 
receiveNMEA = true;
 
 
do
{
//-------------------------
// Screen redraw
//-------------------------
if( redraw )
{
PKT_Title( Config.gps_UsedDevName, true, true); //PKT_Title( text, lShowLipo, clearscreen )
 
if( show == GPSMOUSE_SHOW_TIME ) // Zeile 2: GPS-Zeit
{
lcdx_printp_at( 6, 1, PSTR("["), MNORMAL, -1,2); // Mitte: GPS Time
lcdx_printp_at(15, 1, PSTR("]"), MNORMAL, -2,2); // ..
lcd_line( 0, 13, 34, 13, 1); // ..
lcd_line(92, 13, 127, 13, 1); // ..
}
 
if( show == GPSMOUSE_SHOW_WAITSATFIX ) // Zeile 2: "warte auf Satfix..."
{
yoffs = 1;
lcdx_cls_row( 1, MINVERS, yoffs);
lcdx_printp_center( 1, strGet(STR_WAITSATFIX), MINVERS, 0,yoffs); // "warte auf Satfix..."
}
 
// yoffs = 1;
// lcdx_cls_row( 1, MINVERS, yoffs);
// lcdx_printp_center( 1,strGet(STR_WAITNMEA), MINVERS, 0,yoffs); // "warte auf NMEA..."
 
lcdx_printp_at( 0, 2, PSTR("Fix:") , MNORMAL, 0,3); // Links; Fix
lcdx_printp_at( 0, 3, PSTR("Sat:") , MNORMAL, 0,3); // Links; Sat
lcdx_printp_at( 0, 4, PSTR("Alt:") , MNORMAL, 0,3); // Links; Alt
 
lcdx_printp_at(11, 2, PSTR("RCnt:"), MNORMAL, 0,3); // Rechts: RCnt - Zaehler empfangener GPGGA Datenpakete
lcdx_printp_at(11, 3, PSTR("CErr:"), MNORMAL, 0,3); // Rechts: RErr - Zaehler fehlerhafte NMEA Pakete
lcdx_printp_at(11, 4, PSTR("HDOP:"), MNORMAL, 0,3); // Rechts: HDOP
 
lcdx_cls_row( 5, MINVERS, 4); // Hintergrund invers
lcdx_printp_at( 1, 5, strGet(START_LASTPOS1), MINVERS, 0,4); // "Breitengr. Längengr."
 
lcd_rect( 0, (4*8)+11, 127, (2*8)+4, 1); // Rahmen
 
redraw = false;
}
 
 
//-------------------------
// PKT-LiPo anzeigen
//-------------------------
show_Lipo();
 
 
//-------------------------
// PKT-Update geht hier nicht...
// wegen der Hardware-Verbindung
//-------------------------
//if( PKT_CtrlHook() )
//{
// redraw = true;
//}
 
//-------------------------
//-------------------------
 
if(NMEA_isdataready()) // NMEA Daten vorhanden?
{
 
if( show == GPSMOUSE_SHOW_TIME )
{
lcdx_print_at(7, 1, (uint8_t *)NMEA.Time, MNORMAL, -2,2); // Mitte: GPS Time
}
 
//--------------
// Sat-Fix
//--------------
//writex_ndigit_number_u( 6, 2, NMEA.SatFix , 2,0, MNORMAL, 0,3); // Links: Fix (als Zahl)
switch( NMEA.SatFix )
{
case 0: pStr = STR_FIX0; break; // kein Sat-Fix!
case 1: pStr = STR_FIX1; break; // GPS - Fix: OK
case 2: pStr = STR_FIX2; break; // DGPS - Fix: OK
case 6: pStr = STR_FIX6; break; // Estimated - wird hier als nicht Ok angesehen weil nicht klar was es bedeutet
default: pStr = 0; // Sat-Fix Code unbekannt!
lcdx_printf_at_P( 4, 2, MNORMAL, 1,3, PSTR(" ? %d"), NMEA.SatFix); // -> Zahl wird angezeigt - ggf. recherchieren was da bedeutet (Fix ok oder nicht)
break;
}
 
if( pStr )
{
lcdx_printf_at_P( 4, 2, MNORMAL, 1,3, PSTR("%4S"), pStr); // GPS Fix als String ausgeben
}
 
if( NMEA.SatFix==1 || NMEA.SatFix==2 ) // Sat-Fix OK => einen Haken anzeigen
lcdx_putc( 8, 2, SYMBOL_CHECK, MNORMAL, 2,3 );
else
lcdx_putc( 8, 2, ' ', MNORMAL, 2,3 );
 
 
//--------------
// Sat-Anzahl
//--------------
writex_ndigit_number_u( 6, 3, NMEA.SatsInUse, 2,0, MNORMAL, 1,3); // Links: Sat-Anzahl
if( NMEA.SatsInUse >= GPSMOUSE_MINSAT ) // Haken angezeigt wenn MINSAT ok
lcdx_putc( 8, 3, SYMBOL_CHECK, MNORMAL, 2,3 );
else
lcdx_putc( 8, 3, ' ', MNORMAL, 2,3 );
 
 
//--------------
// Altitude
//--------------
lcdx_printf_at_P( 4, 4, MNORMAL, 1,3, PSTR("%4.1d"), NMEA.Altitude); // Links: Altitude
 
 
//--------------
// empfangene GPGGA Datenpakete
//--------------
lcdx_printf_at_P(16, 2, MNORMAL, 0,3, PSTR("%5ld"), NMEA.Counter ); // Rechts: Anzahl empfangener NMEA GPGGA-Pakete
 
 
//--------------
// NMEA CRC Fehler
//--------------
lcdx_printf_at_P(16, 3, MNORMAL, 0,3, PSTR("%5ld"), NMEA_getCRCerror() ); // Rechts: Anzahl CRC Fehler im NMEA GPGGA-Pakete
// lcdx_printf_at( 15, 3, mode, 0, 3, "%3.5ld", (uint32_t)NMEA_getBearing());
// writex_ndigit_number_u_10th(15, 3, NMEA_getBearing(), 4,0, MNORMAL, 0,3);
 
//--------------
// HDOP
//--------------
if( NMEA.HDOP == 0 ) // Rechts:: HDOP
lcdx_printp_at(16, 4, PSTR(" ---"), MNORMAL, 0,3);
else
writex_ndigit_number_u_10th(16, 4, NMEA.HDOP, 4,0, MNORMAL, 0,3);
 
 
//--------------
// Lat / Lon
//--------------
writex_gpspos( 1, 6, NMEA.Latitude , MNORMAL, 0,6 ); // unten links: Latitude
writex_gpspos(12, 6, NMEA.Longitude, MNORMAL, 0,6 ); // unten rechts: Longitude
 
 
//--------------
//--------------
if( waitsatfix > 0 )
{
if( (NMEA.SatFix==1 || NMEA.SatFix==2) && (state_posfix==0) )
{
state_posfix = 1;
timer = waitsatfix; // Verzoegerung bzgl. Exit (z.B. 600 = 6 Sekunden)
}
 
if( (NMEA.SatFix!=1 && NMEA.SatFix!=2) && (state_posfix==1) && (timer!=0) )
{
state_posfix = 0;
}
 
if( (NMEA.SatFix==1 || NMEA.SatFix==2) && (state_posfix==1) && (timer==0) )
{
clear_key_all();
return 2; // 2: connect zur GPS Maus ok, Satix hat Anzeige beendet
}
}
 
}
 
if (timer_nmea_timeout == 0) receiveNMEA = false;
 
} while( !get_key_press(1 << KEY_ESC) && receiveNMEA );
 
 
 
//---------------------
// GPS beenden
//---------------------
if( (waitsatfix == 0) || !receiveNMEA )
{
 
GPSMouse_Disconnect();
}
 
clear_key_all();
return (receiveNMEA ? 1 : 0); // 1: connect zur GPS Maus ok, Benutzer hat Anzeige beenden
}
 
 
// save, Anzeige der Daten im Format der neuen NMEA Routinen, nach Umbau auf NMEA Structur nicht mehr notwendig
// {
//
//
// if( show == GPSMOUSE_SHOW_TIME )
// {
//// lcdx_print_at(7, 1, (uint8_t *)NMEA.Time, MNORMAL, -2,2); // Mitte: GPS Time
//
// writex_ndigit_number_u( 7, 1, NMEA_getHour(), 2,0, MNORMAL, -2,2);
// lcdx_printp_at( 9, 1, PSTR(":") , MNORMAL, -2,2);
// writex_ndigit_number_u( 10, 1, NMEA_getMinute(), 2,0, MNORMAL, -2,2);
// lcdx_printp_at( 12, 1, PSTR(":") , MNORMAL, -2,2);
// writex_ndigit_number_u( 13, 1, NMEA_getSecond(), 2,0, MNORMAL, -2,2);
//
// }
//
// //--------------
// // Sat-Fix
// //--------------
// //writex_ndigit_number_u( 6, 2, NMEA.SatFix , 2,0, MNORMAL, 0,3); // Links: Fix (als Zahl)
// switch( NMEA_getGPSfix() )
// {
// case 0: pStr = STR_FIX0; break; // kein Sat-Fix!
// case 1: pStr = STR_FIX1; break; // GPS - Fix: OK
// case 2: pStr = STR_FIX2; break; // DGPS - Fix: OK
// case 6: pStr = STR_FIX6; break; // Estimated - wird hier als nicht Ok angesehen weil nicht klar was es bedeutet
// default: pStr = 0; // Sat-Fix Code unbekannt!
// lcdx_printf_at_P( 4, 2, MNORMAL, 1,3, PSTR(" ? %d"), NMEA_getGPSfix()); // -> Zahl wird angezeigt - ggf. recherchieren was da bedeutet (Fix ok oder nicht)
// break;
// }
//
// if( pStr )
// {
// lcdx_printf_at_P( 4, 2, MNORMAL, 1,3, PSTR("%4S"), pStr); // GPS Fix als String ausgeben
// }
//
// if( NMEA_getGPSfix()==1 || NMEA_getGPSfix()==2 ) // Sat-Fix OK => einen Haken anzeigen
// lcdx_putc( 8, 2, SYMBOL_CHECK, MNORMAL, 2,3 );
// else
// lcdx_putc( 8, 2, ' ', MNORMAL, 2,3 );
//
//
// //--------------
// // Sat-Anzahl
// //--------------
// writex_ndigit_number_u( 6, 3, NMEA_getSatellites(), 2,0, MNORMAL, 1,3); // Links: Sat-Anzahl
// if( NMEA_getSatellites() >= GPSMOUSE_MINSAT ) // Haken angezeigt wenn MINSAT ok
// lcdx_putc( 8, 3, SYMBOL_CHECK, MNORMAL, 2,3 );
// else
// lcdx_putc( 8, 3, ' ', MNORMAL, 2,3 );
//
//
// //--------------
// // Altitude
// //--------------
// lcdx_printf_at_P( 4, 4, MNORMAL, 1,3, PSTR("%4.1d"), NMEA_getAltitude()); // Links: Altitude
//
//
// //--------------
// // empfangene GPGGA Datenpakete
// //--------------
// lcdx_printf_at_P(16, 2, MNORMAL, 0,3, PSTR("%5ld"), NMEA_getNMEAcounter() ); // Rechts: Anzahl empfangener NMEA GPGGA-Pakete
//
//
// //--------------
// // NMEA CRC Fehler
// //--------------
// lcdx_printf_at_P(16, 3, MNORMAL, 0,3, PSTR("%5ld"), NMEA_getCRCerror() ); // Rechts: Anzahl empfangener NMEA GPGGA-Pakete
//
//// writex_ndigit_number_u(1, 5, UART1_GPGGA , 4,0, MNORMAL, 0,3);
//// writex_ndigit_number_u(5, 5, bt_overrun , 4,0, MNORMAL, 0,3);
//// writex_ndigit_number_u(10, 5, bt_bufferoverflow , 4,0, MNORMAL, 0,3);
//
//
// //--------------
// // HDOP
// //--------------
// if(NMEA_getHDOP() == 0 ) // Rechts:: HDOP
// lcdx_printp_at(16, 4, PSTR(" ---"), MNORMAL, 0,3);
// else
// writex_ndigit_number_u_10th(16, 4, NMEA_getHDOP(), 4,0, MNORMAL, 0,3);
//
//
// //--------------
// // Lat / Lon
// //--------------
// writex_gpspos( 1, 6, NMEA_getLatitude() , MNORMAL, 0,6 ); // unten links: Latitude
// writex_gpspos(12, 6, NMEA_getLongitude(), MNORMAL, 0,6 ); // unten rechts: Longitude
//
//
// //--------------
// //--------------
// if( waitsatfix > 0 )
// {
// if( (NMEA_getGPSfix()==1 || NMEA_getGPSfix()==2) && (state_posfix==0) )
// {
// state_posfix = 1;
// timer = waitsatfix; // Verzoegerung bzgl. Exit (z.B. 600 = 6 Sekunden)
// }
//
// if( (NMEA_getGPSfix()!=1 && NMEA_getGPSfix()!=2) && (state_posfix==1) && (timer!=0) )
// {
// state_posfix = 0;
// }
//
// if( (NMEA_getGPSfix()==1 || NMEA_getGPSfix()==2) && (state_posfix==1) && (timer==0) )
// {
// clear_key_all();
// return 2; // 2: connect zur GPS Maus ok, Satix hat Anzeige beendet
// }
// }
//
// }
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/gps/gpsmouse.h
0,0 → 1,46
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
//############################################################################
//# HISTORY gpsmouse.h
//#
//# 24.06.2014 OG
//# - chg: Parameteraenderung bei GPSMouse_ShowData()
//# - add: GPSMouse_Connect(), GPSMouse_Disconnect()
//#
//# 22.06.2014 OG
//# - add: GPSMouse_ShowData()
//# - add: #define GPSMOUSE_SHOWDATA, GPSMOUSE_WAITSATFIX
//#
//# 22.06.2014 OG - NEU
//############################################################################
 
 
#ifndef GPSMOUSE_H_
#define GPSMOUSE_H_
 
 
//----------------------------------
// GPSMouse_ShowData() - show
//----------------------------------
#define GPSMOUSE_SHOW_TIME 1
#define GPSMOUSE_SHOW_WAITSATFIX 2
 
 
//----------------------------------
// minimal akzeptierte Sat-Zahl fuer
// Steuerungsfunktionen des MK
//----------------------------------
#define GPSMOUSE_MINSAT 6
 
 
//----------------------------------
// Export
//----------------------------------
int8_t GPSMouse_Connect( void );
void GPSMouse_Disconnect( void );
int8_t GPSMouse_ShowData( uint8_t show, uint16_t waitsatfix );
 
 
 
#endif // #define GPSMOUSE_H_
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/gps/mymath.c
0,0 → 1,214
/****************************************************************/
/* */
/* NG-Video 5,8GHz */
/* */
/* Copyright (C) 2011 - gebad */
/* */
/* This code is distributed under the GNU Public License */
/* which can be found at http://www.gnu.org/licenses/gpl.txt */
/* */
/****************************************************************/
 
//############################################################################
//# HISTORY mymath.c
//#
//# 24.04.2013 OG
//# - chg: 'uint16_t atantab[T] PROGMEM' nach 'const uint16_t atantab[T] PROGMEM'
//# wegen Compile-Error in AtmelStudio 6
//############################################################################
 
 
#include <stdio.h>
#include <stdlib.h>
#include <math.h>
#include <avr/pgmspace.h>
 
#include "mymath.h"
 
// http://www.mikrocontroller.net/articles/AVR_Arithmetik#avr-gcc_Implementierung_.2832_Bit.29
unsigned int sqrt32(uint32_t q)
{ uint16_t r, mask;
uint16_t i = 8*sizeof (r) -1;
r = mask = 1 << i;
for (; i > 0; i--) {
mask >>= 1;
if (q < (uint32_t) r*r)
r -= mask;
else
r += mask;
}
if (q < (uint32_t) r*r)
r -= 1;
return r;
}
 
// aus Orginal MK source code
// sinus with argument in degree at an angular resolution of 1 degree and a discretisation of 13 bit.
const uint16_t sinlookup[91] = {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};
 
//double c_cos_8192(int16_t angle)
int16_t c_cos_8192(int16_t angle)
{
int8_t m,n;
int16_t sinus;
 
angle = 90 - angle;
// avoid negative angles
if (angle < 0)
{
m = -1;
angle = -angle;
}
else m = +1;
 
// fold angle to interval 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 = sinlookup[angle];
// calculate sinus value
return (sinus * m * n);
}
 
// ----------------------------------------------------------------------------------------------
 
 
const int16_t arccos64[65] = {90,89,88,87,86, 85, 84, 83, 83, 82, 81, 80, 79, 78, 77, 76,
75, 74, 73, 72, 71, 71, 70, 69, 68, 67, 66, 65, 64, 63, 62,
61, 60, 59, 58, 57, 56, 55, 54, 53, 51, 50, 49, 48, 47, 45,
44, 43, 41, 40, 39, 37, 36, 34, 32, 31, 29, 27, 25, 23, 20,
18, 14, 10, 0};
 
 
 
int16_t c_arccos2(int32_t a, int32_t b)
{
if(a>b) return(0);
return(arccos64[64 * a / b]);
}
 
 
/* ----------------------------------------------------------------------------------------------
 
atan2.S
 
Author: Reiner Patommel
atan2.S uses CORDIC, an algorithm which was developed in 1956 by Jack Volder.
CORDIC can be used to calculate trigonometric, hyperbolic and linear
functions and is until today implemented in most pocket calculators.
The algorithm makes only use of simple integer arithmetic.
 
The CORDIC equations in vectoring mode for trigonometric functions are:
Xi+1 = Xi - Si * (Yi * 1 / 2^i)
Yi+1 = Yi + Si * (Xi * 1 / 2^i)
Zi+1 = Zi - Si * atan(1 / 2^i)
where Si = +1 if Yi < 0 else Si = -1
The rotation angles are limited to -PI/2 and PI/2 i.e.
-90 degrees ... +90 degrees
 
For the calculation of atan2(x,y) we need a small pre-calculated table of
angles or radians with the values Tn = atan(1/2^i).
We rotate the vector(Xo,Yo) in steps to the x-axis i.e. we drive Y to 0 and
accumulate the rotated angles or radians in Z. The direction of the rotation
will be positive or negative depending on the sign of Y after the previous
rotation and the rotation angle will decrease from step to step. (The first
step is 45 degrees, the last step is 0.002036 degrees for n = 15).
 
After n rotations the variables will have the following values:
Yn = ideally 0
Xn = c*sqrt(Xo^2+Yo^2) (magnitude of the vector)
Zn = Zo+atan(Yo/Xo) (accumulated rotation angles or radians)
 
c, the cordic gain, is the product Pn of sqrt(1+2^(-2i)) and amounts to
approx. 1.64676 for n = 15.
 
In order to represent X, Y and Z as integers we introduce a scaling factor Q
which is chosen as follows:
1. We normalize Xo and Yo (starting values) to be less than or equal to 1*Q and
set Zo = 0 i.e. Xomax = 1*Q, Yomax = 1*Q, Zo = 0.
2. With Xo = 1*Q and Yo = 1*Q, Xn will be Xnmax = Q*c*sqrt(2) = 2.329*Q
3. In order to boost accuracy we only cover the rotation angles between 0 and PI/2
i.e. X and Z are always > 0 and therefore can be unsigned.
(We do the quadrant correction afterwards based on the initial signs of x and y)
4. If X is an unsigned int, Xnmax = 65536, and Q = 65536/2.329 = 28140.
i.e.
Xnmax = 65536 --> unsigned int
Ynmax = +/- 28140 --> signed int
Znmax = PI/2 * 28140 = 44202 --> unsigned int
The systematic error is 90/44202 = 0.002036 degrees or 0.0000355 rad.
Below is atan2 and atan in C: */
 
#define getAtanVal(x) (uint16_t)pgm_read_word(&atantab[x])
 
const uint16_t atantab[T] PROGMEM = {22101,13047,6894,3499,1756,879,440,220,110,55,27,14,7,3,2,1};
 
int16_t my_atan2(int32_t y, int32_t x)
{ unsigned char i;
uint32_t xQ;
int32_t yQ;
uint32_t angle = 0;
uint32_t tmp;
double x1, y1;
 
x1 = abs(x);
y1 = abs(y);
 
if (y1 == 0) {
if (x < 0)
return (180);
else
return 0;
}
if (x1 < y1) {
x1 /= y1;
y1 = 1;
}
else {
y1 /= x1;
x1 = 1;
}
xQ = SCALED(x1);
yQ = SCALED(y1);
 
for (i = 0; i < T-1; i++) {
tmp = xQ >> i;
if (yQ < 0) {
xQ -= yQ >> i;
yQ += tmp;
angle -= getAtanVal(i);
}
else {
xQ += yQ >> i;
yQ -= tmp;
angle += getAtanVal(i);
}
}
 
angle = RAD_TO_DEG * angle/Q;
if (x <= 0)
angle = 180 - angle;
if (y <= 0)
return(-angle);
return(angle);
}
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/gps/mymath.h
0,0 → 1,15
#ifndef _MYMATH_H_
#define _MYMATH_H_
 
#include <avr/io.h>
 
#define T 16
#define Q 28140
#define SCALED(X) ((int32_t)((X) * Q))
#define RAD_TO_DEG 57.2957795 // radians to degrees = 180 / PI
 
uint16_t sqrt32(uint32_t qzahl);
int16_t c_cos_8192(int16_t angle);
int16_t my_atan2(int32_t y, int32_t x);
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/gps
Property changes:
Added: svn:ignore
+_doc
+
+Copy of gpsmouse.h
+
+_old_source
+
+Copy of gpsmouse.c
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/lcd/Font8x8.c
0,0 → 1,273
/*
* font8x8.c
* LCD-OSD
*
* Created by Peter Mack on 26.12.09.
* Copyright 2009 SCS GmbH & Co. KG. All rights reserved.
*
*/
 
#include <avr/pgmspace.h>
 
const uint8_t Font8x8[256][8]PROGMEM=
{
 
{0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // 0x00
{0x7E,0x81,0x95,0xB1,0xB1,0x95,0x81,0x7E}, // 0x01
{0x7E,0xFF,0xEB,0xCF,0xCF,0xEB,0xFF,0x7E}, // 0x02
{0x0E,0x1F,0x3F,0x7E,0x3F,0x1F,0x0E,0x00}, // 0x03
{0x08,0x1C,0x3E,0x7F,0x3E,0x1C,0x08,0x00}, // 0x04
{0x38,0x3A,0x9F,0xFF,0x9F,0x3A,0x38,0x00}, // 0x05
{0x10,0x38,0xBC,0xFF,0xBC,0x38,0x10,0x00}, // 0x06
{0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // 0x07
{0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // 0x08
{0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // 0x09
{0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // 0x0A
{0x70,0xF8,0x88,0x88,0xFD,0x7F,0x07,0x0F}, // 0x0B
{0x00,0x4E,0x5F,0xF1,0xF1,0x5F,0x4E,0x00}, // 0x0C
{0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // 0x0D
{0xC0,0xFF,0x7F,0x05,0x05,0x65,0x7F,0x3F}, // 0x0E
{0x99,0x5A,0x3C,0xE7,0xE7,0x3C,0x5A,0x99}, // 0x0F
{0x7F,0x3E,0x3E,0x1C,0x1C,0x08,0x08,0x00}, // 0x10
{0x08,0x08,0x1C,0x1C,0x3E,0x3E,0x7F,0x00}, // 0x11
{0x00,0x24,0x66,0xFF,0xFF,0x66,0x24,0x00}, // 0x12
{0x00,0x5F,0x5F,0x00,0x00,0x5F,0x5F,0x00}, // 0x13
{0x06,0x0F,0x09,0x7F,0x7F,0x01,0x7F,0x7F}, // 0x14
{0xDA,0xBF,0xA5,0xA5,0xFD,0x59,0x03,0x02}, // 0x15
{0x00,0x70,0x70,0x70,0x70,0x70,0x70,0x00}, // 0x16
{0x80,0x94,0xB6,0xFF,0xFF,0xB6,0x94,0x80}, // 0x17
{0x00,0x04,0x06,0x7F,0x7F,0x06,0x04,0x00}, // 0x18
{0x00,0x10,0x30,0x7F,0x7F,0x30,0x10,0x00}, // 0x19
{0x08,0x08,0x08,0x2A,0x3E,0x1C,0x08,0x00}, // 0x1A
{0x08,0x1C,0x3E,0x2A,0x08,0x08,0x08,0x00}, // 0x1B
{0x3C,0x3C,0x20,0x20,0x20,0x20,0x20,0x00}, // 0x1C
{0x08,0x1C,0x3E,0x08,0x08,0x3E,0x1C,0x08}, // 0x1D
{0x30,0x38,0x3C,0x3E,0x3E,0x3C,0x38,0x30}, // 0x1E
{0x06,0x0E,0x1E,0x3E,0x3E,0x1E,0x0E,0x06}, // 0x1F
 
{0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, // 0x20
{0x00,0x06,0x5F,0x5F,0x06,0x00,0x00,0x00}, // 0x21
{0x00,0x07,0x07,0x00,0x07,0x07,0x00,0x00}, // 0x22
{0x14,0x7F,0x7F,0x14,0x7F,0x7F,0x14,0x00}, // 0x23
{0x24,0x2E,0x6B,0x6B,0x3A,0x12,0x00,0x00}, // 0x24
{0x46,0x66,0x30,0x18,0x0C,0x66,0x62,0x00}, // 0x25
{0x30,0x7A,0x4F,0x5D,0x37,0x7A,0x48,0x00}, // 0x26
{0x04,0x07,0x03,0x00,0x00,0x00,0x00,0x00}, // 0x27
{0x00,0x1C,0x3E,0x63,0x41,0x00,0x00,0x00}, // 0x28
{0x00,0x41,0x63,0x3E,0x1C,0x00,0x00,0x00}, // 0x29
{0x08,0x2A,0x3E,0x1C,0x1C,0x3E,0x2A,0x08}, // 0x2A
{0x08,0x08,0x3E,0x3E,0x08,0x08,0x00,0x00}, // 0x2B
{0x00,0xA0,0xE0,0x60,0x00,0x00,0x00,0x00}, // 0x2C
{0x08,0x08,0x08,0x08,0x08,0x08,0x00,0x00}, // 0x2D
{0x00,0x00,0x60,0x60,0x00,0x00,0x00,0x00}, // 0x2E
{0x60,0x30,0x18,0x0C,0x06,0x03,0x01,0x00}, // 0x2F
{0x3E,0x7F,0x59,0x4D,0x7F,0x3E,0x00,0x00}, // 0x30
{0x42,0x42,0x7F,0x7F,0x40,0x40,0x00,0x00}, // 0x31
{0x62,0x73,0x59,0x49,0x6F,0x66,0x00,0x00}, // 0x32
{0x22,0x63,0x49,0x49,0x7F,0x36,0x00,0x00}, // 0x33
{0x18,0x1C,0x16,0x13,0x7F,0x7F,0x10,0x00}, // 0x34
{0x27,0x67,0x45,0x45,0x7D,0x39,0x00,0x00}, // 0x35
{0x3C,0x7E,0x4B,0x49,0x79,0x30,0x00,0x00}, // 0x36
{0x03,0x63,0x71,0x19,0x0F,0x07,0x00,0x00}, // 0x37
{0x36,0x7F,0x49,0x49,0x7F,0x36,0x00,0x00}, // 0x38
{0x06,0x4F,0x49,0x69,0x3F,0x1E,0x00,0x00}, // 0x39
{0x00,0x00,0x6C,0x6C,0x00,0x00,0x00,0x00}, // 0x3A
{0x00,0xA0,0xEC,0x6C,0x00,0x00,0x00,0x00}, // 0x3B
{0x08,0x1C,0x36,0x63,0x41,0x00,0x00,0x00}, // 0x3C
{0x14,0x14,0x14,0x14,0x14,0x14,0x00,0x00}, // 0x3D
{0x00,0x41,0x63,0x36,0x1C,0x08,0x00,0x00}, // 0x3E
{0x02,0x03,0x51,0x59,0x0F,0x06,0x00,0x00}, // 0x3F
{0x3E,0x7F,0x41,0x5D,0x5D,0x1F,0x1E,0x00}, // 0x40
{0x7C,0x7E,0x13,0x13,0x7E,0x7C,0x00,0x00}, // 0x41
{0x41,0x7F,0x7F,0x49,0x49,0x7F,0x36,0x00}, // 0x42
{0x1C,0x3E,0x63,0x41,0x41,0x63,0x22,0x00}, // 0x43
{0x41,0x7F,0x7F,0x41,0x63,0x7F,0x1C,0x00}, // 0x44
{0x41,0x7F,0x7F,0x49,0x5D,0x41,0x63,0x00}, // 0x45
{0x41,0x7F,0x7F,0x49,0x1D,0x01,0x03,0x00}, // 0x46
{0x1C,0x3E,0x63,0x41,0x51,0x73,0x72,0x00}, // 0x47
{0x7F,0x7F,0x08,0x08,0x7F,0x7F,0x00,0x00}, // 0x48
{0x00,0x41,0x7F,0x7F,0x41,0x00,0x00,0x00}, // 0x49
{0x30,0x70,0x40,0x41,0x7F,0x3F,0x01,0x00}, // 0x4A
{0x41,0x7F,0x7F,0x08,0x1C,0x77,0x63,0x00}, // 0x4B
{0x41,0x7F,0x7F,0x41,0x40,0x60,0x70,0x00}, // 0x4C
{0x7F,0x7F,0x06,0x0C,0x06,0x7F,0x7F,0x00}, // 0x4D
{0x7F,0x7F,0x06,0x0C,0x18,0x7F,0x7F,0x00}, // 0x4E
{0x1C,0x3E,0x63,0x41,0x63,0x3E,0x1C,0x00}, // 0x4F
{0x41,0x7F,0x7F,0x49,0x09,0x0F,0x06,0x00}, // 0x50
{0x1E,0x3F,0x21,0x71,0x7F,0x5E,0x00,0x00}, // 0x51
{0x41,0x7F,0x7F,0x19,0x39,0x6F,0x46,0x00}, // 0x52
{0x26,0x67,0x4D,0x59,0x7B,0x32,0x00,0x00}, // 0x53
{0x03,0x41,0x7F,0x7F,0x41,0x03,0x00,0x00}, // 0x54
{0x7F,0x7F,0x40,0x40,0x7F,0x7F,0x00,0x00}, // 0x55
{0x1F,0x3F,0x60,0x60,0x3F,0x1F,0x00,0x00}, // 0x56
{0x7F,0x7F,0x30,0x18,0x30,0x7F,0x7F,0x00}, // 0x57
{0x63,0x77,0x1C,0x08,0x1C,0x77,0x63,0x00}, // 0x58
{0x07,0x4F,0x78,0x78,0x4F,0x07,0x00,0x00}, // 0x59
{0x67,0x73,0x59,0x4D,0x47,0x63,0x71,0x00}, // 0x5A
{0x00,0x7F,0x7F,0x41,0x41,0x00,0x00,0x00}, // 0x5B
{0x01,0x03,0x06,0x0C,0x18,0x30,0x60,0x00}, // 0x5C
{0x00,0x41,0x41,0x7F,0x7F,0x00,0x00,0x00}, // 0x5D
{0x08,0x0C,0x06,0x03,0x06,0x0C,0x08,0x00}, // 0x5E
{0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80}, // 0x5F
{0x00,0x00,0x03,0x07,0x04,0x00,0x00,0x00}, // 0x60
{0x20,0x74,0x54,0x54,0x3C,0x78,0x40,0x00}, // 0x61
{0x41,0x3F,0x7F,0x44,0x44,0x7C,0x38,0x00}, // 0x62
{0x38,0x7C,0x44,0x44,0x6C,0x28,0x00,0x00}, // 0x63
{0x30,0x78,0x48,0x49,0x3F,0x7F,0x40,0x00}, // 0x64
{0x38,0x7C,0x54,0x54,0x5C,0x18,0x00,0x00}, // 0x65
{0x48,0x7E,0x7F,0x49,0x03,0x02,0x00,0x00}, // 0x66
{0x98,0xBC,0xA4,0xA4,0xF8,0x7C,0x04,0x00}, // 0x67
{0x41,0x7F,0x7F,0x08,0x04,0x7C,0x78,0x00}, // 0x68
{0x00,0x44,0x7D,0x7D,0x40,0x00,0x00,0x00}, // 0x69
{0x40,0xC4,0x84,0xFD,0x7D,0x00,0x00,0x00}, // 0x6A
{0x41,0x7F,0x7F,0x10,0x38,0x6C,0x44,0x00}, // 0x6B
{0x00,0x41,0x7F,0x7F,0x40,0x00,0x00,0x00}, // 0x6C
{0x7C,0x7C,0x0C,0x18,0x0C,0x7C,0x78,0x00}, // 0x6D
{0x7C,0x7C,0x04,0x04,0x7C,0x78,0x00,0x00}, // 0x6E
{0x38,0x7C,0x44,0x44,0x7C,0x38,0x00,0x00}, // 0x6F
{0x84,0xFC,0xF8,0xA4,0x24,0x3C,0x18,0x00}, // 0x70
{0x18,0x3C,0x24,0xA4,0xF8,0xFC,0x84,0x00}, // 0x71
{0x44,0x7C,0x78,0x44,0x1C,0x18,0x00,0x00}, // 0x72
{0x48,0x5C,0x54,0x54,0x74,0x24,0x00,0x00}, // 0x73
{0x00,0x04,0x3E,0x7F,0x44,0x24,0x00,0x00}, // 0x74
{0x3C,0x7C,0x40,0x40,0x3C,0x7C,0x40,0x00}, // 0x75
{0x1C,0x3C,0x60,0x60,0x3C,0x1C,0x00,0x00}, // 0x76
{0x3C,0x7C,0x60,0x30,0x60,0x7C,0x3C,0x00}, // 0x77
{0x44,0x6C,0x38,0x10,0x38,0x6C,0x44,0x00}, // 0x78
{0x9C,0xBC,0xA0,0xA0,0xFC,0x7C,0x00,0x00}, // 0x79
{0x4C,0x64,0x74,0x5C,0x4C,0x64,0x00,0x00}, // 0x7A
{0x08,0x08,0x3E,0x77,0x41,0x41,0x00,0x00}, // 0x7B
{0x00,0x00,0x00,0x77,0x77,0x00,0x00,0x00}, // 0x7C
{0x41,0x41,0x77,0x3E,0x08,0x08,0x00,0x00}, // 0x7D
{0x02,0x03,0x01,0x03,0x02,0x03,0x01,0x00}, // 0x7E
{0x78,0x7C,0x46,0x43,0x46,0x7C,0x78,0x00}, // 0x7F
 
{0x1E,0xBF,0xE1,0x61,0x33,0x12,0x00,0x00}, // 0x80
{0x3A,0x7A,0x40,0x40,0x7A,0x7A,0x40,0x00}, // 0x81
{0x38,0x7C,0x56,0x57,0x5D,0x18,0x00,0x00}, // 0x82
{0x02,0x23,0x75,0x55,0x55,0x7D,0x7B,0x42}, // 0x83
{0x21,0x75,0x54,0x54,0x7D,0x79,0x40,0x00}, // 0x84
{0x20,0x75,0x57,0x56,0x7C,0x78,0x40,0x00}, // 0x85
{0x00,0x22,0x77,0x55,0x55,0x7F,0x7A,0x40}, // 0x86
{0x1C,0xBE,0xE2,0x62,0x36,0x14,0x00,0x00}, // 0x87
{0x02,0x3B,0x7D,0x55,0x55,0x5D,0x1B,0x02}, // 0x88
{0x39,0x7D,0x54,0x54,0x5D,0x19,0x00,0x00}, // 0x89
{0x38,0x7D,0x57,0x56,0x5C,0x18,0x00,0x00}, // 0x8A
{0x01,0x45,0x7C,0x7C,0x41,0x01,0x00,0x00}, // 0x8B
{0x02,0x03,0x45,0x7D,0x7D,0x43,0x02,0x00}, // 0x8C
{0x00,0x45,0x7F,0x7E,0x40,0x00,0x00,0x00}, // 0x8D
{0x79,0x7D,0x26,0x26,0x7D,0x79,0x00,0x00}, // 0x8E
{0x70,0x7A,0x2D,0x2D,0x7A,0x70,0x00,0x00}, // 0x8F
{0x44,0x7C,0x7E,0x57,0x55,0x44,0x00,0x00}, // 0x90
{0x20,0x74,0x54,0x54,0x7C,0x7C,0x54,0x54}, // 0x91
{0x7C,0x7E,0x0B,0x09,0x7F,0x7F,0x49,0x00}, // 0x92
{0x32,0x7B,0x49,0x49,0x7B,0x32,0x00,0x00}, // 0x93
{0x32,0x7A,0x48,0x48,0x7A,0x32,0x00,0x00}, // 0x94
{0x30,0x79,0x4B,0x4A,0x78,0x30,0x00,0x00}, // 0x95
{0x3A,0x7B,0x41,0x41,0x7B,0x7A,0x40,0x00}, // 0x96
{0x38,0x79,0x43,0x42,0x78,0x78,0x40,0x00}, // 0x97
{0xBA,0xBA,0xA0,0xA0,0xFA,0x7A,0x00,0x00}, // 0x98
{0x39,0x7D,0x44,0x44,0x44,0x7D,0x39,0x00}, // 0x99
{0x3D,0x7D,0x40,0x40,0x7D,0x3D,0x00,0x00}, // 0x9A
{0x38,0x7C,0x64,0x54,0x4C,0x7C,0x38,0x00}, // 0x9B
{0x68,0x7E,0x7F,0x49,0x43,0x66,0x20,0x00}, // 0x9C
{0x5C,0x3E,0x73,0x49,0x67,0x3E,0x1D,0x00}, // 0x9D
{0x44,0x6C,0x38,0x38,0x6C,0x44,0x00,0x00}, // 0x9E
{0x40,0xC8,0x88,0xFE,0x7F,0x09,0x0B,0x02}, // 0x9F
{0x20,0x74,0x56,0x57,0x7D,0x78,0x40,0x00}, // 0xA0
{0x00,0x44,0x7E,0x7F,0x41,0x00,0x00,0x00}, // 0xA1
{0x30,0x78,0x48,0x4A,0x7B,0x31,0x00,0x00}, // 0xA2
{0x38,0x78,0x40,0x42,0x7B,0x79,0x40,0x00}, // 0xA3
{0x7A,0x7B,0x09,0x0B,0x7A,0x73,0x01,0x00}, // 0xA4
{0x7A,0x7B,0x19,0x33,0x7A,0x7B,0x01,0x00}, // 0xA5
{0x00,0x26,0x2F,0x29,0x2F,0x2F,0x28,0x00}, // 0xA6
{0x00,0x26,0x2F,0x29,0x29,0x2F,0x26,0x00}, // 0xA7
{0x30,0x78,0x4D,0x45,0x60,0x20,0x00,0x00}, // 0xA8
{0x1C,0x22,0x7D,0x4B,0x5B,0x65,0x22,0x1C}, // 0xA9
{0x08,0x08,0x08,0x08,0x38,0x38,0x00,0x00}, // 0xAA
{0x61,0x3F,0x1F,0xCC,0xEE,0xAB,0xB9,0x90}, // 0xAB
{0x61,0x3F,0x1F,0x4C,0x66,0x73,0xD9,0xF8}, // 0xAC
{0x00,0x00,0x60,0xFA,0xFA,0x60,0x00,0x00}, // 0xAD
{0x08,0x1C,0x36,0x22,0x08,0x1C,0x36,0x22}, // 0xAE
{0x22,0x36,0x1C,0x08,0x22,0x36,0x1C,0x08}, // 0xAF
{0xAA,0x00,0x55,0x00,0xAA,0x00,0x55,0x00}, // 0xB0
{0xAA,0x55,0xAA,0x55,0xAA,0x55,0xAA,0x55}, // 0xB1
{0x55,0xFF,0xAA,0xFF,0x55,0xFF,0xAA,0xFF}, // 0xB2
{0x00,0x00,0x00,0xFF,0xFF,0x00,0x00,0x00}, // 0xB3
{0x10,0x10,0x10,0xFF,0xFF,0x00,0x00,0x00}, // 0xB4
{0x70,0x78,0x2C,0x2E,0x7B,0x71,0x00,0x00}, // 0xB5
{0x72,0x79,0x2D,0x2D,0x79,0x72,0x00,0x00}, // 0xB6
{0x71,0x7B,0x2E,0x2C,0x78,0x70,0x00,0x00}, // 0xB7
{0x1C,0x22,0x5D,0x55,0x55,0x41,0x22,0x1C}, // 0xB8
{0x14,0x14,0xF7,0xF7,0x00,0xFF,0xFF,0x00}, // 0xB9
{0x00,0x00,0xFF,0xFF,0x00,0xFF,0xFF,0x00}, // 0xBA
{0x14,0x14,0xF4,0xF4,0x04,0xFC,0xFC,0x00}, // 0xBB
{0x14,0x14,0x17,0x17,0x10,0x1F,0x1F,0x00}, // 0xBC
{0x18,0x3C,0x24,0xE7,0xE7,0x24,0x24,0x00}, // 0xBD
{0x2B,0x2F,0xFC,0xFC,0x2F,0x2B,0x00,0x00}, // 0xBE
{0x10,0x10,0x10,0xF0,0xF0,0x00,0x00,0x00}, // 0xBF
{0x00,0x00,0x00,0x1F,0x1F,0x10,0x10,0x10}, // 0xC0
{0x10,0x10,0x10,0x1F,0x1F,0x10,0x10,0x10}, // 0xC1
{0x10,0x10,0x10,0xF0,0xF0,0x10,0x10,0x10}, // 0xC2
{0x00,0x00,0x00,0xFF,0xFF,0x10,0x10,0x10}, // 0xC3
{0x10,0x10,0x10,0x10,0x10,0x10,0x10,0x10}, // 0xC4
{0x10,0x10,0x10,0xFF,0xFF,0x10,0x10,0x10}, // 0xC5
{0x22,0x77,0x55,0x57,0x7E,0x7B,0x41,0x00}, // 0xC6
{0x72,0x7B,0x2D,0x2F,0x7A,0x73,0x01,0x00}, // 0xC7
{0x00,0x00,0x1F,0x1F,0x10,0x17,0x17,0x14}, // 0xC8
{0x00,0x00,0xFC,0xFC,0x04,0xF4,0xF4,0x14}, // 0xC9
{0x14,0x14,0x17,0x17,0x10,0x17,0x17,0x14}, // 0xCA
{0x14,0x14,0xF4,0xF4,0x04,0xF4,0xF4,0x14}, // 0xCB
{0x00,0x00,0xFF,0xFF,0x00,0xF7,0xF7,0x14}, // 0xCC
{0x14,0x14,0x14,0x14,0x14,0x14,0x14,0x14}, // 0xCD
{0x14,0x14,0xF7,0xF7,0x00,0xF7,0xF7,0x14}, // 0xCE
{0x66,0x3C,0x3C,0x24,0x3C,0x3C,0x66,0x00}, // 0xCF
{0x05,0x27,0x72,0x57,0x7D,0x38,0x00,0x00}, // 0xD0
{0x49,0x7F,0x7F,0x49,0x63,0x7F,0x1C,0x00}, // 0xD1
{0x46,0x7D,0x7D,0x55,0x55,0x46,0x00,0x00}, // 0xD2
{0x45,0x7D,0x7C,0x54,0x55,0x45,0x00,0x00}, // 0xD3
{0x44,0x7D,0x7F,0x56,0x54,0x44,0x00,0x00}, // 0xD4
{0x0A,0x0E,0x08,0x00,0x00,0x00,0x00,0x00}, // 0xD5
{0x00,0x44,0x7E,0x7F,0x45,0x00,0x00,0x00}, // 0xD6
{0x02,0x45,0x7D,0x7D,0x45,0x02,0x00,0x00}, // 0xD7
{0x01,0x45,0x7C,0x7C,0x45,0x01,0x00,0x00}, // 0xD8
{0x10,0x10,0x10,0x1F,0x1F,0x00,0x00,0x00}, // 0xD9
{0x00,0x00,0x00,0xF0,0xF0,0x10,0x10,0x10}, // 0xDA
{0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF}, // 0xDB
{0xF0,0xF0,0xF0,0xF0,0xF0,0xF0,0xF0,0xF0}, // 0xDC
{0x00,0x00,0x00,0x77,0x77,0x00,0x00,0x00}, // 0xDD
{0x00,0x45,0x7F,0x7E,0x44,0x00,0x00,0x00}, // 0xDE
{0x0F,0x0F,0x0F,0x0F,0x0F,0x0F,0x0F,0x0F}, // 0xDF
{0x38,0x7C,0x46,0x47,0x45,0x7C,0x38,0x00}, // 0xE0
{0xFC,0xFE,0x2A,0x2A,0x3E,0x14,0x00,0x00}, // 0xE1
{0x3A,0x7D,0x45,0x45,0x45,0x7D,0x3A,0x00}, // 0xE2
{0x38,0x7C,0x45,0x47,0x46,0x7C,0x38,0x00}, // 0xE3
{0x32,0x7B,0x49,0x4B,0x7A,0x33,0x01,0x00}, // 0xE4
{0x3A,0x7F,0x45,0x47,0x46,0x7F,0x39,0x00}, // 0xE5
{0x80,0xFE,0x7E,0x20,0x20,0x3E,0x1E,0x00}, // 0xE6
{0x42,0x7E,0x7E,0x54,0x1C,0x08,0x00,0x00}, // 0xE7
{0x41,0x7F,0x7F,0x55,0x14,0x1C,0x08,0x00}, // 0xE8
{0x3C,0x7C,0x42,0x43,0x7D,0x3C,0x00,0x00}, // 0xE9
{0x3A,0x79,0x41,0x41,0x79,0x3A,0x00,0x00}, // 0xEA
{0x3C,0x7D,0x43,0x42,0x7C,0x3C,0x00,0x00}, // 0xEB
{0xB8,0xB8,0xA2,0xA3,0xF9,0x78,0x00,0x00}, // 0xEC
{0x0C,0x5C,0x72,0x73,0x5D,0x0C,0x00,0x00}, // 0xED
{0x02,0x02,0x02,0x02,0x02,0x02,0x00,0x00}, // 0xEE
{0x00,0x00,0x02,0x03,0x01,0x00,0x00,0x00}, // 0xEF
{0x10,0x10,0x10,0x10,0x10,0x10,0x00,0x00}, // 0xF0
{0x44,0x44,0x5F,0x5F,0x44,0x44,0x00,0x00}, // 0xF1
{0x28,0x28,0x28,0x28,0x28,0x28,0x00,0x00}, // 0xF2
{0x71,0x35,0x1F,0x4C,0x66,0x73,0xD9,0xF8}, // 0xF3
{0x06,0x0F,0x09,0x7F,0x7F,0x01,0x7F,0x7F}, // 0xF4
{0xDA,0xBF,0xA5,0xA5,0xFD,0x59,0x03,0x02}, // 0xF5
{0x08,0x08,0x6B,0x6B,0x08,0x08,0x00,0x00}, // 0xF6
{0x00,0x80,0xC0,0x40,0x00,0x00,0x00,0x00}, // 0xF7
{0x00,0x06,0x0F,0x09,0x0F,0x06,0x00,0x00}, // 0xF8
{0x02,0x02,0x00,0x00,0x02,0x02,0x00,0x00}, // 0xF9
{0x00,0x00,0x00,0x10,0x10,0x00,0x00,0x00}, // 0xFA
{0x00,0x12,0x13,0x1F,0x1F,0x10,0x10,0x00}, // 0xFB
{0x00,0x11,0x15,0x15,0x1F,0x1F,0x0A,0x00}, // 0xFC
{0x00,0x19,0x1D,0x15,0x17,0x12,0x00,0x00}, // 0xFD
{0x00,0x00,0x3C,0x3C,0x3C,0x3C,0x00,0x00}, // 0xFE
{0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00} // 0xFF
};
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/lcd/Font8x8.h
0,0 → 1,31
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* - font provided by Claas Anders "CaScAdE" Rathje *
* - umlauts and special characters by Peter "woggle" Mack *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _FONT8X8_H
#define _FONT8X8_H
 
#include <avr/pgmspace.h>
 
 
extern const uint8_t Font8x8[256][8];
 
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/lcd/font8x6.c
0,0 → 1,232
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* - font provided by Claas Anders "CaScAdE" Rathje *
* - umlauts and special characters by Peter "woggle" Mack *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
//############################################################################
//# HISTORY font8x6.c
//#
//# 07.07.2013 OG
//# - add: SYMBOL_CHECK (ehemals 'Antenne' Ascii 31)
//#
//# 11.06.2013 OG
//# - add: SYMBOL_AVG, SYMBOL_MIN, SYMBOL_MAX fuer OSDDATA Anzeige
//# - del: Antennen-Symbol von OSD_General (wird wieder gezeichnet)
//#
//# 15.05.2013 OG
//# - add: ASC 11 (0x0B) SYMBOL_SMALLDEGREE
//# - add: ASC 16 (0x10) SYMBOL_RCQUALITY
//############################################################################
 
#include <avr/pgmspace.h>
 
// one byte is a column
// bit 7 is the bottom
//
// 123456
// L 1 | XXX |
// O 2 |X X |
// W 4 |X X |
// 8 | XXX |
// H 1 |X X |
// I 2 |X X |
// G 4 | XXX |
// H 8 | |
//
// 0x36,0x49,0x49,0x49,0x36,0x00
//
 
// 123456
// L 1 | |
// O 2 | |
// W 4 | X|
// 8 | X |
// H 1 | X |
// I 2 |X X |
// G 4 | X |
// H 8 | |
 
// 0x20,0x40,0x20,0x10,0x08,0x04
 
 
// 123456
// L 1 | |
// O 2 | X|
// W 4 | X |
// 8 | X |
// H 1 |X X |
// I 2 | X |
// G 4 | |
// H 8 | |
 
// 0x10,0x20,0x10,0x08,0x04,0x02
 
// 123456
// L 1 | |
// O 2 | |
// W 4 | XX|
// 8 | XX |
// H 1 |X XX |
// I 2 | XX |
// G 4 | |
// H 8 | |
 
// 0x10,0x20,0x30,0x18,0x0c,0x04
//----------------------------------------------------------------
 
const uint8_t font8x6[128][6] PROGMEM =
{
{ 0x00,0x00,0x00,0x00,0x00,0x00 }, // ASCII - 0 00 (not useable)
 
{ 0x78,0x15,0x14,0x15,0x78,0x00 }, // ASCII - 1 01 'Ä'
{ 0x20,0x55,0x54,0x55,0x78,0x00 }, // ASCII - 2 02 'ä'
{ 0x38,0x45,0x44,0x45,0x38,0x00 }, // ASCII - 3 03 'Ö'
{ 0x30,0x49,0x48,0x49,0x30,0x00 }, // ASCII - 4 04 'ö'
{ 0x3c,0x41,0x40,0x41,0x3c,0x00 }, // ASCII - 5 05 'Ü'
{ 0x38,0x41,0x40,0x21,0x78,0x00 }, // ASCII - 6 06 'ü'
{ 0x7e,0x15,0x15,0x15,0x0a,0x00 }, // ASCII - 7 07 'ß'
{ 0x22,0x17,0x0F,0x17,0x22,0x00 }, // ASCII - 8 08 SAT Symbol
{ 0x00,0x84,0x82,0xFF,0x82,0x84 }, // ASCII - 9 09 Altitude Symbol
{ 0x1c,0x14,0x1c,0x00,0x00,0x00 }, // ASCII - 10 0A (not useable) SYMBOL_AVG
{ 0x00,0x07,0x05,0x07,0x00,0x00 }, // ASCII - 11 0B small degree SYMBOL_SMALLDEGREE
{ 0x10,0x38,0x54,0x10,0x10,0x1e }, // ASCII - 12 0C Enter Symbol
{ 0x18,0x0c,0x18,0x00,0x00,0x00 }, // ASCII - 13 0D (not useable) SYMBOL_MAX
{ 0x10,0x10,0x10,0x10,0x10,0x10 }, // ASCII - 14 0E hor. line
{ 0x10,0x10,0x10,0x7c,0x10,0x10 }, // ASCII - 15 0F hor. line with tick mark
{ 0x08,0x10,0x08,0x00,0x00,0x00 }, // ASCII - 16 10 rc quality SYMBOL_MIN
{ 0x08,0x14,0x00,0x00,0x14,0x08 }, // ASCII - 17 11 <> Change
{ 0x10,0x08,0x04,0x04,0x08,0x10 }, // ASCII - 18 12 /\ Up
{ 0x08,0x10,0x20,0x20,0x10,0x08 }, // ASCII - 19 13 \/ Down
{ 0x00,0x08,0x14,0x22,0x41,0x00 }, // ASCII - 20 14 < Left
{ 0x00,0x41,0x22,0x14,0x08,0x00 }, // ASCII - 21 15 > Right
{ 0x04,0x02,0x7f,0x02,0x04,0x00 }, // ASCII - 22 16 /|\ Arrow up
{ 0x10,0x20,0x7f,0x20,0x10,0x00 }, // ASCII - 23 17 \|/ Arrow down
{ 0x10,0x38,0x54,0x10,0x10,0x10 }, // ASCII - 24 18 <- Arrow left
{ 0x10,0x10,0x10,0x54,0x38,0x10 }, // ASCII - 25 19 -> Arrow right
{ 0x10,0x18,0x1c,0x1c,0x18,0x10 }, // ASCII - 26 1A ^ Triangle up
{ 0x08,0x18,0x38,0x38,0x18,0x08 }, // ASCII - 27 1B v Triangle down
{ 0x00,0x08,0x1c,0x3e,0x7f,0x00 }, // ASCII - 28 1C < Triangle left
{ 0x00,0x7f,0x3e,0x1c,0x08,0x00 }, // ASCII - 29 1D > Triangle right
{ 0x06,0x09,0x09,0x09,0x06,0x00 }, // ASCII - 30 1E '°' big degree SYMBOL_BIGDEGREE
 
// { 0x06,0x49,0x7d,0x49,0x06,0x00 }, // ASCII - 31 1F Antenne (ALT)
{ 0x10,0x20,0x10,0x08,0x04,0x02 }, // ASCII - 31 1F SYMBOL_CHECK
 
{ 0x00,0x00,0x00,0x00,0x00,0x00 }, // ASCII - 32 20 ' '
{ 0x00,0x00,0x2f,0x00,0x00,0x00 }, // ASCII - 33 21 '!'
{ 0x00,0x07,0x00,0x07,0x00,0x00 }, // ASCII - 34 22 '"'
{ 0x14,0x7f,0x14,0x7f,0x14,0x00 }, // ASCII - 35 23 '#'
{ 0x24,0x2a,0x6b,0x2a,0x12,0x00 }, // ASCII - 36 24 '$'
{ 0x23,0x13,0x08,0x64,0x62,0x00 }, // ASCII - 37 25 '%'
{ 0x36,0x49,0x55,0x22,0x50,0x00 }, // ASCII - 38 26 '&'
{ 0x00,0x05,0x03,0x00,0x00,0x00 }, // ASCII - 39 27 '''
{ 0x00,0x1c,0x22,0x41,0x00,0x00 }, // ASCII - 40 28 '('
{ 0x00,0x41,0x22,0x1c,0x00,0x00 }, // ASCII - 41 29 ')'
{ 0x14,0x08,0x3e,0x08,0x14,0x00 }, // ASCII - 42 2a '*'
{ 0x08,0x08,0x3e,0x08,0x08,0x00 }, // ASCII - 43 2b '+'
{ 0x00,0x50,0x30,0x00,0x00,0x00 }, // ASCII - 44 2c ','
{ 0x08,0x08,0x08,0x08,0x08,0x00 }, // ASCII - 45 2d '-'
{ 0x00,0x60,0x60,0x00,0x00,0x00 }, // ASCII - 46 2e '.'
{ 0x20,0x10,0x08,0x04,0x02,0x00 }, // ASCII - 47 2f '/'
{ 0x3e,0x51,0x49,0x45,0x3e,0x00 }, // ASCII - 48 30 '0'
{ 0x00,0x42,0x7f,0x40,0x00,0x00 }, // ASCII - 49 31 '1'
{ 0x42,0x61,0x51,0x49,0x46,0x00 }, // ASCII - 50 32 '2'
{ 0x21,0x41,0x45,0x4b,0x31,0x00 }, // ASCII - 51 33 '3'
{ 0x18,0x14,0x12,0x7f,0x10,0x00 }, // ASCII - 52 34 '4'
{ 0x27,0x45,0x45,0x45,0x39,0x00 }, // ASCII - 53 35 '5'
{ 0x3c,0x4a,0x49,0x49,0x30,0x00 }, // ASCII - 54 36 '6'
{ 0x03,0x01,0x71,0x09,0x07,0x00 }, // ASCII - 55 37 '7'
{ 0x36,0x49,0x49,0x49,0x36,0x00 }, // ASCII - 56 38 '8'
{ 0x06,0x49,0x49,0x29,0x1e,0x00 }, // ASCII - 57 39 '9'
{ 0x00,0x36,0x36,0x00,0x00,0x00 }, // ASCII - 58 3a ':'
{ 0x00,0x56,0x36,0x00,0x00,0x00 }, // ASCII - 59 3b ';'
{ 0x08,0x14,0x22,0x41,0x00,0x00 }, // ASCII - 60 3c '<'
{ 0x14,0x14,0x14,0x14,0x14,0x00 }, // ASCII - 61 3d '='
{ 0x00,0x41,0x22,0x14,0x08,0x00 }, // ASCII - 62 3e '>'
{ 0x02,0x01,0x51,0x09,0x06,0x00 }, // ASCII - 63 3f '?'
{ 0x32,0x49,0x79,0x41,0x3e,0x00 }, // ASCII - 64 40 '@'
{ 0x7e,0x11,0x11,0x11,0x7e,0x00 }, // ASCII - 65 41 'A'
{ 0x7f,0x49,0x49,0x49,0x36,0x00 }, // ASCII - 66 42 'B'
{ 0x3e,0x41,0x41,0x41,0x22,0x00 }, // ASCII - 67 43 'C'
{ 0x7f,0x41,0x41,0x22,0x1c,0x00 }, // ASCII - 68 44 'D'
{ 0x7f,0x49,0x49,0x49,0x41,0x00 }, // ASCII - 69 45 'E'
{ 0x7f,0x09,0x09,0x09,0x01,0x00 }, // ASCII - 70 46 'F'
{ 0x3e,0x41,0x49,0x49,0x7a,0x00 }, // ASCII - 71 47 'G'
{ 0x7f,0x08,0x08,0x08,0x7f,0x00 }, // ASCII - 72 48 'H'
{ 0x00,0x41,0x7f,0x41,0x00,0x00 }, // ASCII - 73 49 'I'
{ 0x20,0x40,0x41,0x3f,0x01,0x00 }, // ASCII - 74 4a 'J'
{ 0x7f,0x08,0x14,0x22,0x41,0x00 }, // ASCII - 75 4b 'K'
{ 0x7f,0x40,0x40,0x40,0x40,0x00 }, // ASCII - 76 4c 'L'
{ 0x7f,0x02,0x0c,0x02,0x7f,0x00 }, // ASCII - 77 4d 'M'
{ 0x7f,0x04,0x08,0x10,0x7f,0x00 }, // ASCII - 78 4e 'N'
{ 0x3e,0x41,0x41,0x41,0x3e,0x00 }, // ASCII - 79 4f 'O'
{ 0x7f,0x09,0x09,0x09,0x06,0x00 }, // ASCII - 80 50 'P'
{ 0x3e,0x41,0x51,0x21,0x5e,0x00 }, // ASCII - 81 51 'Q'
{ 0x7f,0x09,0x19,0x29,0x46,0x00 }, // ASCII - 82 52 'R'
{ 0x46,0x49,0x49,0x49,0x31,0x00 }, // ASCII - 83 53 'S'
{ 0x01,0x01,0x7f,0x01,0x01,0x00 }, // ASCII - 84 54 'T'
{ 0x3f,0x40,0x40,0x40,0x3f,0x00 }, // ASCII - 85 55 'U'
{ 0x1f,0x20,0x40,0x20,0x1f,0x00 }, // ASCII - 86 56 'V'
{ 0x3f,0x40,0x38,0x40,0x3f,0x00 }, // ASCII - 87 57 'W'
{ 0x63,0x14,0x08,0x14,0x63,0x00 }, // ASCII - 88 58 'X'
{ 0x07,0x08,0x70,0x08,0x07,0x00 }, // ASCII - 89 59 'Y'
{ 0x61,0x51,0x49,0x45,0x43,0x00 }, // ASCII - 90 5a 'Z'
{ 0x7f,0x41,0x41,0x00,0x00,0x00 }, // ASCII - 91 5b '['
{ 0x02,0x04,0x08,0x10,0x20,0x00 }, // ASCII - 92 5c '\'
{ 0x00,0x41,0x41,0x7f,0x00,0x00 }, // ASCII - 93 5d ']'
{ 0x04,0x02,0x01,0x02,0x04,0x00 }, // ASCII - 94 5e '^'
{ 0x40,0x40,0x40,0x40,0x40,0x00 }, // ASCII - 95 5f '_'
{ 0x00,0x01,0x02,0x04,0x00,0x00 }, // ASCII - 96 60 '`'
{ 0x20,0x54,0x54,0x54,0x78,0x00 }, // ASCII - 97 61 'a'
{ 0x7f,0x48,0x44,0x44,0x38,0x00 }, // ASCII - 98 62 'b'
{ 0x38,0x44,0x44,0x44,0x20,0x00 }, // ASCII - 99 63 'c'
{ 0x38,0x44,0x44,0x48,0x7f,0x00 }, // ASCII - 100 64 'd'
{ 0x38,0x54,0x54,0x54,0x18,0x00 }, // ASCII - 101 65 'e'
{ 0x08,0x7e,0x09,0x01,0x02,0x00 }, // ASCII - 102 66 'f'
{ 0x0c,0x52,0x52,0x52,0x3e,0x00 }, // ASCII - 103 67 'g'
{ 0x7f,0x08,0x04,0x04,0x78,0x00 }, // ASCII - 104 68 'h'
{ 0x00,0x44,0x7d,0x40,0x00,0x00 }, // ASCII - 105 69 'i'
{ 0x20,0x40,0x44,0x3d,0x00,0x00 }, // ASCII - 106 6a 'j'
{ 0x7f,0x10,0x28,0x44,0x00,0x00 }, // ASCII - 107 6b 'k'
{ 0x00,0x41,0x7f,0x40,0x00,0x00 }, // ASCII - 108 6c 'l'
{ 0x7c,0x04,0x18,0x04,0x78,0x00 }, // ASCII - 109 6d 'm'
{ 0x7c,0x08,0x04,0x04,0x78,0x00 }, // ASCII - 110 6e 'n'
{ 0x38,0x44,0x44,0x44,0x38,0x00 }, // ASCII - 111 6f 'o'
{ 0x7c,0x14,0x14,0x14,0x08,0x00 }, // ASCII - 112 70 'p'
{ 0x08,0x14,0x14,0x18,0x7c,0x00 }, // ASCII - 113 71 'q'
{ 0x7c,0x08,0x04,0x04,0x08,0x00 }, // ASCII - 114 72 'r'
{ 0x48,0x54,0x54,0x54,0x20,0x00 }, // ASCII - 115 73 's'
{ 0x04,0x3f,0x44,0x40,0x20,0x00 }, // ASCII - 116 74 't'
{ 0x3c,0x40,0x40,0x20,0x7c,0x00 }, // ASCII - 117 75 'u'
{ 0x1c,0x20,0x40,0x20,0x1c,0x00 }, // ASCII - 118 76 'v'
{ 0x3c,0x40,0x38,0x40,0x3c,0x00 }, // ASCII - 119 77 'w'
{ 0x44,0x28,0x10,0x28,0x44,0x00 }, // ASCII - 120 78 'x'
{ 0x0c,0x50,0x50,0x50,0x3c,0x00 }, // ASCII - 121 79 'y'
{ 0x44,0x64,0x54,0x4c,0x44,0x00 }, // ASCII - 122 7a 'z'
{ 0x00,0x08,0x36,0x41,0x00,0x00 }, // ASCII - 123 7b '{'
{ 0x00,0x00,0x7f,0x00,0x00,0x00 }, // ASCII - 124 7c '|'
{ 0x00,0x41,0x36,0x08,0x00,0x00 }, // ASCII - 125 7d '}'
{ 0x08,0x08,0x2a,0x1c,0x08,0x00 }, // ASCII - 126 7e ->
{ 0x08,0x1c,0x2a,0x08,0x08,0x00 }, // ASCII - 127 7f <-
};
 
 
/*
{ 0x02,0x0a,0x2a,0x0a,0x02,0x00 }, // ASCII - 16 10 rc quality SYMBOL_RCQUALITY (wieder entfernt weil der Platz gebraucht wurde)
*/
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/lcd/font8x6.h
0,0 → 1,30
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* - font provided by Claas Anders "CaScAdE" Rathje *
* - umlauts and special characters by Peter "woggle" Mack *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
#ifndef _FONT8X6_H
#define _FONT8X6_H
 
#include <avr/pgmspace.h>
 
//extern prog_uint8_t font8x6[128][6];
extern const uint8_t font8x6[128][6];
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/lcd/lcd.c
0,0 → 1,1990
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* - original LCD control by Thomas "thkais" Kaiser *
* - special number formating routines taken from C-OSD *
* from Claas Anders "CaScAdE" Rathje *
* - some extension, ellipse and circ_line by Peter "woggle" Mack *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
*****************************************************************************/
 
//############################################################################
//# HISTORY lcd.c
//#
//# 10.11.2014 cebra
//# - fix: lcd_init() weiter Helligkeitseinstellungen korrigiert (OCR2A)
//#
//# 28.06.2014 OG
//# - chg: lcdx_cls_rowwidth() kompatibel zu mode MINVERSX und MNORMALX
//# - chg: lcdx_cls_row() auf lcdx_cls_rowwidth() umgestellt
//# - fix: lcdx_printp() umgestellt auf strlen_P() statt strlen()
//#
//# 27.06.2014 OG
//# - add: die lcd-print Funktionen wurden um MINVERSX und MNORMALX erweitert
//# um einen zusaetzlichen Rand links und oben als Linie zu zeichnen
//# (wird z.B. in followme.c verwendet)
//#
//# 11.06.2014 OG
//# - add: lcd_set_contrast()
//# - add: include <avr/interrupt.h>
//#
//# 04.06.2014 OG
//# - add: lcdx_cls_rowwidth()
//#
//# 26.05.2014 OG
//# - chg: LCD_Init() - LCD-Modus nur noch normal (kein Invers mehr)
//#
//# 02.05.2014 OG
//# - add: Popup_Draw() (ehemals in osd.c)
//#
//# 13.04.2014 OG
//# - add: lcd_print_LF()
//#
//# 11.04.2014 OG
//# - add: lcdx_cls_row()
//#
//# 10.04.2014 OG
//# - add: include: lipo.h
//#
//# 08.04.2014 OG
//# - add: lcdx_printf_center(), lcdx_printf_center_P()
//#
//# 07.04.2014 OG
//# - add: lcd_setpos(), lcd_print_char()
//#
//# 04.04.2014 OG
//# - add: ShowTitle_P()
//#
//# 28.02.2014 OG
//# - del: show_baudrate()
//# - chg: PRINTF_BUFFER_SIZE von 80 auf 40
//#
//# 16.02.2014 OG
//# - add: lcdx_printp_center(), lcdx_print_center()
//#
//# 13.02.2014 OG
//# - add: lcd_frect_round()
//# - chg: lcd_rect_round() um R2 ergaenzt
//#
//# 12.02.2014 OG
//# - add: lcd_rect_round()
//#
//# 04.02.2014 OG
//# - fix: writex_ndigit_number_u_100th() Aufbau der Formatmaske
//#
//# 03.02.2014 OG
//# - fix: writex_ndigit_number_u_100th() Berechnung Formatstring korrigiert
//# - fix: writex_ndigit_number_u_100th() Parameter 'mode' fehlte
//#
//# 16.06.2013 OG
//# - chg: LCD_ORIENTATION festgesetzt auf 0 (Normal)
//#
//# 04.05.2013 OG
//# - chg: angepasst auf xutils.c
//# - chg: writex_datetime_time(), writex_datetime_date() Lokalzeitberechnung
//# via UTCdatetime2local()
//#
//# 03.05.2013 OG
//# - fix: writex_gpspos() - Anzeige negativer GPS-Koordinaten
//# - fix: Anzeigefehler writex_datetime_time()
//# - chg: writex_datetime_date() & writex_datetime_time() Parameter
//# 'timeoffset' entfernt da das durch PKT-Config geregelt werden soll
//#
//# 29.04.2013 OG
//# - chg: lcd_cls() geaendert auf memset
//#
//# 28.04.2013 OG
//# - chg: high-level Funktionen wie writex_ndigit... auf xprintf umgebaut
//# - add: lcdx_printf_at(), lcdx_printf_at_P()
//# lcd_printf_at(), lcd_printf_at_P()
//# siehe dazu: Doku in utils/xstring.h fuer xprintf
//#
//# 27.03.2013 OG
//# - add: writex_datetime_time()
//# - add: writex_datetime_date()
//# - add: Show_PKTError_NoRAM()
//#
//# 22.03.2013 OG
//# - add: writex_gpspos()
//#
//# 11.03.2013 OG
//# - fix: writex_time() Ausgabe Doppelpunkt ":" ergaenzt um mode,xoffs,yoffs
//#
//# 07.03.2013 OG
//# - del: Kompatibilitaetsfunktion lcd_printpj_at() entfernt
//#
//# 06.03.2013 OG
//# - lcdx_putc() wurde erweitert mit Unterstuetzung des 8x8 Font (alte Jeti
//# Funktionen) und Pixel-Verschiebung (xoffs,yoffs)
//# - etliche Char basierte Funktionen wurden erweitert um Parameter xoffs,yoffs
//# um die Ausgabe um +/- Pixel zu verschieben. Fuer Pixelgenaue Positionierung
//# von OSD-Screen Elementen.
//# Die neuen Funktionen mit Pixel-Verschiebung beginnen mit lcdx_, writex_ ...
//# - add: Kompatibilitaet gewaehrleistet durch Mapper-Funktionen
//# - add: defines fuer Char-Drawmode's (MNORMAL, MINVERS, MBIG, MBIGINVERS)
//# - del: Jeti-Funktionen (teilweise ersetzt durch Kompatibilitaetsfunktionen)
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include <stdarg.h>
 
#include "../eeprom/eeprom.h"
#include "../timer/timer.h"
#include "lcd.h"
#include "../main.h"
#include "../HAL_HW3_9.h"
#include "../utils/xutils.h" // xprintf, UTCdatetime2local
#include "../lipo/lipo.h" // show_Lipo()
 
 
#include "font8x6.h"
#ifdef USE_FONT_BIG
#include "Font8x8.h"
#endif
 
 
#define DISP_W 128
#define DISP_H 64
 
#define DISP_BUFFER ((DISP_H * DISP_W) / 8)
#define LINE_BUFFER (((DISP_H/8) * DISP_W) / 8)
 
#define Jeti 1 // Jeti Routinen
 
volatile uint8_t display_buffer[DISP_BUFFER]; // Display-Puffer, weil nicht zurückgelesen werden kann
volatile uint8_t line_buffer[LINE_BUFFER]; // Zeilen-Puffer, weil nicht zurückgelesen werden kann
 
volatile uint16_t display_buffer_pointer; // Pointer auf das aktuell übertragene Byte
volatile uint8_t display_buffer_counter; // Hilfszähler zur Selektierung der Page
volatile uint8_t display_page_counter; // aktuelle Page-Nummer
volatile uint8_t display_mode; // Modus für State-Machine
volatile uint8_t LCD_ORIENTATION = 0; // 0=Normal / 1=reversed
 
// DOG: 128 x 64 with 6x8 Font => 21 x 8
// MAX7456: 30 x 16
 
uint8_t lcd_xpos;
uint8_t lcd_ypos;
 
char s[7];
 
#define PRINTF_BUFFER_SIZE 40 // max. 40 Chars fuer den Buffer fuer lcdx_printf_at() / lcdx_printf_at_P()
char printf_buffer[PRINTF_BUFFER_SIZE];
 
char format_buffer[20];
 
//-----------------------------------------------------------
void send_byte( uint8_t data )
{
clr_cs ();
SPDR = data;
while (!(SPSR & (1<<SPIF)));
//SPSR = SPSR;
set_cs ();
}
 
 
//-----------------------------------------------------------
// * Writes one command byte
// * cmd - the command byte
//
void lcd_command( uint8_t cmd )
{
// LCD_SELECT();
// LCD_CMD();
// spi_write(cmd);
// LCD_UNSELECT();
clr_cs ();
SPDR = cmd;
while (!(SPSR & (1<<SPIF)));
//SPSR = SPSR;
set_cs ();
}
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcd_set_contrast( uint8_t value )
{
cli();
clr_A0();
send_byte( 0x81 );
send_byte( value ); // Daten zum LCD senden
set_A0();
sei();
}
 
 
 
//-----------------------------------------------------------
void lcd_cls( void )
{
uint16_t i, j;
 
memset( (void *)display_buffer, 0, 1024);
 
// for (i = 0; i < DISP_BUFFER; i++)
// display_buffer[i] = 0x00;
 
for (i = 0; i < 8; i++)
{
clr_A0 ();
send_byte (0xB0 + i); //1011xxxx
send_byte (0x10); //00010000
// send_byte(0x04); //00000100 gedreht plus 4 Byte
// send_byte(0x00); //00000000
send_byte (LCD_ORIENTATION); //00000000
 
set_A0 ();
for (j = 0; j < 128; j++)
send_byte (0x00);
}
 
lcd_xpos = 0;
lcd_ypos = 0;
}
 
 
//-----------------------------------------------------------
void set_adress (uint16_t adress, uint8_t data)
{
uint8_t page;
uint8_t column;
 
page = adress >> 7;
 
clr_A0 ();
send_byte (0xB0 + page);
 
column = (adress & 0x7F) + LCD_ORIENTATION;
 
send_byte (0x10 + (column >> 4));
send_byte (column & 0x0F);
 
set_A0 ();
send_byte (data);
}
 
 
//-----------------------------------------------------------
void scroll (void)
{
uint16_t adress;
 
for (adress = 0; adress < 896; adress++)
{
display_buffer[adress] = display_buffer[adress + 128];
set_adress (adress, display_buffer[adress]);
}
 
for (adress = 896; adress < 1024; adress++)
{
display_buffer[adress] = 0;
set_adress (adress, 0);
}
}
 
//####################################################################################
//####################################################################################
 
//-----------------------------------------------------------
// + Plot (set one Pixel)
//-----------------------------------------------------------
// mode:
// 0=Clear, 1=Set, 2=XOR
void lcd_plot (uint8_t xpos, uint8_t ypos, uint8_t mode)
{
uint16_t adress;
uint8_t mask;
 
if ((xpos < DISP_W) && (ypos < DISP_H))
{
adress = (ypos / 8) * DISP_W + xpos; // adress = 0/8 * 128 + 0 = 0
mask = 1 << (ypos & 0x07); // mask = 1<<0 = 1
adress &= DISP_BUFFER - 1;
switch (mode)
{
 
case 0:
display_buffer[adress] &= ~mask;
break;
 
case 1:
display_buffer[adress] |= mask;
break;
 
case 2:
display_buffer[adress] ^= mask;
break;
}
set_adress (adress, display_buffer[adress]);
}
}
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcdx_putc( uint8_t x, uint8_t y, uint8_t c, uint8_t mode, int8_t xoffs, int8_t yoffs )
{
uint8_t ch;
uint16_t adress;
 
uint8_t x1,y1;
uint8_t x0,y0;
uint8_t xw;
uint8_t mask;
uint8_t bit;
 
uint8_t *font;
 
//------------------------
// char translate
//------------------------
switch (c)
{ // ISO 8859-1
 
case 0xc4: c = 0x01; break; // Ä
case 0xe4: c = 0x02; break; // ä
case 0xd6: c = 0x03; break; // Ö
case 0xf6: c = 0x04; break; // ö
case 0xdc: c = 0x05; break; // Ü
case 0xfc: c = 0x06; break; // ü
case 0xdf: c = 0x1e; break; // ß c = 0x07; ° (used by Jeti)
}
 
c &= 0x7f;
 
//------------------------
// Font Parameter setzen
//------------------------
#ifdef USE_FONT_BIG
if( mode <=2 ) // normaler font (8x6)
{
font = (uint8_t *) &font8x6[0][0];
xw = 6;
}
else // grosser font (8x8)
{
font = (uint8_t *) &Font8x8[0][0];
xw = 8;
}
#else
font = (uint8_t *) &font8x6[0][0];
xw = 6;
#endif
 
 
//------------------------
//------------------------
x0 = (x*xw) + xoffs;
y0 = (y*8) + yoffs;
 
 
if( yoffs == 0)
{
//----------------------------------------------------------
// orginaler Character Algo
//
// funktioniert auch mit x Verschiebung aber nicht
// mit y Verschiebung.
//
// Da 8 Bit aufeinmal gesetzt werden ist dieser Algo
// bzgl. Geschwindigkeit effektiver als der Y-Algo.
//----------------------------------------------------------
 
if( mode==MINVERS || mode==MBIGINVERS )
lcd_frect( (x*xw)+xoffs, (y*8), xw-1, 7, 1); // invertierte Darstellung
 
adress = y * 128 + x * xw + xoffs;
adress &= 0x3FF;
 
for( x1 = 0; x1 < xw; x1++)
{
ch = pgm_read_byte (font + x1 + c * xw);
 
if( mode==MINVERS || mode==MBIGINVERS )
display_buffer[adress + x1] ^= ch;
else
display_buffer[adress + x1] = ch;
 
set_adress (adress + x1, display_buffer[adress + x1]);
}
}
else
{
//----------------------------------------------------------
// Y-Algo
// neuer Character Algo (nur wenn Pixel y-Verschiebung)
//----------------------------------------------------------
for( x1 = 0; x1 < xw; x1++ )
{
ch = pgm_read_byte (font + x1 + c * xw);
 
mask = 1;
 
for( y1 = 0; y1 < 8; y1++ )
{
bit = (ch & mask);
 
if( bit )
lcd_plot( x0+x1, y0+y1, ( (mode==MINVERS || mode==MBIGINVERS) ? 0 : 1) );
else
lcd_plot( x0+x1, y0+y1, ( (mode==MINVERS || mode==MBIGINVERS) ? 1 : 0) );
 
mask = (mask << 1);
}
}
}
}
 
 
//-----------------------------------------------------------
//--- Kompatibilitaet
//-----------------------------------------------------------
void lcd_putc( uint8_t x, uint8_t y, uint8_t c, uint8_t mode )
{
lcdx_putc( x, y, c, mode, 0,0 );
}
 
 
 
//####################################################################################
//####################################################################################
 
 
//-----------------------------------------------------------
void lcd_cls_line (uint8_t x, uint8_t y, uint8_t w)
{
uint8_t lcd_width;
uint8_t lcd_zpos;
uint8_t i;
uint8_t max = 21;
lcd_width = w;
lcd_xpos = x;
lcd_ypos = y;
 
if ((lcd_xpos + lcd_width) > max)
lcd_width = max - lcd_xpos;
 
lcd_zpos = lcd_xpos + lcd_width;
 
for (i = lcd_xpos; i < lcd_zpos; i++)
lcd_putc (i, lcd_ypos, 0x20, 0);
}
 
 
//-----------------------------------------------------------
void wait_1ms (void)
{
_delay_ms (1);
}
 
 
//-----------------------------------------------------------
void wait_ms (uint16_t time)
{
uint16_t i;
 
for (i = 0; i < time; i++)
wait_1ms ();
}
 
 
//-----------------------------------------------------------
void LCD_Init( uint8_t LCD_Mode ) // LCD_Mode 0= Default Mode 1= EEPROM-Parameter)
{
lcd_xpos = 0;
lcd_ypos = 0;
 
// DDRB = 0xFF;
 
// SPI max. speed
// the DOGM128 lcd controller can work at 20 MHz
SPCR = (1 << SPE) | (1 << MSTR) | (1 << CPHA) | (1 << CPOL);
SPSR = (1 << SPI2X);
 
set_cs();
clr_reset();
wait_ms(10);
set_reset();
 
clr_cs();
clr_A0();
 
send_byte( 0x40 ); //Display start line = 0
 
 
//------------------------------------------------------------
// 10.11.2014 cebra
// Umschaltung der Displayansicht wird nicht mehr benötigt
// if (LCD_Mode == 1)
// {
// if (LCD_ORIENTATION == 0)
// {
// send_byte( 0xA1 ); // A1 normal A0 reverse(original)
// send_byte( 0xC0 ); // C0 normal C8 reverse(original)
// }
// else
// {
// send_byte( 0xA0 ); // A1 normal A0 reverse(original)
// send_byte( 0xC8 ); // C0 normal C8 reverse(original)
// }
// }
// else
// {
send_byte( 0xA1 ); // A1 normal A0 reverse(original)
send_byte( 0xC0 ); // C0 normal C8 reverse(original)
// }
 
/*
//------------------------------------------------------------
// 26.05.2014 OG: einstellen von Normal/Invers durch den User
// nicht mehr unterstuetzt, da der Modus Invers beim PKT
// auf verschiedenen Display's nicht gut aussieht.
// Ab jetzt nur noch LC-Modus Normal.
//------------------------------------------------------------
if (LCD_Mode == 1)
{
if (Config.LCD_DisplayMode == 0)
send_byte (0xA6); //Display normal, not mirrored
else
send_byte (0xA7); //Display reverse, not mirrored
}
else
send_byte (0xA6);
*/
 
send_byte( 0xA6 ); //Display normal, not mirrored
 
send_byte( 0xA2 ); //Set bias 1/9 (Duty 1/65)
send_byte( 0x2F ); //Booster, regulator and follower on
send_byte( 0xF8 ); //Set internal booster to 4x
send_byte( 0x00 ); //Set internal booster to 4x
send_byte( 0x27 ); //resistor ratio set
 
if( LCD_Mode == 1 )
{
send_byte( 0x81 ); //Electronic volume register set
send_byte( Config.LCD_Kontrast ); //Electronic volume register set
}
else
{
send_byte( 0x81 );
send_byte( 0x16 );
}
 
send_byte( 0xAC ); //Cursor
send_byte( 0x00 ); //No Cursor
send_byte( 0xAF ); //No indicator
 
 
 
if( Config.HWSound == 0 )
{
if( LCD_Mode == 1 )
{
//------------------------------------------------------------
//10.11.2014 cebra,
//Helligkeitseinstellungen werden nicht mehr genutzt
// Helligkeit setzen
// OCR2A = Config.LCD_Helligkeit * 2.55;
 
//OCR2A = 255;
}
else
{
// OCR2A = 255;
}
}
lcd_cls();
}
 
 
 
 
//-----------------------------------------------------------
// sicher eine Zeile für die Statusanzeige
void copy_line (uint8_t y)
{
uint8_t i;
uint16_t adress;
 
adress = y * 128 + 0 * 6;
adress &= 0x3FF;
 
for (i = 0; i < 6*21; i++)
{
line_buffer[i] = display_buffer[adress+i];
set_adress (adress + i, display_buffer[adress + i]);
}
}
 
 
//-----------------------------------------------------------
// holt gesicherte Zeile wieder zurück
void paste_line (uint8_t y)
{
uint8_t i;
uint16_t adress;
 
adress = y * 128 + 0 * 6;
adress &= 0x3FF;
 
for (i = 0; i < 6*21; i++)
{
display_buffer[adress+i] =line_buffer[i];
set_adress (adress + i, display_buffer[adress + i]);
}
}
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcdx_puts_at( uint8_t x, uint8_t y, const char *s, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
while (*s)
{
lcdx_putc(x, y, *s++, mode, xoffs,yoffs);
x++;
}
}/* lcd_puts */
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcd_puts_at( uint8_t x, uint8_t y, const char *s, uint8_t mode )
{
lcdx_puts_at( x, y, s, mode, 0,0 );
}
 
 
//-----------------------------------------------------------
void new_line (void)
{
lcd_ypos++;
 
if (lcd_ypos > 7)
{
scroll ();
lcd_ypos = 7;
}
}
 
 
//-----------------------------------------------------------
void lcd_printpns (const char *text, uint8_t mode)
{
while (pgm_read_byte(text))
{
switch (pgm_read_byte(text))
{
 
case 0x0D:
lcd_xpos = 0;
break;
 
case 0x0A:
new_line();
break;
 
default:
lcd_putc (lcd_xpos, lcd_ypos, pgm_read_byte(text), mode);
lcd_xpos++;
if (lcd_xpos > 21)
{
lcd_xpos = 0;
// new_line ();
}
break;
}
text++;
}
}
 
 
//-----------------------------------------------------------
void lcd_printpns_at (uint8_t x, uint8_t y, const char *text, uint8_t mode)
{
lcd_xpos = x;
lcd_ypos = y;
lcd_printpns (text, mode);
}
 
 
 
//--------------------------------------------------------------
// INTERN
//
// erweitert bei mode MINVERSX und MNORMALX links und oben den
// Text um jeweils einen Pixel -> der Invers-Modus sieht besser aus
//--------------------------------------------------------------
uint8_t _lcdx_print_modeextend( uint8_t progmem, uint8_t x, uint8_t y, uint8_t textlen, uint8_t mode, int8_t xoffs, int8_t yoffs )
{
uint8_t draw = 0;
 
if( (mode == MNORMALX) || (mode == MINVERSX) )
{
if( mode == MNORMALX ) mode = MNORMAL;
else mode = MINVERS;
 
if( mode == MINVERS )
draw = 1;
 
if( (y*8)+yoffs-1 >= 0 )
lcd_line( (x*6)+xoffs, (y*8)+yoffs-1, (x*6)+xoffs+(textlen*6)-1, (y*8)+yoffs-1, draw); // horizontale Linie ueber dem Text
 
if( (x*6)+xoffs-1 >= 0 )
lcd_line( (x*6)+xoffs-1, (y*8)+yoffs-1, (x*6)+xoffs-1, (y*8)+yoffs+7, draw); // vertikale Linie links neben dem Text
}
 
return mode;
}
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void _lcdx_print_outchar( unsigned char c, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
switch( c )
{
case 0x0D: lcd_xpos = 0;
break;
 
case 0x0A: new_line();
break;
 
default: lcdx_putc( lcd_xpos, lcd_ypos, c, mode, xoffs,yoffs );
lcd_xpos++;
if( lcd_xpos > 21 )
{
lcd_xpos = 0;
new_line();
}
break;
}
}
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcdx_print( uint8_t *text, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
mode = _lcdx_print_modeextend( false, lcd_xpos, lcd_ypos, strlen( (const char *)text), mode, xoffs, yoffs ); // RAM Modus
 
while( *text )
{
_lcdx_print_outchar( *text, mode, xoffs,yoffs);
text++;
}
}
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcdx_printp( const char *text, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
char c;
 
mode = _lcdx_print_modeextend( true, lcd_xpos, lcd_ypos, strlen_P( (const char *)text), mode, xoffs, yoffs ); // PROGMEM Modus
 
while( (c = pgm_read_byte(text)) )
{
_lcdx_print_outchar( c, mode, xoffs,yoffs);
text++;
}
}
 
 
 
 
 
 
/*
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcdx_print( uint8_t *text, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
mode = _lcdx_print_invers_extend( false, lcd_xpos, lcd_ypos, strlen( (const char *)text), mode, xoffs, yoffs ); // RAM Modus
 
 
while( *text )
{
switch( *text )
{
case 0x0D: lcd_xpos = 0;
break;
 
case 0x0A: new_line();
break;
 
default: lcdx_putc (lcd_xpos, lcd_ypos, *text, mode, xoffs,yoffs);
lcd_xpos++;
if( lcd_xpos > 21 )
{
lcd_xpos = 0;
new_line();
}
break;
}
text++;
}
}
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcdx_printp( const char *text, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
mode = _lcdx_print_invers_extend( true, lcd_xpos, lcd_ypos, strlen( (const char *)text), mode, xoffs, yoffs ); // PROGMEM Modus
 
 
while( pgm_read_byte(text) )
{
switch( pgm_read_byte(text) )
{
case 0x0D: lcd_xpos = 0;
break;
 
case 0x0A: new_line();
break;
 
default: lcdx_putc (lcd_xpos, lcd_ypos, pgm_read_byte(text), mode, xoffs,yoffs);
lcd_xpos++;
if( lcd_xpos > 21 )
{
lcd_xpos = 0;
new_line();
}
break;
}
text++;
}
}
*/
 
 
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcd_printp (const char *text, uint8_t mode)
{
lcdx_printp ( text, mode, 0,0);
}
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcdx_printp_at (uint8_t x, uint8_t y, const char *text, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
lcd_xpos = x;
lcd_ypos = y;
lcdx_printp (text, mode, xoffs,yoffs);
}
 
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcd_printp_at (uint8_t x, uint8_t y, const char *text, uint8_t mode)
{
lcdx_printp_at ( x, y, text, mode, 0,0);
}
 
 
 
//-----------------------------------------------------------
//--- lcd_print: Kompatibilitaet
//-----------------------------------------------------------
void lcd_print (uint8_t *text, uint8_t mode )
{
lcdx_print (text, mode, 0,0 );
}
 
 
//-----------------------------------------------------------
void lcdx_print_at (uint8_t x, uint8_t y, uint8_t *text, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
lcd_xpos = x;
lcd_ypos = y;
lcdx_print (text, mode, xoffs, yoffs);
}
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcdx_print_center( uint8_t y, uint8_t *text, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
xoffs = xoffs + ((uint8_t)(64 - ( (strlen((const char *)text)*6) /2))); // Pixelgenau zentrieren (fuer 6x8 font)
lcdx_print_at( 0, y, text, mode, xoffs,yoffs);
}
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcdx_printp_center( uint8_t y, const char *text, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
xoffs = xoffs + ((uint8_t)(64 - ( (strlen_P(text)*6) /2))); // Pixelgenau zentrieren (fuer 6x8 font)
lcdx_printp_at( 0, y, text, mode, xoffs,yoffs);
}
 
 
//-----------------------------------------------------------
// lcdx_printf_center( y, mode, xoffs,yoffs, format, ...)
//
// Ausgabe von n-Parametern via Formattierung
// mit erweitertem xoffs,yoffs
//
// Die Ausgabe wird zentriert,
//
// Parameter:
// y : Position in Char y
// mode : MNORMAL, MINVERS, ...
// xoffs,yoffs: Verschiebung in Pixel
// format : String aus PROGMEM (siehe: xprintf in utils/xstring.h)
// ... : Parameter fuer 'format'
//-----------------------------------------------------------
void lcdx_printf_center( uint8_t y, uint8_t mode, int8_t xoffs, int8_t yoffs, const char *format, ... )
{
va_list ap;
 
va_start( ap, format );
_xvsnprintf( false, printf_buffer, PRINTF_BUFFER_SIZE, format, ap );
va_end(ap);
lcdx_print_center( y, (unsigned char *)printf_buffer, mode, xoffs, yoffs);
}
 
 
 
//-----------------------------------------------------------
// lcdx_printf_center_P( y, mode, xoffs,yoffs, format, ...)
//
// Ausgabe von n-Parametern via Formattierung
// mit erweitertem xoffs,yoffs (PROGMEN-Version)
//
// Die Ausgabe wird zentriert,
//
// Parameter:
// y : Position in Char y
// mode : MNORMAL, MINVERS, ...
// xoffs,yoffs: Verschiebung in Pixel
// format : String aus PROGMEM (siehe: xprintf in utils/xstring.h)
// ... : Parameter fuer 'format'
//-----------------------------------------------------------
void lcdx_printf_center_P( uint8_t y, uint8_t mode, int8_t xoffs, int8_t yoffs, const char *format, ... )
{
va_list ap;
 
va_start( ap, format );
_xvsnprintf( true, printf_buffer, PRINTF_BUFFER_SIZE, format, ap );
va_end(ap);
lcdx_print_center( y, (unsigned char *)printf_buffer, mode, xoffs, yoffs);
}
 
 
 
//-----------------------------------------------------------
//--- lcd_print_at: Kompatibilitaet
//-----------------------------------------------------------
void lcd_print_at (uint8_t x, uint8_t y, uint8_t *text, uint8_t mode )
{
lcdx_print_at ( x, y, text, mode, 0,0);
}
 
 
//-----------------------------------------------------------
void print_display (uint8_t *text)
{
while (*text)
{
lcd_putc (lcd_xpos, lcd_ypos, *text, 0);
lcd_xpos++;
if (lcd_xpos >= 20)
{
lcd_xpos = 0;
new_line ();
}
text++;
}
}
 
 
//-----------------------------------------------------------
void print_display_at (uint8_t x, uint8_t y, uint8_t *text)
{
lcd_xpos = x;
lcd_ypos = y;
print_display (text);
}
 
 
//-----------------------------------------------------------
// + Line (draws a line from x1,y1 to x2,y2
// + Based on Bresenham line-Algorithm
// + found in the internet, modified by thkais 2007
//-----------------------------------------------------------
 
void lcd_line( unsigned char x1, unsigned char y1, unsigned char x2, unsigned char y2, uint8_t mode)
{
int x, y, count, xs, ys, xm, ym;
 
x = (int) x1;
y = (int) y1;
xs = (int) x2 - (int) x1;
ys = (int) y2 - (int) y1;
if (xs < 0)
xm = -1;
else
if (xs > 0)
xm = 1;
else
xm = 0;
if (ys < 0)
ym = -1;
else
if (ys > 0)
ym = 1;
else
ym = 0;
if (xs < 0)
xs = -xs;
 
if (ys < 0)
ys = -ys;
 
lcd_plot ((unsigned char) x, (unsigned char) y, mode);
 
if (xs > ys) // Flat Line <45 degrees
{
count = -(xs / 2);
while (x != x2)
{
count = count + ys;
x = x + xm;
if (count > 0)
{
y = y + ym;
count = count - xs;
}
lcd_plot ((unsigned char) x, (unsigned char) y, mode);
}
}
else // Line >=45 degrees
{
count =- (ys / 2);
while (y != y2)
{
count = count + xs;
y = y + ym;
if (count > 0)
{
x = x + xm;
count = count - ys;
}
lcd_plot ((unsigned char) x, (unsigned char) y, mode);
}
}
}
 
 
//-----------------------------------------------------------
// + Filled rectangle
// + x1, y1 = upper left corner
//-----------------------------------------------------------
void lcd_frect( uint8_t x1, uint8_t y1, uint8_t widthx, uint8_t widthy, uint8_t mode)
{
uint16_t x2, y2;
uint16_t i;
 
if (x1 >= DISP_W)
x1 = DISP_W - 1;
 
if (y1 >= DISP_H)
y1 = DISP_H - 1;
 
x2 = x1 + widthx;
y2 = y1 + widthy;
 
if (x2 > DISP_W)
x2 = DISP_W;
 
if (y2 > DISP_H)
y2 = DISP_H;
 
for (i = y1; i <= y2; i++)
{
lcd_line (x1, i, x2, i, mode);
}
}
 
 
//-----------------------------------------------------------
// ausgefuelltes Rechteck mit abgerundeten Ecken
//
// Hinweis:
// r (Radius) ist aktuell 'pseudo' und unterstuetzt
// nur R0 (=0), R1 (=1) oder R2 (=2=
//-----------------------------------------------------------
void lcd_frect_round( uint8_t x1, uint8_t y1, uint8_t widthx, uint8_t widthy, uint8_t mode, uint8_t r)
{
lcd_frect( x1, y1, widthx, widthy, mode);
 
switch(r)
{
case R0: break;
 
case R2:
lcd_plot( x1+1 , y1 , !mode); // Ecke links oben
lcd_plot( x1 , y1+1 , !mode);
 
lcd_plot( x1+widthx-1, y1 , !mode); // Ecke rechts oben
lcd_plot( x1+widthx , y1+1 , !mode);
 
lcd_plot( x1 , y1+widthy-1, !mode); // Ecke links unten
lcd_plot( x1+1 , y1+widthy , !mode);
 
lcd_plot( x1+widthx-1, y1+widthy , !mode); // Ecke rechts unten
lcd_plot( x1+widthx , y1+widthy-1, !mode);
 
case R1:
lcd_plot( x1 , y1 , !mode); // Ecke links oben
lcd_plot( x1+widthx , y1 , !mode); // Ecke rechts oben
lcd_plot( x1 , y1+widthy , !mode); // Ecke links unten
lcd_plot( x1+widthx , y1+widthy , !mode); // Ecke rechts unten
}
}
 
 
//-----------------------------------------------------------
// + outline of rectangle
// + x1, y1 = upper left corner
//-----------------------------------------------------------
void lcd_rect( uint8_t x1, uint8_t y1, uint8_t widthx, uint8_t widthy, uint8_t mode)
{
uint16_t x2, y2;
 
if (x1 >= DISP_W)
x1 = DISP_W - 1;
if (y1 >= DISP_H)
y1 = DISP_H - 1;
x2 = x1 + widthx;
y2 = y1 + widthy;
 
if (x2 > DISP_W)
x2 = DISP_W;
 
if (y2 > DISP_H)
y2 = DISP_H;
 
lcd_line (x1, y1, x2, y1, mode);
lcd_line (x2, y1, x2, y2, mode);
lcd_line (x2, y2, x1, y2, mode);
lcd_line (x1, y2, x1, y1, mode);
}
 
 
//-----------------------------------------------------------
// Rechteck mit mit abgerundeten Ecken
//
// Hinweis:
// r (Radius) ist aktuell 'pseudo' und unterstuetzt
// nur R0 (=0), R1 (=1) oder R2 (=2=
//-----------------------------------------------------------
void lcd_rect_round( uint8_t x1, uint8_t y1, uint8_t widthx, uint8_t widthy, uint8_t mode, uint8_t r)
{
lcd_rect( x1, y1, widthx, widthy, mode);
 
switch(r)
{
case R0: break;
 
case R2:
lcd_plot( x1+1 , y1 , !mode); // Ecke links oben
lcd_plot( x1 , y1+1 , !mode);
lcd_plot( x1+1 , y1+1 , mode);
 
lcd_plot( x1+widthx-1, y1 , !mode); // Ecke rechts oben
lcd_plot( x1+widthx , y1+1 , !mode);
lcd_plot( x1+widthx-1, y1+1 , mode);
 
lcd_plot( x1 , y1+widthy-1, !mode); // Ecke links unten
lcd_plot( x1+1 , y1+widthy , !mode);
lcd_plot( x1+1 , y1+widthy-1, mode);
 
lcd_plot( x1+widthx-1, y1+widthy , !mode); // Ecke rechts unten
lcd_plot( x1+widthx , y1+widthy-1, !mode);
lcd_plot( x1+widthx-1, y1+widthy-1, mode);
 
case R1:
lcd_plot( x1 , y1 , !mode); // Ecke links oben
lcd_plot( x1+widthx , y1 , !mode); // Ecke rechts oben
lcd_plot( x1 , y1+widthy , !mode); // Ecke links unten
lcd_plot( x1+widthx , y1+widthy , !mode); // Ecke rechts unten
}
}
 
 
//-----------------------------------------------------------
// + outline of a circle
// + Based on Bresenham-algorithm found in wikipedia
// + modified by thkais (2007)
//-----------------------------------------------------------
void lcd_circle (int16_t x0, int16_t y0, int16_t radius, uint8_t mode)
{
int16_t f = 1 - radius;
int16_t ddF_x = 0;
int16_t ddF_y = -2 * radius;
int16_t x = 0;
int16_t y = radius;
 
lcd_plot (x0, y0 + radius, mode);
lcd_plot (x0, y0 - radius, mode);
lcd_plot (x0 + radius, y0, mode);
lcd_plot (x0 - radius, y0, mode);
 
while (x < y)
{
if (f >= 0)
{
y --;
ddF_y += 2;
f += ddF_y;
}
x ++;
ddF_x += 2;
f += ddF_x + 1;
 
lcd_plot (x0 + x, y0 + y, mode);
lcd_plot (x0 - x, y0 + y, mode);
 
lcd_plot (x0 + x, y0 - y, mode);
lcd_plot (x0 - x, y0 - y, mode);
 
lcd_plot (x0 + y, y0 + x, mode);
lcd_plot (x0 - y, y0 + x, mode);
 
lcd_plot (x0 + y, y0 - x, mode);
lcd_plot (x0 - y, y0 - x, mode);
}
}
 
 
//-----------------------------------------------------------
// + filled Circle
// + modified circle-algorithm thkais (2007)
//-----------------------------------------------------------
void lcd_fcircle (int16_t x0, int16_t y0, int16_t radius,uint8_t mode)
{
int16_t f = 1 - radius;
int16_t ddF_x = 0;
int16_t ddF_y = -2 * radius;
int16_t x = 0;
int16_t y = radius;
 
lcd_line (x0, y0 + radius, x0, y0 - radius, mode);
 
lcd_line (x0 + radius, y0, x0 - radius, y0, mode);
 
while (x < y)
{
if (f >= 0)
{
y--;
ddF_y += 2;
f += ddF_y;
}
x++;
ddF_x += 2;
f += ddF_x + 1;
 
lcd_line (x0 + x, y0 + y, x0 - x, y0 + y, mode);
lcd_line (x0 + x, y0 - y, x0 - x, y0 - y, mode);
lcd_line (x0 + y, y0 + x, x0 - y, y0 + x, mode);
lcd_line (x0 + y, y0 - x, x0 - y, y0 - x, mode);
}
}
 
 
//-----------------------------------------------------------
//
void lcd_circ_line (uint8_t x, uint8_t y, uint8_t r, uint16_t deg, uint8_t mode)
{
uint8_t xc, yc;
double deg_rad;
 
deg_rad = (deg * M_PI) / 180.0;
 
yc = y - (uint8_t) round (cos (deg_rad) * (double) r);
xc = x + (uint8_t) round (sin (deg_rad) * (double) r);
lcd_line (x, y, xc, yc, mode);
}
 
 
//-----------------------------------------------------------
//
void lcd_ellipse_line (uint8_t x, uint8_t y, uint8_t rx, uint8_t ry, uint16_t deg, uint8_t mode)
{
uint8_t xc, yc;
double deg_rad;
 
deg_rad = (deg * M_PI) / 180.0;
 
yc = y - (uint8_t) round (cos (deg_rad) * (double) ry);
xc = x + (uint8_t) round (sin (deg_rad) * (double) rx);
lcd_line (x, y, xc, yc, mode);
}
 
 
//-----------------------------------------------------------
//
void lcd_ellipse (int16_t x0, int16_t y0, int16_t rx, int16_t ry, uint8_t mode)
{
const int16_t rx2 = rx * rx;
const int16_t ry2 = ry * ry;
int16_t F = round (ry2 - rx2 * ry + 0.25 * rx2);
int16_t ddF_x = 0;
int16_t ddF_y = 2 * rx2 * ry;
int16_t x = 0;
int16_t y = ry;
 
lcd_plot (x0, y0 + ry, mode);
lcd_plot (x0, y0 - ry, mode);
lcd_plot (x0 + rx, y0, mode);
lcd_plot (x0 - rx, y0, mode);
// while ( 2*ry2*x < 2*rx2*y ) { we can use ddF_x and ddF_y
while (ddF_x < ddF_y)
{
if(F >= 0)
{
y -= 1; // south
ddF_y -= 2 * rx2;
F -= ddF_y;
}
x += 1; // east
ddF_x += 2 * ry2;
F += ddF_x + ry2;
lcd_plot (x0 + x, y0 + y, mode);
lcd_plot (x0 + x, y0 - y, mode);
lcd_plot (x0 - x, y0 + y, mode);
lcd_plot (x0 - x, y0 - y, mode);
}
F = round (ry2 * (x + 0.5) * (x + 0.5) + rx2 * (y - 1) * (y - 1) - rx2 * ry2);
while(y > 0)
{
if(F <= 0)
{
x += 1; // east
ddF_x += 2 * ry2;
F += ddF_x;
}
y -= 1; // south
ddF_y -= 2 * rx2;
F += rx2 - ddF_y;
lcd_plot (x0 + x, y0 + y, mode);
lcd_plot (x0 + x, y0 - y, mode);
lcd_plot (x0 - x, y0 + y, mode);
lcd_plot (x0 - x, y0 - y, mode);
}
}
 
 
//-----------------------------------------------------------
//
void lcd_ecircle (int16_t x0, int16_t y0, int16_t radius, uint8_t mode)
{
lcd_ellipse (x0, y0, radius + 3, radius, mode);
}
 
 
//-----------------------------------------------------------
//
void lcd_ecirc_line (uint8_t x, uint8_t y, uint8_t r, uint16_t deg, uint8_t mode)
{
lcd_ellipse_line(x, y, r + 3, r, deg, mode);
}
 
 
//-----------------------------------------------------------
//
void lcd_view_font (uint8_t page)
{
int x;
int y;
 
lcd_cls ();
lcd_printp (PSTR(" 0123456789ABCDEF\r\n"), 0);
lcd_printpns_at (0, 7, PSTR(" \x1a \x1b Exit"), 0);
 
lcd_ypos = 2;
for (y = page * 4 ; y < (page * 4 + 4); y++)
{
if (y < 10)
{
lcd_putc (0, lcd_ypos, '0' + y, 0);
}
else
{
lcd_putc (0, lcd_ypos, 'A' + y - 10, 0);
}
lcd_xpos = 2;
for (x = 0; x < 16; x++)
{
lcd_putc (lcd_xpos, lcd_ypos, y * 16 + x, 0);
lcd_xpos++;
}
lcd_ypos++;
}
}
 
 
//-----------------------------------------------------------
uint8_t hdigit (uint8_t d)
{
if (d < 10)
{
return '0' + d;
}
else
{
return 'A' + d - 10;
}
}
 
 
//-----------------------------------------------------------
void lcd_print_hex_at (uint8_t x, uint8_t y, uint8_t h, uint8_t mode)
{
lcd_xpos = x;
lcd_ypos = y;
 
lcd_putc (lcd_xpos++, lcd_ypos, hdigit (h >> 4), mode);
lcd_putc (lcd_xpos, lcd_ypos, hdigit (h & 0x0f), mode);
}
 
 
//-----------------------------------------------------------
void lcd_print_hex (uint8_t h, uint8_t mode)
{
// lcd_xpos = x;
// lcd_ypos = y;
 
lcd_putc (lcd_xpos++, lcd_ypos, hdigit (h >> 4), mode);
lcd_putc (lcd_xpos++, lcd_ypos, hdigit (h & 0x0f), mode);
lcd_putc (lcd_xpos++, lcd_ypos, ' ', mode);
}
 
//##################################################################################################################################
//##################################################################################################################################
 
//-----------------------------------------------------------
// lcdx_printf_at( x,y, mode, xoffs,yoffs, format, ...)
//
// Ausgabe von n-Parametern via Formattierung
// mit erweitertem xoffs,yoffs (RAM-Version)
//
// Parameter:
// x,y : Position in Char x,y
// mode : MNORMAL, MINVERS, ...
// xoffs,yoffs: Verschiebung in Pixel
// format : String aus RAM (siehe: xprintf in utils/xstring.h)
// ... : Parameter fuer 'format'
//-----------------------------------------------------------
void lcdx_printf_at( uint8_t x, uint8_t y, uint8_t mode, int8_t xoffs, int8_t yoffs, const char *format, ... )
{
va_list ap;
 
va_start( ap, format );
// _xvsnprintf( int useprogmem, char *buffer, size_t n, const char *format, va_list ap )
_xvsnprintf( false, printf_buffer, PRINTF_BUFFER_SIZE, format, ap );
va_end(ap);
lcdx_print_at( x, y, (unsigned char *)printf_buffer, mode, xoffs, yoffs);
}
 
 
//-----------------------------------------------------------
// lcdx_printf_at_P( x,y, mode, xoffs,yoffs, format, ...)
//
// Ausgabe von n-Parametern via Formattierung
// mit erweitertem xoffs,yoffs (PROGMEN-Version)
//
// Parameter:
// x,y : Position in Char x,y
// mode : MNORMAL, MINVERS, ...
// xoffs,yoffs: Verschiebung in Pixel
// format : String aus PROGMEM (siehe: xprintf in utils/xstring.h)
// ... : Parameter fuer 'format'
//-----------------------------------------------------------
void lcdx_printf_at_P( uint8_t x, uint8_t y, uint8_t mode, int8_t xoffs, int8_t yoffs, const char *format, ... )
{
va_list ap;
 
va_start( ap, format );
_xvsnprintf( true, printf_buffer, PRINTF_BUFFER_SIZE, format, ap );
va_end(ap);
lcdx_print_at( x, y, (unsigned char *)printf_buffer, mode, xoffs, yoffs);
}
 
 
//-----------------------------------------------------------
// lcdx_printf_at( x,y, mode, xoffs,yoffs, format, ...)
//
// Ausgabe von n-Parametern via Formattierung (RAM-Version)
//
// Parameter:
// x,y : Position in Char x,y
// mode : MNORMAL, MINVERS, ...
// format : String aus RAM (siehe: xprintf in utils/xstring.h)
// ... : Parameter fuer 'format'
//-----------------------------------------------------------
void lcd_printf_at( uint8_t x, uint8_t y, uint8_t mode, const char *format, ... )
{
va_list ap;
 
va_start( ap, format );
// _xvsnprintf( int useprogmem, char *buffer, size_t n, const char *format, va_list ap )
_xvsnprintf( false, printf_buffer, PRINTF_BUFFER_SIZE, format, ap );
va_end(ap);
lcdx_print_at( x, y, (unsigned char *)printf_buffer, mode, 0,0);
}
 
 
//-----------------------------------------------------------
// lcd_printf_at_P( x,y, mode, xoffs,yoffs, format, ...)
//
// Ausgabe von n-Parametern via Formattierung (PROGMEN-Version)
//
// Parameter:
// x,y : Position in Char x,y
// mode : MNORMAL, MINVERS, ...
// format : String aus PROGMEM (siehe: xprintf in utils/xstring.h)
// ... : Parameter fuer 'format'
//-----------------------------------------------------------
void lcd_printf_at_P( uint8_t x, uint8_t y, uint8_t mode, const char *format, ... )
{
va_list ap;
 
va_start( ap, format );
_xvsnprintf( true, printf_buffer, PRINTF_BUFFER_SIZE, format, ap );
va_end(ap);
lcdx_print_at( x, y, (unsigned char *)printf_buffer, mode, 0,0);
}
 
 
 
//##################################################################################################################################
//##################################################################################################################################
 
 
//-----------------------------------------------------------
void lcd_write_number_u (uint8_t number)
{
uint8_t num = 100;
uint8_t started = 0;
 
while (num > 0)
{
uint8_t b = number / num;
if (b > 0 || started || num == 1)
{
lcd_putc (lcd_xpos++, lcd_ypos, '0' + b, 0);
started = 1;
}
number -= b * num;
 
num /= 10;
}
}
 
 
//-----------------------------------------------------------
void lcd_write_number_u_at (uint8_t x, uint8_t y, uint8_t number)
{
lcd_xpos = x;
lcd_ypos = y;
lcd_write_number_u (number);
}
 
 
//-----------------------------------------------------------
// numtype: 'd' oder 'u'
//
// Ergebnis: ein String in format_buffer
// -> "%4d" "%4.2d" "%03.1d" "%4u" usw...
//-----------------------------------------------------------
void make_number_format( char numtype, int16_t length, int16_t decimals, uint8_t pad )
{
register char *p;
register char *psrc;
 
p = format_buffer;
*p = '%'; p++; // start '%'
if(pad) { *p = '0'; p++; } // pad '0'
 
itoa( length, s, 10 );
psrc = s; while(*psrc) *p++ = *psrc++; // vorkomma
 
if( decimals > 0 )
{
*p = '.'; p++; // punkt '.'
itoa( decimals, s, 10 );
psrc = s; while(*psrc) *p++ = *psrc++; // nachkomma
}
 
*p = numtype; p++; // 'd' oder 'u'
*p = 0;
}
 
 
//-----------------------------------------------------------
// Write only some digits of a unsigned <number> at <x>/<y> to MAX7456 display memory
// <num> represents the largest multiple of 10 that will still be displayable as
// the first digit, so num = 10 will be 0-99 and so on
// <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 007 instead of 7
//
void writex_ndigit_number_u (uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
make_number_format( 'u', length, 0, pad ); // ergebnis in: format_buffer
lcdx_printf_at( x, y, mode, xoffs, yoffs, format_buffer, number );
}
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void write_ndigit_number_u (uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad, uint8_t mode)
{
writex_ndigit_number_u( x, y, number, length, pad, mode, 0,0);
}
 
 
//-----------------------------------------------------------
// Write only some digits of a signed <number> at <x>/<y> to MAX7456 display memory
// <num> represents the largest multiple of 10 that will still be displayable as
// the first digit, so num = 10 will be 0-99 and so on
// <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 007 instead of 7
//
void writex_ndigit_number_s (uint8_t x, uint8_t y, int16_t number, int16_t length, uint8_t pad, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
make_number_format( 'd', length, 0, pad ); // ergebnis in: format_buffer
lcdx_printf_at( x, y, mode, xoffs, yoffs, format_buffer, number );
}
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void write_ndigit_number_s (uint8_t x, uint8_t y, int16_t number, int16_t length, uint8_t pad, uint8_t mode)
{
writex_ndigit_number_s (x, y, number, length, pad, mode, 0,0);
}
 
 
//-----------------------------------------------------------
// Write only some digits of a unsigned <number> at <x>/<y> to MAX7456 display memory
// as /10th of the value
// <num> represents the largest multiple of 10 that will still be displayable as
// the first digit, so num = 10 will be 0-99 and so on
// <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 007 instead of 7
//
void writex_ndigit_number_u_10th( uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
make_number_format( 'u', length-1, 1, pad ); // ergebnis in: format_buffer
lcdx_printf_at( x, y, mode, xoffs, yoffs, format_buffer, number );
}
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void write_ndigit_number_u_10th( uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad, uint8_t mode)
{
writex_ndigit_number_u_10th( x, y, number, length, pad, mode, 0,0);
}
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void writex_ndigit_number_u_100th( uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
make_number_format( 'u', length-2, 2, pad ); // ergebnis in: format_buffer
lcdx_printf_at( x, y, mode, xoffs, yoffs, format_buffer, number );
}
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void write_ndigit_number_u_100th( uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad)
{
writex_ndigit_number_u_100th( x, y, number, length, pad, MNORMAL, 0,0);
}
 
 
//-----------------------------------------------------------
// Write only some digits of a signed <number> at <x>/<y> to MAX7456 display memory
// as /10th of the value
// <num> represents the largest multiple of 10 that will still be displayable as
// the first digit, so num = 10 will be 0-99 and so on
// <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 007 instead of 7
//
void writex_ndigit_number_s_10th (uint8_t x, uint8_t y, int16_t number, int16_t length, uint8_t pad, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
make_number_format( 'd', length-1, 1, pad ); // ergebnis in: format_buffer
lcdx_printf_at( x, y, mode, xoffs, yoffs, format_buffer, number );
}
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void write_ndigit_number_s_10th (uint8_t x, uint8_t y, int16_t number, int16_t length, uint8_t pad, uint8_t mode)
{
writex_ndigit_number_s_10th ( x, y, number, length, pad, mode, 0,0);
 
}
 
 
//-----------------------------------------------------------
// write <seconds> as human readable time at <x>/<y> to MAX7456 display mem
//
void writex_time( uint8_t x, uint8_t y, uint16_t seconds, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
uint16_t min = seconds / 60;
seconds -= min * 60;
 
lcdx_printf_at( x, y, mode, xoffs, yoffs, "%02u:%02u", min, seconds);
/*
writex_ndigit_number_u (x, y, min, 2, 0,mode, xoffs,yoffs);
lcdx_putc (x + 2, y, ':', mode, xoffs,yoffs);
writex_ndigit_number_u (x + 3, y, seconds, 2, 1,mode, xoffs,yoffs);
*/
}
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void write_time( uint8_t x, uint8_t y, uint16_t seconds)
{
writex_time( x, y, seconds, 0, 0,0);
}
 
 
//--------------------------------------------------------------
// writex_datetime_time()
//
// Anzeigeformat: 'hh:mm:ss'
//
// datetime : vom Typ PKTdatetime_t
//--------------------------------------------------------------
void writex_datetime_time( uint8_t x, uint8_t y, PKTdatetime_t datetime, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
PKTdatetime_t dtlocal;
 
UTCdatetime2local( &dtlocal, &datetime );
lcdx_printf_at( x, y, mode, xoffs, yoffs, "%02u:%02u:%02u", (uint8_t)(dtlocal.seconds/3600), (uint8_t)((dtlocal.seconds/60)%60), (uint8_t)(dtlocal.seconds%60));
}
 
 
//--------------------------------------------------------------
// writex_datetime_date()
//
// Anzeigeformat: 'dd.mm.yyyy' (keine Unterstuetzung von anderen Formaten aus aller Welt)
//
// datetime : vom Typ PKTdatetime_t
//--------------------------------------------------------------
void writex_datetime_date( uint8_t x, uint8_t y, PKTdatetime_t datetime, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
PKTdatetime_t dtlocal;
 
if( datetime.year > 0 )
{
UTCdatetime2local( &dtlocal, &datetime );
lcdx_printf_at( x, y, mode, xoffs, yoffs, "%02u.%02u.%04u", dtlocal.day, dtlocal.month, dtlocal.year);
}
else
{
// keine UTCZeit -> keine Datumsanzeige
lcdx_printp_at( x, y, PSTR(" . . "), mode, xoffs,yoffs);
}
}
 
 
//-----------------------------------------------------------
// writes a single gps-pos
//-----------------------------------------------------------
void writex_gpspos( uint8_t x, uint8_t y, int32_t GPSpos, uint8_t mode, int8_t xoffs, int8_t yoffs )
{
lcdx_printf_at( x, y, mode, xoffs, yoffs, "%3.5ld", GPSpos/100);
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Show_PKTError_NoRAM(void)
{
lcd_cls();
lcd_rect( 8, 8, 127-16, 6*8, 1);
 
// 123456789012345678901
lcd_printp_at( 2,2 , PSTR("** OUT OF RAM **"), MINVERS);
lcd_printp_at( 2,4 , PSTR("this function is"), MNORMAL);
lcd_printp_at( 2,5 , PSTR("not available!"), MNORMAL);
 
while ( !( (get_key_press (1 << KEY_ENTER)) || (get_key_press (1 << KEY_ESC)) || (get_key_press (1 << KEY_PLUS)) || (get_key_press (1 << KEY_MINUS)) ) );
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void ShowTitle_P( const char *title, uint8_t clearscreen )
{
if( clearscreen )
lcd_cls();
 
lcd_frect( 0, 0, 127, 7, 1); // Titel: Invers
 
if( strlen_P(title) < 17 )
show_Lipo();
 
lcd_printp_at ( 1, 0, title , MINVERS);
}
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void Popup_Draw( uint8_t heigthC )
{
uint8_t y, h;
 
h = heigthC*8;
y = 63-h;
 
//lcd_frect( 0, (hC*8)-6, 127, 63-(hC*8)+6, 1); // Box white
lcd_frect( 0, y-8, 127, 3, 0); // Box clear
lcd_frect( 0, y-4, 127, h+4, 1); // Box fill white
lcd_plot ( 0, y-4, 0); // Ecke links oben 1
lcd_plot ( 127, y-4, 0); // Ecke rechts oben 1
 
lcd_line ( 1, y-4, 0, y-3, 0); // Ecke links oben 2
lcd_line ( 127-1, y-4, 127, y-3, 0); // Ecke rechts oben 2
}
 
 
 
//-----------------------------------------------------------
// lcdx_cls_rowwidth( y, width, mode, xoffs,yoffs )
//
// loescht eine Zeile auf dem Display
// mode ist kompatibel zu MNORMALX, MINVERSX
//
// width: in Zeichen
//-----------------------------------------------------------
void lcdx_cls_rowwidth( uint8_t y, uint8_t width, uint8_t mode, int8_t xoffs, int8_t yoffs )
{
int8_t xadd = 0;
int8_t yadd = 0;
 
if( mode == MNORMALX || mode == MINVERSX )
{
if( xoffs > 0 ) xadd = 1;
if( (y*8)+yoffs > 0 ) yadd = 1;
 
if( mode == MNORMALX )
mode = MNORMAL;
else
mode = MINVERS;
}
 
lcd_frect( xoffs-xadd, (y*8)+yoffs-yadd, (width*6)+xadd, 7+yadd, (mode == MNORMAL ? 0 : 1) ); // Zeile loeschen
}
 
 
//-----------------------------------------------------------
// lcdx_cls_row( y, mode, yoffs )
//
// loescht eine Zeile auf dem Display
// mode ist kompatibel zu MNORMALX, MINVERSX
//-----------------------------------------------------------
void lcdx_cls_row( uint8_t y, uint8_t mode, int8_t yoffs )
{
lcdx_cls_rowwidth( y, 21, mode, 0, yoffs );
}
 
 
 
//####################################################################################
//####################################################################################
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcd_setpos( uint8_t x, uint8_t y )
{
lcd_xpos = x;
lcd_ypos = y;
}
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void lcd_print_char( uint8_t c, uint8_t mode )
{
switch( c )
{
case 0x0D: lcd_xpos = 0;
break;
 
case 0x0A: new_line();
break;
 
default: lcdx_putc (lcd_xpos, lcd_ypos, c, mode, 0,0);
lcd_xpos++;
if( lcd_xpos > 20 )
{
lcd_xpos = 0;
new_line();
}
break;
}
}
 
 
//----------------------------------------------------
// gibt einen Linefeed aus (CR+LF)
//----------------------------------------------------
void lcd_print_LF( void )
{
lcd_print_char( 0x0D, MNORMAL );
lcd_print_char( 0x0A, MNORMAL );
}
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/lcd/lcd.h
0,0 → 1,425
/*****************************************************************************
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* - original LCD control by Thomas "thkais" Kaiser *
* - special number formating routines taken from C-OSD *
* from Claas Anders "CaScAdE" Rathje *
* - some extension, ellipse and circ_line by Peter "woggle" Mack *
* Thanks to Oliver Schwaneberg for adding several functions to this library!*
* *
* Author: Jan Michel (jan at mueschelsoft dot de) *
* License: GNU General Public License, version 3 *
* Version: v0.93 September 2010 *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
*****************************************************************************/
 
//############################################################################
//# HISTORY lcd.h
//#
//# 27.06.2014 OG
//# - add: define MINVERSX, MNORMALX
//#
//# 11.06.2014 OG
//# - add: lcd_set_contrast()
//#
//# 04.06.2014 OG
//# - add: lcdx_cls_rowwidth()
//#
//# 02.05.2014 OG
//# - add: Popup_Draw() (ehemals in osd.c)
//#
//# 13.04.2014 OG
//# - add: lcd_print_LF()
//#
//# 11.04.2014 OG
//# - add: lcdx_cls_row()
//#
//# 08.04.2014 OG
//# - add: lcdx_printf_center(), lcdx_printf_center_P()
//#
//# 07.04.2014 OG
//# - add: lcd_setpos(), lcd_print_char()
//#
//# 04.04.2014 OG
//# - add: ShowTitle_P()
//#
//# 28.02.2014 OG
//# - del: show_baudrate()
//#
//# 16.02.2014 OG
//# - add: lcdx_printp_center(), lcdx_print_center()
//#
//# 13.02.2014 OG
//# - add: R# define's fuer lcd_rect_round()
//#
//# 12.02.2014 OG
//# - add: lcd_frect_round()
//# - add: lcd_rect_round()
//#
//# 03.02.2014 OG
//# - fix: bei writex_ndigit_number_u_100th() fehlte der Parameter 'mode'
//#
//# 07.07.2013 OG
//# - add: SYMBOL_CHECK
//#
//# 11.06.2013 OG
//# - add: SYMBOL_AVG, SYMBOL_MIN, SYMBOL_MAX fuer OSDDATA Anzeige
//# - del: Antennen-Symbol von OSD_General (wird wieder gezeichnet)
//#
//# 15.05.2013 OG
//# - add: define SYMBOL_SMALLDEGREE, SYMBOL_RCQUALITY
//#
//# 03.05.2013 OG
//# - fix: writex_gpspos() - Anzeige negativer Koordinaten
//# - fix: Anzeigefehler writex_datetime_time()
//# - chg: writex_datetime_date() & writex_datetime_time() Parameter
//# 'timeoffset' entfernt da das durch PKT-Config geregelt werden soll
//#
//# 28.04.2013 OG
//# - add: lcdx_printf_at(), lcdx_printf_at_P()
//# lcd_printf_at(), lcd_printf_at_P()
//# - del: write_gps_pos()
//#
//# 22.03.2013 OG
//# - siehe lcd.c
//#
//# 11.03.2013 OG
//# - siehe lcd.c
//#
//# 07.03.2013 OG
//# - siehe lcd.c
//#
//# 06.03.2013 OG
//# - add: extended Funktionen lcdx_... / writex...
//############################################################################
 
 
#ifndef _LCD_H
#define _LCD_H
 
#include <stdarg.h> // Notwendig! (OG)
#include "../timer/timer.h"
 
#define MNORMAL 0 // Zeichendarstellung: Normal
#define MINVERS 2 // Zeichendarstellung: Invers
#define MBIG 3 // OBSOLETE! - Zeichendarstellung: grosser Zeichensatz (8x8) Normal
#define MBIGINVERS 4 // OBSOLETE! - Zeichendarstellung: grosser Zeichensatz (8x8) Invers
#define MNORMALX 5 // Zeichendarstellung: Normal - oben und Links wird eine 1 Pixel Linie gezogen
#define MINVERSX 6 // Zeichendarstellung: Invers - oben und Links wird eine 1 Pixel Linie gezogen
 
 
// fuer lcd_rect_round()
#define R0 0 // Radius 0
#define R1 1 // Radius 1
#define R2 2 // Radius 2
 
 
#define SYMBOL_AVG 10
#define SYMBOL_MAX 13
#define SYMBOL_MIN 16
#define SYMBOL_SMALLDEGREE 11
#define SYMBOL_BIGDEGREE 30
#define SYMBOL_CHECK 31
 
//------------------------------------------------------------------------------------
void lcdx_printf_at( uint8_t x, uint8_t y, uint8_t mode, int8_t xoffs, int8_t yoffs, const char *format, ... );
void lcdx_printf_at_P( uint8_t x, uint8_t y, uint8_t mode, int8_t xoffs, int8_t yoffs, const char *format, ... );
void lcd_printf_at( uint8_t x, uint8_t y, uint8_t mode, const char *format, ... );
void lcd_printf_at_P( uint8_t x, uint8_t y, uint8_t mode, const char *format, ... );
void lcdx_printf_center( uint8_t y, uint8_t mode, int8_t xoffs, int8_t yoffs, const char *format, ... );
void lcdx_printf_center_P( uint8_t y, uint8_t mode, int8_t xoffs, int8_t yoffs, const char *format, ... );
 
 
//------------------------------------------------------------------------------------
// X-tended
void lcdx_putc( uint8_t x, uint8_t y, uint8_t c, uint8_t mode, int8_t xoffs, int8_t yoffs );
void lcdx_print (uint8_t *text, uint8_t mode, int8_t xoffs, int8_t yoffs);
void lcdx_print_at (uint8_t x, uint8_t y, uint8_t *text, uint8_t mode, int8_t xoffs, int8_t yoffs);
void lcdx_printp (const char *text, uint8_t mode, int8_t xoffs, int8_t yoffs);
void lcdx_printp_at (uint8_t x, uint8_t y, const char *text, uint8_t mode, int8_t xoffs, int8_t yoffs);
 
void writex_ndigit_number_s (uint8_t x, uint8_t y, int16_t number, int16_t length, uint8_t pad, uint8_t mode, int8_t xoffs, int8_t yoffs);
void writex_ndigit_number_s_10th (uint8_t x, uint8_t y, int16_t number, int16_t length, uint8_t pad, uint8_t mode, int8_t xoffs, int8_t yoffs);
 
void writex_ndigit_number_u (uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad, uint8_t mode, int8_t xoffs, int8_t yoffs);
void writex_ndigit_number_u_10th (uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad, uint8_t mode, int8_t xoffs, int8_t yoffs);
void writex_ndigit_number_u_100th( uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad, uint8_t mode, int8_t xoffs, int8_t yoffs);
 
void lcdx_puts_at(uint8_t x, uint8_t y, const char *s, uint8_t mode, int8_t xoffs, int8_t yoffs);
void writex_time (uint8_t x, uint8_t y, uint16_t seconds, uint8_t mode, int8_t xoffs, int8_t yoffs);
//void writex_gpspos( uint8_t x, uint8_t y, uint32_t GPSpos, uint8_t mode, int8_t xoffs, int8_t yoffs );
void writex_gpspos( uint8_t x, uint8_t y, int32_t GPSpos, uint8_t mode, int8_t xoffs, int8_t yoffs );
 
void writex_datetime_time( uint8_t x, uint8_t y, PKTdatetime_t datetime, uint8_t mode, int8_t xoffs, int8_t yoffs);
void writex_datetime_date( uint8_t x, uint8_t y, PKTdatetime_t datetime, uint8_t mode, int8_t xoffs, int8_t yoffs);
 
void Show_PKTError_NoRAM(void);
void ShowTitle_P( const char *title, uint8_t clearscreen );
 
 
//------------------------------------------------------------------------------------
void lcd_rect_round( uint8_t x1, uint8_t y1, uint8_t widthx, uint8_t widthy, uint8_t mode, uint8_t r);
void lcd_frect_round( uint8_t x1, uint8_t y1, uint8_t widthx, uint8_t widthy, uint8_t mode, uint8_t r);
 
void lcdx_print_center( uint8_t y, uint8_t *text, uint8_t mode, int8_t xoffs, int8_t yoffs);
void lcdx_printp_center( uint8_t y, const char *text, uint8_t mode, int8_t xoffs, int8_t yoffs);
 
void lcdx_cls_row( uint8_t y, uint8_t mode, int8_t yoffs );
void lcdx_cls_rowwidth( uint8_t y, uint8_t width, uint8_t mode, int8_t xoffs, int8_t yoffs );
 
void lcd_setpos( uint8_t x, uint8_t y );
void lcd_print_char( uint8_t c, uint8_t mode );
void lcd_print_LF( void );
 
void Popup_Draw( uint8_t heigthC );
 
/*
 
//-----------------------------------------------------------------------------
// Command Codes
//-----------------------------------------------------------------------------
//1: Display on/off
#define LCD_DISPLAY_ON 0xAF //switch display on
#define LCD_DISPLAY_OFF 0xAE //switch display off
 
//2: display start line set (lower 6 bits select first line on lcd from 64 lines in memory)
#define LCD_START_LINE 0x40
 
//3: Page address set (lower 4 bits select one of 8 pages)
#define LCD_PAGE_ADDRESS 0xB0
 
//4: column address (lower 4 bits are upper / lower nibble of column address)
#define LCD_COL_ADDRESS_MSB 0x10
#define LCD_COL_ADDRESS_LSB 0x00 //second part of column address
 
//8: select orientation (black side of the display should be further away from viewer)
#define LCD_BOTTOMVIEW 0xA1 //6 o'clock view
#define LCD_TOPVIEW 0xA0 //12 o'clock view
 
//9: select normal (white background, black pixels) or reverse (black background, white pixels) mode
#define LCD_DISPLAY_POSITIVE 0xA6 //not inverted mode
#define LCD_DISPLAY_INVERTED 0xA7 //inverted display
 
//10: show memory content or switch all pixels on
#define LCD_SHOW_NORMAL 0xA4 //show dram content
#define LCD_SHOW_ALL_POINTS 0xA5 //show all points
 
//11: lcd bias set
#define LCD_BIAS_1_9 0xA2
#define LCD_BIAS_1_7 0xA3
 
//14: Reset Controller
#define LCD_RESET_CMD 0xE2
 
//15: output mode select (turns display upside-down)
#define LCD_SCAN_DIR_NORMAL 0xC0 //normal scan direction
#define LCD_SCAN_DIR_REVERSE 0xC8 //reversed scan direction
 
//16: power control set (lower 3 bits select operating mode)
//Bit 0: Voltage follower on/off - Bit 1: Voltage regulator on/off - Bit 2: Booster circuit on/off
#define LCD_POWER_CONTROL 0x28 //base command
#define LCD_POWER_LOW_POWER 0x2F
#define LCD_POWER_WIDE_RANGE 0x2F
#define LCD_POWER_LOW_VOLTAGE 0x2B
 
//17: voltage regulator resistor ratio set (lower 3 bits select ratio)
//selects lcd voltage - 000 is low (~ -2V), 111 is high (~ - 10V), also depending on volume mode. Datasheet suggests 011
#define LCD_VOLTAGE 0x20
 
//18: Volume mode set (2-byte command, lower 6 bits in second word select value, datasheet suggests 0x1F)
#define LCD_VOLUME_MODE_1 0x81
#define LCD_VOLUME_MODE_2 0x00
 
//#if DISPLAY_TYPE == 128 || DISPLAY_TYPE == 132
//19: static indicator (2-byte command), first on/off, then blinking mode
#define LCD_INDICATOR_ON 0xAD //static indicator on
#define LCD_INDICATOR_OFF 0xAC //static indicator off
#define LCD_INDICATOR_MODE_OFF 0x00
#define LCD_INDICATOR_MODE_1HZ 0x01
#define LCD_INDICATOR_MODE_2HZ 0x10
#define LCD_INDICATOR_MODE_ON 0x11
 
//20: booster ratio set (2-byte command)
#define LCD_BOOSTER_SET 0xF8 //set booster ratio
#define LCD_BOOSTER_234 0x00 //2x-4x
#define LCD_BOOSTER_5 0x01 //5x
#define LCD_BOOSTER_6 0x03 //6x
//#endif
 
//22: NOP command
#define LCD_NOP 0xE3
 
//#if DISPLAY_TYPE == 102
////25: advanced program control
//#define LCD_ADV_PROG_CTRL 0xFA
//#define LCD_ADV_PROG_CTRL2 0x10
//#endif
 
//-----------------------------------------------------------------------------
// Makros to execute commands
//-----------------------------------------------------------------------------
 
#define LCD_SWITCH_ON() lcd_command(LCD_DISPLAY_ON)
#define LCD_SWITCH_OFF() lcd_command(LCD_DISPLAY_OFF)
#define LCD_SET_FIRST_LINE(i) lcd_command(LCD_START_LINE | ((i) & 0x3F))
#define LCD_SET_PAGE_ADDR(i) lcd_command(LCD_PAGE_ADDRESS | ((i) & 0x0F))
#define LCD_SET_COLUMN_ADDR(i) lcd_command(LCD_COL_ADDRESS_MSB | ((i>>4) & 0x0F)); \
lcd_command(LCD_COL_ADDRESS_LSB | ((i) & 0x0F))
#define LCD_GOTO_ADDRESS(page,col); lcd_command(LCD_PAGE_ADDRESS | ((page) & 0x0F)); \
lcd_command(LCD_COL_ADDRESS_MSB | ((col>>4) & 0x0F)); \
lcd_command(LCD_COL_ADDRESS_LSB | ((col) & 0x0F));
 
#define LCD_SET_BOTTOM_VIEW() lcd_command(LCD_BOTTOMVIEW)
#define LCD_SET_TOP_VIEW() lcd_command(LCD_TOPVIEW)
#define LCD_SET_MODE_POSITIVE() lcd_command(LCD_DISPLAY_POSITIVE)
#define LCD_SET_MODE_INVERTED() lcd_command(LCD_DISPLAY_INVERTED)
#define LCD_SHOW_ALL_PIXELS_ON() lcd_command(LCD_SHOW_ALL_POINTS)
#define LCD_SHOW_ALL_PIXELS_OFF() lcd_command(LCD_SHOW_NORMAL)
#define LCD_SET_BIAS_RATIO_1_7() lcd_command(LCD_BIAS_1_7)
#define LCD_SET_BIAS_RATIO_1_9() lcd_command(LCD_BIAS_1_9)
#define LCD_SEND_RESET() lcd_command(LCD_RESET_CMD)
#define LCD_ORIENTATION_NORMAL() lcd_command(LCD_SCAN_DIR_NORMAL)
#define LCD_ORIENTATION_UPSIDEDOWN() lcd_command(LCD_SCAN_DIR_REVERSE)
#define LCD_SET_POWER_CONTROL(i) lcd_command(LCD_POWER_CONTROL | ((i) & 0x07))
#define LCD_SET_LOW_POWER() lcd_command(LCD_POWER_LOW_POWER)
#define LCD_SET_WIDE_RANGE() lcd_command(LCD_POWER_WIDE_RANGE)
#define LCD_SET_LOW_VOLTAGE() lcd_command(LCD_POWER_LOW_VOLTAGE)
#define LCD_SET_BIAS_VOLTAGE(i) lcd_command(LCD_VOLTAGE | ((i) & 0x07))
#define LCD_SET_VOLUME_MODE(i) lcd_command(LCD_VOLUME_MODE_1); \
lcd_command(LCD_VOLUME_MODE_2 | ((i) & 0x3F))
 
//#if DISPLAY_TYPE == 128 || DISPLAY_TYPE == 132
#define LCD_SET_INDICATOR_OFF() lcd_command(LCD_INDICATOR_OFF); \
lcd_command(LCD_INDICATOR_MODE_OFF)
#define LCD_SET_INDICATOR_STATIC() lcd_command(LCD_INDICATOR_ON); \
lcd_command(LCD_INDICATOR_MODE_ON)
#define LCD_SET_INDICATOR_1HZ() lcd_command(LCD_INDICATOR_ON); \
lcd_command(LCD_INDICATOR_MODE_1HZ)
#define LCD_SET_INDICATOR_2HZ() lcd_command(LCD_INDICATOR_ON); \
lcd_command(LCD_INDICATOR_MODE_2HZ)
#define LCD_SET_INDICATOR(i,j) lcd_command(LCD_INDICATOR_OFF | ((i) & 1)); \
lcd_command(((j) & 2))
#define LCD_SLEEP_MODE lcd_command(LCD_INDICATOR_OFF); \
lcd_command(LCD_DISPLAY_OFF); \
lcd_command(LCD_SHOW_ALL_POINTS)
//#endif
 
//#if DISPLAY_TYPE == 102
//#define LCD_TEMPCOMP_HIGH 0x80
//#define LCD_COLWRAP 0x02
//#define LCD_PAGEWRAP 0x01
//#define LCD_SET_ADV_PROG_CTRL(i) lcd_command(LCD_ADV_PROG_CTRL);
// lcd_command(LCD_ADV_PROG_CTRL2 & i)
//#endif
 
*/
 
 
 
extern volatile uint8_t LCD_ORIENTATION;
 
//#define LCD_LINES 8
//#define LCD_COLS 21
 
extern uint8_t lcd_xpos;
extern uint8_t lcd_ypos;
 
void lcd_set_contrast( uint8_t value );
void lcd_command(uint8_t cmd);
void send_byte (uint8_t data);
void LCD_Init (uint8_t LCD_Mode);
void new_line (void);
void lcd_puts_at(uint8_t x, uint8_t y,const char *s, uint8_t mode );
void lcd_putc (uint8_t x, uint8_t y, uint8_t c, uint8_t mode);
void send_byte (uint8_t data);
void lcd_print (uint8_t *text, uint8_t mode);
void lcd_print_at (uint8_t x, uint8_t y, uint8_t *text, uint8_t mode);
 
void lcd_printp (const char *text, uint8_t mode);
void lcd_printp_at (uint8_t x, uint8_t y, const char *text, uint8_t mode);
void lcd_printpns (const char *text, uint8_t mode);
void lcd_printpns_at (uint8_t x, uint8_t y, const char *text, uint8_t mode);
void lcd_cls (void);
void lcd_cls_line (uint8_t x, uint8_t y, uint8_t w);
 
void print_display (uint8_t *text);
void print_display_at (uint8_t x, uint8_t y, uint8_t *text);
void copy_line (uint8_t y);
void paste_line (uint8_t y);
 
void lcd_plot (uint8_t x, uint8_t y, uint8_t mode);
void lcd_line (unsigned char x1, unsigned char y1, unsigned char x2, unsigned char y2, uint8_t mode);
void lcd_rect (uint8_t x1, uint8_t y1, uint8_t widthx, uint8_t widthy, uint8_t mode);
void lcd_frect (uint8_t x1, uint8_t y1, uint8_t widthx, uint8_t widthy, uint8_t mode);
void lcd_circle (int16_t x0, int16_t y0, int16_t radius, uint8_t mode);
void lcd_fcircle (int16_t x0, int16_t y0, int16_t radius, uint8_t mode);
void lcd_circ_line (uint8_t x, uint8_t y, uint8_t r, uint16_t deg, uint8_t mode);
 
void lcd_ellipse (int16_t x0, int16_t y0, int16_t rx, int16_t ry, uint8_t mode);
void lcd_ellipse_line (uint8_t x, uint8_t y, uint8_t rx, uint8_t ry, uint16_t deg, uint8_t mode);
 
void lcd_ecircle (int16_t x0, int16_t y0, int16_t radius, uint8_t mode);
void lcd_ecirc_line (uint8_t x, uint8_t y, uint8_t r, uint16_t deg, uint8_t mode);
 
void lcd_view_font (uint8_t page);
void lcd_print_hex_at (uint8_t x, uint8_t y, uint8_t h, uint8_t mode);
 
void lcd_write_number_u (uint8_t number);
void lcd_write_number_u_at (uint8_t x, uint8_t y, uint8_t number);
void lcd_print_hex (uint8_t h, uint8_t mode);
/**
* Write only some digits of a unsigned <number> at <x>/<y>
* <length> represents the length to rightbound the number
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 007 instead of 7
*/
void write_ndigit_number_u (uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad,uint8_t mode);
 
/**
* Write only some digits of a signed <number> at <x>/<y>
* <length> represents the length to rightbound the number
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 007 instead of 7
*/
 
void write_ndigit_number_s (uint8_t x, uint8_t y, int16_t number, int16_t length, uint8_t pad, uint8_t mode);
 
/**
* Write only some digits of a unsigned <number> at <x>/<y> as /10th of the value
* <length> represents the length to rightbound the number
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 00.7 instead of .7
*/
void write_ndigit_number_u_10th (uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad, uint8_t mode);
 
/**
* Write only some digits of a unsigned <number> at <x>/<y> as /100th of the value
* <length> represents the length to rightbound the number
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 00.7 instead of .7
*/
void write_ndigit_number_u_100th (uint8_t x, uint8_t y, uint16_t number, int16_t length, uint8_t pad);
 
/**
* Write only some digits of a signed <number> at <x>/<y> as /10th of the value
* <length> represents the length to rightbound the number
* <pad> = 1 will cause blank spaced to be filled up with zeros e.g. 00.7 instead of .7
*/
void write_ndigit_number_s_10th (uint8_t x, uint8_t y, int16_t number, int16_t length, uint8_t pad, uint8_t mode);
 
/**
* write <seconds> as human readable time at <x>/<y>
*/
void write_time (uint8_t x, uint8_t y, uint16_t seconds);
 
 
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/lcd
Property changes:
Added: svn:ignore
+_doc
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/lipo/lipo.c
0,0 → 1,178
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* based on the key handling by Peter Dannegger *
* see www.mikrocontroller.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY lipo.c
//#
//# 15.06.2014 OG
//# - fix; show_Lipo() - wenn die Spannung unter 3.20 Volt ging, wurde wieder
//# ein voller Akkubalken angezeigt aufgrund einer Subtraktion - fixed
//#
//# 21.02.2014 OG
//# - chg: show_Lipo() neu geschrieben - etwas smarter, ein paar Bytes kleiner
//#
//# 20.02.2014 OG
//# - chg: Codeformattierungen
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <util/delay.h>
#include <avr/interrupt.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include "../main.h"
#include "../lcd/lcd.h"
#include "lipo.h"
#include "../eeprom/eeprom.h"
 
 
// Global variables
double accumulator = 0; //!< Accumulated 10-bit samples
double Vin = 0; //!< 16-bit float number result
short temp = 0; //!< Temporary variable
short samples = 0; //!< Number of conversions
uint16_t volt_avg = 0;
 
 
 
//--------------------------------------------------------------
//! ADC interrupt routine
//--------------------------------------------------------------
ISR (ADC_vect)
{
accumulator += ADCW;
samples++;
 
if( samples>4095 )
{
oversampled();
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void ADC_Init (void)
{
DDRA &= ~(1<<DDA1); // MartinR
PORTA &= ~(1<<PORTA1); // MartinR
ADMUX = (0<<REFS1) | (1<<REFS0); // externe 5V Referenzspannung nutzen
ADMUX = (ADMUX & ~(0x1F)) | (1 & 0x1F); // ADC1 verwenden
ADCSRA = (1<<ADEN)|(1<<ADIE)|(1<<ADSC)|(1<<ADATE)|(1<<ADPS2)|(1<<ADPS1)|(1<<ADPS0); // Prescaler 128, Freilaufend, Interrupte frei
}
 
 
 
 
//--------------------------------------------------------------
// Error compensation, Scaling 16-bit result, Rounding up,
// Calculate 16-bit result, Resets variables
//
// Quelle AVR121: Enhancing ADC resolution by versampling
//--------------------------------------------------------------
void oversampled(void)
{
cli();
accumulator += Config.Lipo_UOffset; //5150 Offset error compensation
 
// accumulator *= 0.9993; // Gain error compensation
accumulator *= 0.9600; //0.9800 Gain error compensation
temp=(int)accumulator%64;
accumulator/=64; // Scaling the answer
 
if(temp>=32)
{
accumulator += 1; // Round up
}
 
// Vin = (accumulator/65536)*4.910; // Calculating 16-bit result
 
Vin =accumulator/7.5;
volt_avg = Vin;
 
// write_ndigit_number_u(0, 3, Vin, 5, 0,0);
// write_ndigit_number_u(0, 4, volt_avg, 5, 0,0);
 
samples = 0;
accumulator = 0;
 
sei();
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void show_Lipo( void )
{
int16_t w = 0;
 
//--------------------------------------------
// Batterie Symbol zeichnen
//--------------------------------------------
lcd_rect(104, 0, 23, 7, 1); // Rahmen aussen
lcd_rect(105, 1, 21, 5, 0); // Rahmen innen
lcd_frect(102, 0, 1, 7, 0); // ganz links etwas loeschen
lcd_rect(103,2,1,3,1); // Batterie "Kappe"
 
 
//--------------------------------------------
// Batterie Balken berechnen / zeichnen
//--------------------------------------------
//
// Config.PKT_Accutyp
// true = LiPO Akku mit max. 4.2 Volt (420)
// false = LiON Akku mit max. 4.1 Volt (410)
 
if( volt_avg > 320 )
{
w = (volt_avg-320)/(Config.PKT_Accutyp ? 4.8 : 4.5); // die Faktoren 4.8 (kann bis 5.0) und 4.5 fuer LiPo / LiON wurden per Test ermittelt
//lcdx_printf_at_P( 12, 1, MNORMAL, 0,0, PSTR("v=%3d"), w ); // Debug Anzeige um Faktoren zu ermitteln
}
 
if(w<0) w = 0;
if(w>20) w = 20; // nicht mehr als 20 Pixel Breite
 
if( w>0 )
lcd_frect( 106+(20-w), 2, w-1, 3, 1); // Batterie Balken: fill
 
if( w<20 )
lcd_frect( 106, 2, 19-w, 3, 0); // Batterie Balken: clear
}
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/lipo/lipo.h
0,0 → 1,50
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* based on the key handling by Peter Dannegger *
* see www.mikrocontroller.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
#ifndef _LIPO_H
#define _LIPO_H
 
 
short samples; //!< Number of conversions
double Vin;
double accumulator;
 
uint16_t volt_avg;
 
void ADC_Init (void);
void oversampled(void);
void show_Lipo(void);
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/main.c
0,0 → 1,202
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY main.c
//#
//# 14.05.2014 OG
//# - chg: include "mk/mksettings.h" geaendert auf "mksettings/mksettings.h"
//#
//# 29.03.2014 OG
//# - chg: MK_Show_LastGPS_Position() ersetzt durch OSDDATA_ShowLastGPSPosition()
//#
//# 28.03.2014 OG
//# - chg: mk_last_position() ersetzt durch MK_Show_LastGPS_Position() (mkbase.c)
//# - del: mk_last_position()
//#
//# 21.02.2014 OG
//# - chg: mk_show_lastposition() auf PKT_TitlePKTVersion() angepasst
//#
//# 19.02.2014 OG
//# - chg: main() hinzugefuegt: MKSettings_TMP_Init0()
//# - add: #include "mk/mksettings.h"
//#
//# 12.02.2014 OG
//# - del: die includes zu den alten parameter... entfernt
//#
//# 11.02.2014 OG
//# - chg: main() Aufruf von searchMK() bzgl. Parametern angepasst
//#
//# 03.02.2014 OG
//# - chg: Titelanzeige in searchMK() umgestellt auf PKT_ShowTitlePKTVersion()
//#
//# 02.02.2014 OG
//# - chg: Screen-Layout von der Anzeige der letzten MK-Position und
//# Ausgliederung davon in mk_show_lastposition()
//#
//# 29.01.2014 OG
//# - del: #include "display.h"
//# - chg: verschoben: MK_load_setting() und searchMK() nach mk/mkbase.c
//# - add: #include "mk/mkbase.h"
//#
//# 25.01.2014 OG
//# - chg: searchMK(): kuerzerer Fehlerbeep bei falscher FC-Revision und
//# automatisches beenden des Fehlerscreens nach 4 Sekunden
//#
//# 24.01.2014 OG
//# - fix: searchMK(): wenn MK_load_setting() keine Daten liefert wird keine
//# falsche RC-Settings-Revisionsnummer mehr angezeigt sondern "ERR!"
//# - chg: searchMK(): Bestaetigung Fehleranzeige bei falscher FC-Revision
//# geaendert von KEY_ESC nach KEY_ENTER - Grund: das PKT behandelt
//# dieses Problem nun flexibler und z.B. OSD (und anderes) geht noch
//# - chg: searchMK(): beschleunigte Erkennung inkompatibler FC-Settings-Revisionen
//# - chg: timings in MK_load_setting()
//#
//# 07.1.2016 Cebra
//# - chg: setzen globale Variable für Abfrage WrongFCVersion etwas verändert
//#
//# 26.06.2013 OG
//# - del: searchMK() Layout und Code-Struktur
//# - fix: searchMK() laden der MK-Settings
//# - add: MK_load_setting() - wird ggf. spaeter zu einer bessern Stelle verschoben
//# - del: Code zu USE_PKT_STARTINFO
//#
//# 20.05.2013 OG
//# - chg: searchMK() Code fuer KEY_ESC geaendert
//#
//# 19.05.2013 OG
//# - del: PKT_Update(), PKT_CheckUpdate(), PKT_Info(), PKT_SwitchOff()
//# -> verschoben nach pkt/pkt.c
//# - chg: Aufruf von main_menu() geaendert zu Menu_Main()
//#
//# 19.05.2013 OG
//# - add: PKT_Update(), PKT_CheckUpdate(), PKT_Info(), PKT_SwitchOff()
//#
//# 16.05.2013 Cebra
//# - chg: Startinfo wird nur noch komplett angezeigt wenn im Setup auf JA
//#
//# 15.05.2013 OG
//# - chg: define USE_PKT_STARTINFO ergaenzt (siehe main.h)
//#
//# 07.05.2013 Cebra
//# - chg: wenn NC vorhanden wird die Version der NC in NCversion gespeichert
//# sonst die FC-Version in FCversion
//#
//# 27.04.2013 OG
//# - chg: GPS-Positionsausgabe umgestellt auf writex_gpspos()
//# - chg: einige clear-lines auf lcd_frect() umgestellt um Speicher zu sparen
//############################################################################
 
 
#include "cpu.h"
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <avr/wdt.h>
#include <util/delay.h>
#include <avr/eeprom.h>
 
 
//************************************************************************************
// Watchdog integrieren und abschalten, wird für Bootloader benötigt
// !!muss hier stehen bleiben!!
 
//--------------------------------------------------------------
void wdt_init(void) __attribute__((naked)) __attribute__((section(".init1")));
 
//--------------------------------------------------------------
void wdt_init(void)
{
MCUSR = 0;
wdt_disable();
return;
}
 
//************************************************************************************
// erst ab hier weitere #includes
 
 
#include "main.h"
#include "lcd/lcd.h"
#include "uart/usart.h"
#include "mk-data-structs.h"
#include "menu.h"
#include "timer/timer.h"
#include "eeprom/eeprom.h"
#include "wi232/Wi232.h"
#include "motortest/twimaster.h"
#include "messages.h"
#include "utils/scrollbox.h"
#include "pkt/pkt.h"
#include "lipo/lipo.h"
#include "mk/mkbase.h"
#include "mksettings/mksettings.h"
#include "osd/osddata.h"
 
 
 
//----------------------------------------------------------------------------
// Anmerkung: 29.01.2014 OG
// - muss spaeter an geeignete Stelle verschoben werden (ggf. mkbase.c/usart.c)
//----------------------------------------------------------------------------
volatile uint8_t mode = 0;
uint8_t hardware = 0;
uint8_t current_hardware = 0;
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
int main(void)
{
InitHWPorts(); // Hardwareanhängige Ports konfigurieren
// dafür wird je nach Hardware die HAL_HWxxx verwendet
// Define dazu in der main.h
hardware = NO;
current_hardware = 0;
 
MKSettings_TMP_Init0(); // TMP-Setting initialisieren
 
if( Config.LastLongitude>0x00000000 && Config.LastLatitude>0x00000000 )
{
OSDDATA_ShowLastGPSPosition(); // letzte MK GPS-Position zeigen
}
 
searchMK(true); // MK suchen (true = MK_Info() anzeigen)
 
while(true)
{
Menu_Main();
}
}
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/main.h
0,0 → 1,444
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2012 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2012 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY main.h
//#
//# 20.09.2015 Starter
//# - FollowMeStep2 wird jetzt nurnoch von USE_FOLLOWME_STEP2 aktiviert
//#
//# 19.09.2015 Cebra
//# - add: Ordner 10DOF hinzugefügt für die Bearbeitung des GY-87 Sensorboard
//# Kompass, Gyro, ACC, Luftdruck
//#
//# 03.08.2015 Cebra
//# - add: Define für GPS Debug hinzugefügt für GPS Berechnung FollowMe
//# - add: #define USE_WAYPOINTS , Code sparen
//#
//# 30.07.2015 Cebra
//# - chg: neue Version 3.85e wegen einigen Änderungen in GPS-Maus Bereich, CRC Erkennung und Weitergabe
//#
//#
//# 30.07.2015 Cebra
//# - chg: neue Version 3.85d wegen Änderungen in gpsmouse.c
//#
//#
//# 16.07.2015 Cebra
//# - chg: neue Version 3.85a wegen FC2.11a
//#
//# 09.04.2015 Cebra
//# - chg: neue Version 3.84a wegen FC2.09j
//#
//# 05.04.2015 Cebra (PKT383b)
//# - chg: Änderungen wegen Fehlfunktion mit NC 2.09h
//# SendOutData( 'h', ADDRESS_ANY, 2, &mkdisplayCmd, 1, 0x00,1)
//# ergänzt um 2. Parameter
//#
//# 19.03.2015 Cebra (PKT383a)
//# - chg: Anpassung an FC209d
//#
//# 27.01.2015 Cebra (PKT382a)
//# - chg: Anpassung an FC209a
//#
//# 26.09.2014 Cebra (PKT381b)
//#
//#
//# 26.09.2014 Cebra (PKT381a)
//#
//# 01.07.2014 OG (PKT380e)
//#
//# 28.06.2014 OG (PKT380dX4)
//#
//# 27.06.2014 OG (PKT380dX3)
//# - chg: USE_FOLLOWME eingeschaltet
//# - chg: USE_TRACKING abgeschaltet
//#
//# 22.06.2014 OG (PKT380dX3)
//#
//# 20.06.2014 OG (PKT380dX2)
//#
//# 18.06.2014 OG (PKT380dX1)
//#
//# 18.06.2014 OG (PKT380d)
//#
//# 05.06.2014 OG (PKT380cX5)
//#
//# 02.06.2014 OG (PKT380cX4)
//# Update auf Windows Atmel AVR Studio 6.2.1153 (Release)
//# (von ehemals Atmel AVR Studio 6.2 Beta)
//#
//# 27.05.2014 OG (PKT380cX3)
//#
//# 20.05.2014 OG (PKT380cX2)
//#
//# 19.05.2014 OG (PKT380cX1)
//# - add: USE_OSD_SCREEN_WAYPOINTS (keine Freigabe! In Entwicklung!)
//#
//# 18.05.2014 OG (PKT380cX1)
//#
//# 15.05.2014 OG (PKT380c)
//#
//# 15.05.2014 OG (PKT380bX7)
//# - chg: USE_OSD_SCREEN_3DLAGE eingeschaltet (war ungewollt abgeschaltet)
//#
//# 14.05.2014 OG (PKT380bX7)
//#
//# 13.05.2014 OG (PKT380bX6)
//# - add: USE_MAINMENU_SEPARATOR (aus menu.h hierhin verschoben)
//# - del: MKINFO_AUTO_REFRESH
//#
//# 12.05.2014 OG (PKT380bX5b)
//# - chg: keine Code-Changes - dafuer Compiler jetzt Atmel Studio 6.2 Beta
//# (statt bisher Atmel Studio 5.1)
//#
//# 07.05.2014 OG (PKT380bX4)
//#
//# 07.05.2014 OG (PKT380bX3)
//# - fix: EEpromversion erhoeht auf 138 (siehe eeprom.c)
//#
//# 02.05.2014 OG (PKT380bX2)
//#
//# 28.04.2014 OG
//# - chg: USE_OSD_SCREEN_OLD abgeschaltet
//#
//# 20.04.2014 OG (PKT380bX1)
//#
//# 18.04.2014 OG (PKT380b)
//#
//# 17.04.2014 OG (PKT380aX1)
//# - chg: PKT Versionsanzeige geaendert auf "3.80a" statt wie frueher "3.8.0a"
//#
//# 16.04.2014 OG (PKT380a)
//#
//# 14.04.2014 OG (PKT374aX8)
//#
//# 02.04.2014 OG
//# - chg: define fuer Baud_2400 von 0 auf 7 geaendert
//# (0/false wird benoetigt um zu erkennen ob keine Baud-Rate erkannt wurde)
//#
//# 01.04.2014 OG
//# - add: USE_SV2MODULE_BLE (Bluetooth 4 Low Energy Modul an SV2)
//#
//# 31.03.2014 OG (PKT374aX7)
//#
//# 30.03.2014 OG (PKT374aX6)
//# Sprachunterstuetzung fuer Hollaendisch vollstaendig entfernt
//#
//# 30.03.2014 OG (PKT374aX5)
//# Source-Schnipp PKT374aX5
//#
//# 01.03.2014 OG (PKT374aX5)
//#
//# 26.02.2014 OG (PKT374aX4)
//# - chg: DEBUG_NEW_PARAMETERS umbenannt zu DEBUG_PARAMSET
//#
//# 22.02.2014 OG (PKT374aX4)
//#
//# 17.02.2014 OG (PKT374aX3)
//# - chg: umbenannt: USE_MKPARAMETER -> USE_MKSETTINGS
//#
//# 14.02.2014 OG (PKT374aX2)
//# - add: MKINFO_AUTO_REFRESH
//# - del: veraltete PKT defines HWVERSION... entfernt
//#
//# 12.02.2014 OG (PKT374aX2)
//# - del: defines zu MKVERSIONnnn entfernt
//#
//# 10.02.2014 OG (PKT374aX1)
//# - add: ...
//#
//# 05.02.2014 OG (PKT374aX1)
//# - add: DEBUG_NEW_PARAMETERS - nur fuer Entwicklung!
//#
//# 30.01.2014 OG (PKT373cX4)
//# - add: USE_BLUETOOTH
//#
//# 29.01.2014 OG (3.7.3cX3)
//# - del: extern uint8_t searchMK(void) ist jetzt in mk/mkbase.c
//#
//# 24.01.2014 OG (3.7.3cX1)
//# - add: DEBUG_FC_COMMUNICATION (Auswirkung in usart.c)
//#
//# 06.01.2014 CB
//# - add: Abschaltung MK Parameter aendern bei nicht passender FC Software
//#
//# 02.12.2013 CB
//# - add: Anpassung Parameter an FC 2.01f
//#
//# 21.10.2013 CB
//# - add: Anpassung Parameter an FC 2.01a
//#
//# 16.07.2013 CB
//# - chg: neuen Versionsnummer wegen Wiflypatch
//#
//# 07.07.2013 OG
//# - add: ABO_TIMEOUT und von 3 sec auf 2 sec gesetzt (war vorher in timer.h)
//# - del: define USE_OSD_SCREEN_ELECTRIC_N
//# - del: USE_PKT_STARTINFO (wird nicht mehr benoetigt)
//# - add: DEBUG_SV2_EXTENSION um Debug-Ausgaben fuer den SV2-Patch an-/auszuschalten
//#
//# 05.07.2013 CB
//# - add: USE_WLAN
//#
//# 30.06.2013 OG
//# - add: USE_OSD_PKTHOOK
//#
//# 26.06.2013 OG
//# - del: USE_PKT_STARTINFO (wird nicht mehr benoetigt)
//#
//# 24.06.2013 OG
//# - add: USE_PKTTOOLS_SV2 - zeigt SV2-Verbindungsmenuepunkte in PKT-Tools an
//# bzw. nicht an. Am PKT-SV2 liegen +5 Volt für die FC/NC an.
//# Anmerkung OG: bei meinen Kompilaten wird das erstmal ausgeschaltet
//# sein bis 100% klar ist ob das keine Probleme macht
//# wenn der Kopter mit FC/NC nicht bereits anderweitig
//# (Netzteil/Lipo) mit Strom versorgt wird.
//#
//# 22.06.2013 Cebra
//# - chg: Fehler bei der Lipooffset Einstellung beseitigt, neue Version 3.7.0c
//#
//# 20.06.2013 Cebra
//# - chg: falsche Versionsnummer korrigiert, neu jetzt 3.7.0b
//#
//# 13.06.2013 OG
//# - del: USE_PCFASTCONNECT (nicht mehr benoetigt)
//#
//# 12.06.2013 Cebra
//# - chg: Versionswechsel auf 3.7.0a, Zielrelease für FC-Software 0.91 (bzw.1.00??)
//#
//# 10.06.2013 Cebra
//# - add: #define MKVERSION091f für FC-Version 0.91f
//#
//# 30.05.2013 Cebra
//# - add: #define MKVERSION091a für FC-Version 0.91a
//#
//# 19.05.2013 OG
//# - del: PKT_Update(), PKT_CheckUpdate(), PKT_Info(), PKT_SwitchOff()
//# -> verschoben nach pkt/pkt.c
//# - chg: Kommentare zum Module-Support
//#
//# 19.05.2013 OG
//# - add: USE_MODULEINFO
//# - add: PKT_Update(), PKT_CheckUpdate(), PKT_Info(), PKT_SwitchOff()
//#
//# 18.05.2013 OG
//# - add: USE_JOYSTICK, USE_TRACKING, USE_OSDDATA, USE_MKPARAMETER, USE_MKDISPLAY
//#
//# 16.05.2013 OG
//# - add: USE_OSD_SCREEN_NAVIGATION, USE_OSD_SCREEN_ELECTRIC, USE_OSD_SCREEN_ELECTRIC_N,
//# USE_OSD_SCREEN_MKSTATUS, USE_OSD_SCREEN_USERGPS, USE_OSD_SCREEN_3DLAGE,
//# USE_OSD_SCREEN_STATISTIC
//# - add: USE_MKGPSINFO
//#
//# 15.05.2013 OG
//# - add: define USE_PKT_STARTINFO
//#
//# 13.05.2013 Cebra
//# - add: #define MKVERSION090h // wegen GPS-Zeitausgabe NC
//#
//# 13.05.2013 Cebra
//# - add: #define USE_I2CMOTORTEST, I2C Funktionen schaltbar
//#
//# 05.05.2013 Cebra
//# - chg: #define USE_FOLLOWME
//#
//# 03.05.2013 OG
//# - del: USE_XPRINTF_LONG - spart keinen Platz mehr und ist nun dauerhaft notwendig
//#
//# 28.04.2013 OG
//# - add: define USE_PCFASTCONNECT
//# - add: define USE_FONT_BIG
//# - add: define USE_XPRINTF_LONG
//# - chg: Anordnung der Feature- & Debug-defines um einfacher via Copy&Paste
//# die Einstellungen notieren bzw. posten zu koennen
//#
//# 03.04.2013 OG
//# - chg: define 'analognames' zu define 'USE_MKDEBUGDATA'
//# - add: USE_OSD_... defines
//############################################################################
 
#ifndef _MAIN_H
#define _MAIN_H
 
// Softwareversion des PKT
#define PKTSWVersion "3.85_f" // PKT Version
 
 
//#########################################################################
//# Einstellungen
//#########################################################################
#define USE_MAINMENU_SEPARATOR // Menuetrennlinien im PKT-Hauptmenues anzeigen
 
 
//#########################################################################
//# MODULE SUPPORT
//# ein-/ausgeschalten von Modulen des PKT um ggf. Speicherplatz zu sparen
//#
//# Hinweis:
//# wenn neue USE_* hinzugefuegt werden bitte die in PKT_Info()(pkt.c)
//# ergaenzen fuer eine aktualisierte Modul-Info
//#########################################################################
 
//---------------------------------------------
//- Module: Hauptfunktionen und allgemeine
//---------------------------------------------
#define USE_OSDDATA // zeigt die OSD-Statistikdaten an (ca. 3.5 KByte)
#define USE_MKSETTINGS // lesen, aktivieren und bearbeiten der MK-Settings 1-5 (ca. ?? KByte)
#define USE_MKDEBUGDATA // Anzeige MK-Debug-Data (ca. 1.7 KByte)
#define USE_MKDISPLAY // Anzeige MK-Display (ca. 1 KByte)
#define USE_MKGPSINFO // Anzeige MK-GPS-Daten (ca. 2 KByte)
//#define USE_SOUND // PKT Sounderweiterung, benoetigt entsprechende Hardware (ca. 2.5 Kbyte)
#define USE_MODULEINFO // Anzeige installierter Module in PKT_Info() (ca. 1.8 KByte)
#define USE_BLUETOOTH // Bluetooth Unterstuetzung des PKT (ca. 13 KByte)
// Achtung! Das schaltet USE_TRACKING, USE_FOLLOWME aus!
//#define USE_WAYPOINTS // Waypoint mit dem PKT
 
//Entwicklung:
//#define USE_ACCCALIBRATION // schaltet ACC Calibration im Menü ein/aus
//#define USE_KOMPASS // Tilt kompensierter Kompass für FollowMe Funktionen
//---------------------------------------------
//- Module: OSD-Screens
//---------------------------------------------
//#define USE_OSD_SCREEN_OLD // OSD Screens OSD0, OSD1, OSD2 (ca. 6.6 KByte)
#define USE_OSD_SCREEN_NAVIGATION // OSD-Screen: Navigation
#define USE_OSD_SCREEN_WAYPOINTS // OSD-Screen: Waypoints
#define USE_OSD_SCREEN_ELECTRIC // OSD-Screen: Electric
#define USE_OSD_SCREEN_MKSTATUS // OSD-Screen: MK-Status
#define USE_OSD_SCREEN_USERGPS // OSD-Screen: UserGPS
#define USE_OSD_SCREEN_3DLAGE // OSD-Screen: 3D-Lage (ca. 900 Bytes)
#define USE_OSD_SCREEN_STATISTIC // OSD-Screen: Statistic
 
//---------------------------------------------
//- Module fuer spezielle Benutzergruppen
//---------------------------------------------
#define USE_FOLLOWME // FollowMe Funktionen (ca. 3 Kbyte)
#define USE_FOLLOWME_STEP2 // FollowMe Funktionen Abstand und Winkel einstellbar
//#define USE_JOYSTICK // Joystick Support, benoetigt spezielle Hardware (ca. 4.1 KByte)
#define USE_WLAN // WLAN WiFly Modul an SV2 (ca. 6 KByte))
#define USE_SV2MODULE_BLE // Bluetooth 4 Low Energy Modul - externes Modul an SV2 (RedBearLab BLE Mini) (ca. 200 Bytes)
 
//---------------------------------------------
//- Module mit geringer Relevanz
//---------------------------------------------
//#define USE_I2CMOTORTEST // I2C Funktionen für Motortest (ca. 3.8 KByte)
//#define USE_FONT_BIG // grosser 8x8 Font (ca. 2.2 KByte, bei Verwendung von USE_OSD_SCREEN_OLD ca. 2.4 KByte)
 
//---------------------------------------------
//- Module unfertig bzw. noch in der Entwicklung
//---------------------------------------------
//#define USE_TRACKING // Antennentracking, benoetigt spezielle Hardware (ca. 6 KByte)
 
 
//---------------------------------------------
//- zusaetzliche Optionen
//---------------------------------------------
//#define USE_OSD_PKTHOOK
#define USE_PKTTOOLS_SV2 // im Menue von PKT-Tools erscheinen Punkte zur Verbindung zum MK via
// 10-Pol-Kabel am PKT-SV2. Der PKT-SV2-Anschluss liefert zur FC/NC +5 Volt!
 
 
//#########################################################################
//# Debug Module & Einstellungen
//# Nur fuer die Entwicklung - fuer Veroeffentlichung alles abschalten!
//#########################################################################
//#define IgnoreFCVersion // keine FC-Revisions Pruefung
//#define DEBUG_SV2_EXTENSION // ...
//#define USE_OSD_DEMO // zeigt Demo-Daten in den OSD-Screens (sofern vom Screen unterstuetzt) (fuer Fotos) (nicht fuer die Oeffentlichkeit)
//#define USE_OSD_SCREEN_DEBUG // zusaetzliche Debug-Screen's aktivieren (ca. 1 KByte) (nicht fuer die Oeffentlichkeit)
//#define DEBUG // ?? Funktion unbekannt!
//#define DEBUG_FC_COMMUNICATION // in usart.c Debugausgaben auf dem PKT bzgl. Datenempfang vom Kopter
//#define DEBUG_PARAMSET // nur fuer Entwicklung! Fuer Release ABSCHALTEN!
//#define DEBUG_GPS // Entwicklung der GPS Berechnung für FollowMe (wird im Moment nicth genutzt)
 
 
//#########################################################################
//# Einstellungen
//#########################################################################
//#define ABO_TIMEOUT 300 // 3 sec
#define ABO_TIMEOUT 200 // 2 sec
 
 
 
 
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//+ ggf. abhaengige USE-defines deaktivieren
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
#ifndef USE_BLUETOOTH
#undef USE_TRACKING
#undef USE_FOLLOWME
#endif
 
 
 
// Fusebits fü½r Hardware 1.2 D7 DC FC
// Fusebits für Hardware 1.3 D7 DC FC
// Fusebits für Hardware 3.x D7 DC FC
// avrdude -pm1284p -cavr109 -P/dev/ttyUSB1 -b115200 -V -Uflash:w:Dateiname.hex:a
 
 
// hier die entsprechende Hardwareversion der Leiterplatte einstellen
#define HWVERSION3_9 // Hardware Cebra Oktober 2011 ATmega1284P
 
#ifdef HWVERSION3_9
#include "HAL_HW3_9.h"
#endif
 
#define NO 0
#define NC 1
#define FC 2
#define MK3MAG 3
#define MKGPS 4
#define Wi232 5
 
// CB #define ENABLE_PWM
 
 
// Baud Rate
#define Baud_9600 1
#define Baud_19200 2
#define Baud_38400 3
#define Baud_57600 4
#define Baud_115200 5
#define Baud_4800 6
#define Baud_2400 7
 
 
//----------------------------------------------------------------------------
// Anmerkung: 29.01.2014 OG
// - muss spaeter an geeignete Stelle verschoben werden (ggf. mkbase.c/usart.c)
//----------------------------------------------------------------------------
extern volatile uint8_t mode;
extern uint8_t hardware;
extern uint8_t current_hardware;
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/menu.c
0,0 → 1,848
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY menu.c
//#
//# 03.08.2015 Cebra
//# - add: Menü _DefMenu_Main_NO erweitert für GPS Test , mit #define schaltbar
//#
//# 09.04.2015 Cebra
//# - add: Vorbereitung für ACC Kalibrartion aus dem Menü
//# #ifdef USE_ACCCALIBRATION
//#
//# 27.06.2014 OG
//# - chg: Menu_PKTSpezial() - Tracking etwas nach oben verschoben
//#
//# 26.06.2014 OG
//# - chg: Menu_PKTSpezial() - ergaenzt um Setup_FollowMe()
//#
//# 18.06.2014 OG
//# - chg: Menu_PKTSpezial() umorganisiert
//#
//# 14.06.2014 OG
//# - chg: _DefMenu_Main_NO() - "PKT Spezial" wird nicht mehr angezeigt wenn
//# kein Kopter gefunden wurde; aktuell sind dort nur Funktionen
//# enthalten die einen Kopter benoetigen - wenn sich das mal irgendwann
//# aendert muss man das anpassen
//#
//# 01.06.2014 OG
//# - chg: Menu_PKTSpezial() - Aufruf von Tracking und Followme ergaenzt
//# um Abfrage MKVersion.isNC
//# - chg: _ConfigMenu_Main() umgestellt auf MKVersion.isNC/isFC
//#
//# 14.05.2014 OG
//# - chg: Aufruf von gps() geaendert zu MK_Gps_Info()
//# - chg: include "gps/gps.h" geaendert zu "mk/mkgpsinfo.h"
//#
//# 13.05.2014 OG
//# - del: USE_MAINMENU_SEPARATOR (verschoben nach main.h)
//# - chg: Menu_Main() - del unused variable 'event'
//#
//# 11.05.2014 OG
//# - chg: Menu_PKTSpezial() umgestellt auf MenuCtrl_SetTitleFromParentItem()
//# -> die Menues 'erben' damit ihren Titel vom aufrufenden Menuepunkt
//#
//# 08.04.2014 OG
//# - chg: die Menuetrennlinien werden jetzt via define USE_MAINMENU_SEPARATOR
//# angezeigt (das define ist hier im Code) und sind erstmal wieder
//# abgeschaltet
//#
//# 08.04.2014 OG
//# - add: _DefMenu_Main_NC() - Menuetrennlinien hinzugefuegt
//# - add: _DefMenu_Main_FC(), _DefMenu_Main_NO() - Menuetrennlinien hinzugefuegt
//#
//# 01.04.2014 OG
//# - chg: PCB_WiFlyPatch umbenannt zu PCB_SV2RxTxPatch
//# - add: PKT-Connect(): "BLE Extender" (ext. Bluetooth 4 Low Energy Modul an SV2)
//# - fix: Menu_PKTConnect(): "WLAN Extender" nur sichtar wenn Config.UseWL gesetzt ist
//#
//# 30.03.2014 OG
//# - chg: Sprache Hollaendisch vollstaendig entfernt
//# - chg: MenuCtrl_PushML_P() umgestellt auf MenuCtrl_PushML2_P()
//#
//# 29.03.2014 OG
//# - chg: versch. Funktionen: del: MenuCtrl_SetShowBatt() wegen Aenderung
//# des Defaults auf true
//#
//# 24.03.2014 OG
//# - chg: "MK Info" vor "MK Settings" verschoben
//#
//# 28.02.2014 OG
//# - chg: ID_MKSETTINGS in den Menues fuer NC/FC weiter nach oben geschoben
//#
//# 27.02.2014 OG
//# - chg: Menuetexte fuer Menu_PKTConnect()
//#
//# 26.02.2014 OG
//# - chg: DEBUG_NEW_PARAMETERS umbenannt zu DEBUG_PARAMSET
//#
//# 18.02.2014 OG
//# - chg: Aufruf von MK_Parameters() ist jetzt MK_Settings() und geht auf
//# den Source mk/mksettings.c
//#
//# 17.02.2014 OG
//# - chg: aus "MK Parameters" ist "MK Settings" geworden! Entsprechende
//# defines zu ID's, USE und Sprachen haben sich geaendert
//# - chg: umbenannt: USE_MKPARAMETER -> USE_MKSETTINGS
//#
//# 12.02.2014 OG
//# - del: die includes zu den alten parameter... entfernt
//# - chg: auf mk/mkparameters.c/h umgestellt -> MK_Parameters()
//# - chg: auf 'MKVersion.paramsetOK' umgestellt
//#
//# 05.02.2014 OG
//# - add: DEBUG_NEW_PARAMETERS in Hauptmenues fuer Entwicklung
//#
//# 30.01.2014 OG
//# - add: Unterstuetzung fuer USE_BLUETOOTH
//#
//# 29.01.2014 OG
//# - chg: Umstrukturierung vom Hauptmenue
//# chg: "PKT Tools" -> "PKT Connect" (nur noch Connect-Funktionen drin)
//# add: "PKT Spezial" -> MK-Motortest und Spezial-Funktionen
//# wie Joystick, Tracking, FollowMe
//# - chg: call: display_debug() -> MK_DebugData()
//# - chg: call: display_data() -> MK_Display()
//# - chg: #include "debug.h" -> "mk/mkdebugdata.h"
//# - chg: #include "display.h" -> #include "mk/mkdisplay.h"
//# - add: #include "mk/mkbase.h"
//#
//# 25.01.2014 OG
//# - chg: MK-Display und MK-DebugData auch bei falscher FC-Revision wieder
//# aktiviert
//#
//# 07.01.2014 Cebra
//# - chg: Abfrage WrongFCVersion etwas verändert
//#
//# 06.01.2014 Cebra
//# - add: Alle Menüpunkte die FC versionabhängig werden bei falscher FC Version ausgeblendet
//#
//# 04.10.2013 Cebra
//# - add: Motortest ohne FC = I2C-Anschluss PKT, mit FC/NC Motortest über FC
//#
//# 26.06.2013 Cebra
//# - add: Menüpunkt Wlan Rangeextender
//#
//# 24.06 2013 OG
//# - chg: Menu_PKTTools(): Menuepunkte fuer PKT-SV2-Verbindungen werden
//# durch define USE_PKTTOOLS_SV2 (main.h) an-/ausgeschaltet
//# - chg: Menu_PKTTools(): Menuepunkte werden je nach aktiviertem Wi232 und
//# Bluetooth ein-/ausgeblendet
//# - chg: Menuetexte fuer ID_USB2SV2 und ID_BT2SV2 geaendert
//# - chg: defines fuer Menuetexte von PKT-Tools geaendert
//# - del: verschiedene Exec_* Funktionen
//#
//# 24.06 2013 Cebra
//# - add: Menuepunkt MKUSB in PKT-Tools
//#
//# 13.06.2013 OG
//# - chg: Fastconnect auf Menu_PKTTools() umgelegt
//# - chg: Menueeintraege von Menu_PKTTools() modifiziert und reduziert
//# - chg: in allen Hauptmenues ist PKT-Setup und PKT-Info drin
//#
//# 11.06.2013 OG
//# - chg: Code zu Menu_OSDData() ausgegliedert nach osddata.c
//#
//# 24.05.2013 OG
//# - chg: Aufrufe von MenuCtrl_Push() umgestellt auf MenuCtrl_PushML_P()
//#
//# 21.05.2013 OG
//# - chg: Menu_Main() umgestellt auf MENUCTRL_EVENT
//# - fix: Menu_Main() nach Menu-Redraw searchMK()
//# - chg: Menu_Setup() umbenannt zu Setup_MAIN()
//# - del: include utils/menuold.h
//#
//# 20.05.2013 OG
//# - chg: Layout Menutitel
//#
//# 19.05.2013 OG
//# - chg: Menuepunkte Tracking und FollowMe werden nur angezeigt wenn BTM222
//# installiert ist (Config.UseBT == true)
//# - add: Menu_PKTTools() (ehemals in tools.c)
//# - del: PC_Fast_Connect() verschoben nach pkt.c
//# - chg: main_menu() umbenannt zu Menu_Main()
//#
//# 19.05.2013 OG
//# - chg: Funktionen nach main.c verschoben
//# CheckUpdate(), Update_PKT(), PKT_Info(), PKT_SwitchOff()
//#
//# 18.05.2013 OG
//# - chg: PKT_Info() erweitert um optionale Module-Info (via USE_MODULEINFO)
//# und Credits chronoligisch umgedreht
//#
//# 18.05.2013 OG
//# - add: USE_JOYSTICK, USE_TRACKING, USE_OSDDATA, USE_MKPARAMETER, USE_MKDISPLAY
//# - chg: redundante Menue-Strings sind untereinander verpointert um Platz zu
//# sparen
//# - chg: Umstellung auf neue menuctrl.c und damit starke Strukturaenderung
//# Hinweis: autom. PKT-Update via Hauptmenue geht noch nicht - wird
//# wieder eingebaut (wenn m�glich direkt in menuctrl.c dann geht
//# das in allen Menues)
//# - del: Ausgliederung der alten Menue-Funktionen nach utils/menuold.c
//# inkl. not_possible()
//#
//# 16.05.2013 OG
//# - add: define USE_MKGPSINFO fuer gps()
//#
//# 05.05.2013 Cebra
//# - chg: Fehler im Menü bei nicht verfügbaren Funktionen
//#
//# 02.05.2013 OG
//# - chg: Menuetext: osddata_menuitems: "MK Fehlerliste" -> "MK Fehler"
//# - chg: Menuetext: "OSD Anzeige" wieder zurueck zu "OSD"
//#
//# 28.04.2013 OG
//# - chg: Show_Version() auf ScrollBox umgestellt
//# - chg: Menuetext "Debug Data" zu "MK Debug Data" (kam frueher zu Verwirrungen bei mir)
//# - chg: main_menu() bzgl. Menu_OSDDATA()
//# - add: Menu_OSDDATA() (aus ehemaligem osd/osd_tools.c)
//#
//# 21.04.2013 Cebra
//# - chg: OSD-Tools im Menue integriert
//#
//# 16.04.2013 Cebra
//# - chg: PROGMEM angepasst auf neue avr-libc und GCC, prog_char depreciated
//#
//# 14.04.2013 OG
//# - WIP: Anzeige "OSD-Daten" in param_menuitems_nc, param_menuitems_no
//#
//# 04.04.2013 Cebra
//# - chg:Texttuning
//# not_possible, für Menüpunkte nicht nicht wählbar sind
//#
//# 03.04.2013 OG
//# - fix: Anzeigefehler wenn (hardware == NC) und nicht gesetzt define 'USE_MKDEBUGDATA' (bzw. 'analognames')
//# - chg: Layout von Anzeige wenn USE_MKDEBUGDATA nicht verfuegbar (jetzt Invers)
//# - chg: define 'analognames' zu define 'USE_MKDEBUGDATA'
//#
//# 30.03.2013 CB
//# - add: automatischer Start der PKT-Updatefunktion im Mainmenüe für das Updatetool
//#
//# 28.03.2013 CB
//# - chg: Hinweis wenn Debug Data nicht möglich ist
//#
//# 10.03.2013 Cebra
//# - add: menu_select, gemeinsame Routine für alle Setupmenüs
//#
//# 27.03.2013 Cebra
//# - chg: Fehler bei der Menüsteuerung behoben
//############################################################################
 
 
#include "cpu.h"
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <avr/wdt.h>
#include <util/delay.h>
#include <string.h>
 
#include "main.h"
#include "lcd/lcd.h"
#include "menu.h"
#include "mk/mkdisplay.h"
#include "mk/mkdebugdata.h"
#include "timer/timer.h"
#include "osd/osd.h"
#include "osd/osddata.h"
#include "motortest/motortest.h"
#include "mk/mkgpsinfo.h"
#include "eeprom/eeprom.h"
#include "setup/setup.h"
#include "uart/uart1.h"
#include "mk-data-structs.h"
#include "wi232/Wi232.h"
 
#include "connect.h"
#include "lipo/lipo.h"
#include "messages.h"
#include "bluetooth/bluetooth.h"
#include "followme/followme.h"
#include "tracking/ng_servo.h"
#include "tracking/tracking.h"
#include "stick/stick.h"
#include "utils/menuctrl.h"
#include "pkt/pkt.h"
#include "mk/mkbase.h"
#include "mksettings/paramset.h"
#include "mksettings/mksettings.h"
 
 
//############################################################################
 
char titlemain[] = "PKT v "; // buffer fuer PKT-Versionsinfo
//123456789012345678901
 
 
 
// nur fuer Entwicklung...
static const char DEBUG_PARAMSET_Text[] PROGMEM = "DEBUG PARAMSET";
 
//############################################################################
 
//-----------------------
// main_menu
//-----------------------
#define ID_OSD 1
#define ID_OSDDATA 2
#define ID_MKDISPLAY 3
#define ID_MKSETTINGS 4
#define ID_MKDEBUGDATA 5
#define ID_MKGPSINFO 6
#define ID_SEARCHMK 7
#define ID_PKTCONNECT 8
#define ID_PKTSETUP 9
#define ID_PKTINFO 10
#define ID_PKTSPEZIAL 11
#define ID_MKINFO 12
#define ID_MKACCCAL 13
 
#define ID_DEBUG_GPS 14
 
 
static const char SEARCHMK_de[] PROGMEM = "Suche Mikrokopter";
static const char SEARCHMK_en[] PROGMEM = "search Kopter";
 
static const char OSD_de[] PROGMEM = "OSD";
#define OSD_en OSD_de
 
static const char OSDDATA_de[] PROGMEM = "OSD Daten";
static const char OSDDATA_en[] PROGMEM = "OSD Data";
 
static const char MKINFO_de[] PROGMEM = "MK Info";
#define MKINFO_en MKINFO_de
 
static const char MKDISPLAY_de[] PROGMEM = "MK Display";
#define MKDISPLAY_en MKDISPLAY_de
 
static const char MKACCCAL_de[] PROGMEM = "MK ACC Kalibr.";
static const char MKACCCAL_en[] PROGMEM = "MK ACC Calibr.";
 
static const char MKSETTINGS_de[] PROGMEM = "MK Settings";
#define MKSETTINGS_en MKSETTINGS_de
 
static const char MKDEBUGDATA_de[] PROGMEM = "MK Daten";
static const char MKDEBUGDATA_en[] PROGMEM = "MK Data";
 
static const char MKGPSINFO_de[] PROGMEM = "MK GPS Info";
#define MKGPSINFO_en MKGPSINFO_de
 
static const char PKTCONNECT_de[] PROGMEM = "PKT Connect";
#define PKTCONNECT_en PKTCONNECT_de
 
static const char PKTSPEZIAL_de[] PROGMEM = "PKT Spezial";
static const char PKTSPEZIAL_en[] PROGMEM = "PKT Special";
 
static const char PKTSETUP_de[] PROGMEM = "PKT Setup";
#define PKTSETUP_en PKTSETUP_de
 
static const char PKTINFO_de[] PROGMEM = "PKT Info";
#define PKTINFO_en PKTINFO_de
 
 
#ifdef DEBUG_GPS
static const char PKTGPS_de[] PROGMEM = "PKT GPS Debug";
#define PKTGPS_en PKTGPS_de
#endif
 
 
//############################################################################
 
//-----------------------------
// Menu_PKTSpezial()
//-----------------------------
#define ID_BLTESTER 60
#define ID_TRACKING 61
#define ID_JOYSTICK 62
#define ID_FOLLOWME 63
#define ID_FOLLOWMESETUP 64
 
static const char BLTESTER_de[] PROGMEM = "MK Motortest";
#define BLTESTER_en BLTESTER_de
 
static const char TRACKING_de[] PROGMEM = "Tracking";
#define TRACKING_en TRACKING_de
 
static const char JOYSTICK_de[] PROGMEM = "Joystick";
#define JOYSTICK_en JOYSTICK_de
 
static const char FOLLOWME_de[] PROGMEM = "Follow Me";
#define FOLLOWME_en FOLLOWME_de
 
static const char FOLLOWMESETUP_de[] PROGMEM = "Follow Me Setup";
#define FOLLOWMESETUP_en FOLLOWMESETUP_de
 
//############################################################################
 
//-----------------------------
// Menu_PKTConnect()
//-----------------------------
#define ID_BT2WI232 40
#define ID_USB2WI232 41
#define ID_USB2SV2 42
#define ID_BT2SV2 43
#define ID_WIFLY2WI232 44
#define ID_BLE2WI232 45
 
 
 
static const char BT2WI232_de[] PROGMEM = "BT Extender";
#define BT2WI232_en BT2WI232_de
 
static const char BLE2WI232_de[] PROGMEM = "BLE Extender";
#define BLE2WI232_en BLE2WI232_de
 
static const char WIFLY2WI232_de[] PROGMEM = "WLAN Extender";
#define WIFLY2WI232_en WIFLY2WI232_de
 
static const char USB2WI232_de[] PROGMEM = "USB -> Wi232";
#define USB2WI232_en USB2WI232_de
 
#ifdef USE_PKTTOOLS_SV2
static const char USB2SV2_de[] PROGMEM = "USB -> SV2";
#define USB2SV2_en USB2SV2_de
#endif
 
#ifdef USE_PKTTOOLS_SV2
static const char BT2SV2_de[] PROGMEM = "BT -> SV2";
#define BT2SV2_en BT2SV2_de
#endif
 
 
//#############################################################################################
//# Hilfsfunktionen & Verschiedenes
//#############################################################################################
 
 
//--------------------------------------------------------------
// wird von Menu_PKTTools() verwendet
//--------------------------------------------------------------
void Exec_BLTESTER(void)
{
if(hardware == NO) motor_test( I2C_Mode );
if(hardware == NC) motor_test( FC_Mode );
if(hardware == FC) motor_test( FC_Mode );
 
}
 
 
//#############################################################################################
//# Menu: Spezial
//#############################################################################################
 
 
 
//--------------------------------------------------------------
// Menue fuer 'PKTSpezial'
//--------------------------------------------------------------
void Menu_PKTSpezial( void )
{
//---------------
// Create
//---------------
MenuCtrl_Create();
 
//---------------
// Einstellungen
//---------------
MenuCtrl_SetTitleFromParentItem(); // "PKT Spezial"
//MenuCtrl_SetTitle_P( PSTR("PKT Spezial") );
//MenuCtrl_SetShowBatt( true );
 
//---------------
// Menuitems: PKTSpezial
//---------------
#ifdef USE_FOLLOWME
if( Config.UseBT && MKVersion.isNC )
{
MenuCtrl_PushML2_P( ID_FOLLOWME , MENU_ITEM, &FollowMe , FOLLOWME_de , FOLLOWME_en );
MenuCtrl_PushML2_P( ID_FOLLOWMESETUP, MENU_ITEM, &Setup_FollowMe, FOLLOWMESETUP_de, FOLLOWMESETUP_en );
}
#endif
 
 
#ifdef USE_TRACKING
if( Config.UseBT && MKVersion.isNC )
{
MenuCtrl_PushML2_P( ID_TRACKING , MENU_ITEM, &PKT_tracking , TRACKING_de , TRACKING_en );
}
#endif
 
 
#ifdef USE_JOYSTICK
MenuCtrl_PushML2_P( ID_JOYSTICK , MENU_ITEM, &joystick , JOYSTICK_de , JOYSTICK_en );
#endif
 
 
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
 
MenuCtrl_PushML2_P( ID_BLTESTER , MENU_ITEM, &Exec_BLTESTER , BLTESTER_de , BLTESTER_en );
 
// {"Servo Tester ","servo test ","Servo Tester "},
// if((val+offset) == 2 ) servo_test();
 
//---------------
// Control
//---------------
MenuCtrl_Control( MENUCTRL_EVENT );
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
//#############################################################################################
//# Menu: PKT-Connect
//#############################################################################################
 
//--------------------------------------------------------------
// Menue fuer; PKT-Connect
//
// verbindet das PKT mit anderen Devices wie Tablet usw.
//--------------------------------------------------------------
void Menu_PKTConnect( void )
{
//---------------
// Create
//---------------
MenuCtrl_Create();
 
//---------------
// Einstellungen
//---------------
MenuCtrl_SetTitle_P( PSTR("PKT Connect") ); // kann nicht auf MenuCtrl_SetTitleFromParentItem() umgestellt
// werden da PKT-Connect auch durch einen Hot-Key aufgerufen
// werden kann
//MenuCtrl_SetCycle( false );
//MenuCtrl_SetShowBatt( true );
//MenuCtrl_SetBeep( true );
 
//---------------
// Menuitems
//---------------
#ifdef USE_BLUETOOTH
if( Config.UseBT && Config.UseWi )
MenuCtrl_PushML2_P( ID_BT2WI232 , MENU_ITEM, &Port_BT2Wi , BT2WI232_de , BT2WI232_en );
#endif
 
#ifdef USE_SV2MODULE_BLE
if( PCB_SV2RxTxPatch && Config.UseBLE )
MenuCtrl_PushML2_P( ID_BLE2WI232 , MENU_ITEM, &Port_BLE2Wi , BLE2WI232_de , BLE2WI232_en );
#endif
 
if( PCB_SV2RxTxPatch && Config.UseWL )
MenuCtrl_PushML2_P( ID_WIFLY2WI232 , MENU_ITEM, &Port_WiFly2Wi , WIFLY2WI232_de , WIFLY2WI232_en );
 
if( Config.UseWi )
MenuCtrl_PushML2_P( ID_USB2WI232 , MENU_ITEM, &Port_USB2Wi , USB2WI232_de , USB2WI232_en );
 
#ifdef USE_PKTTOOLS_SV2 // am PKT-SV2 liegen +5 Volt an...
MenuCtrl_PushML2_P( ID_USB2SV2 , MENU_ITEM, &Port_USB2FC , USB2SV2_de , USB2SV2_en );
 
#ifdef USE_BLUETOOTH
if( Config.UseBT )
MenuCtrl_PushML2_P( ID_BT2SV2 , MENU_ITEM, &Port_BT2FC , BT2SV2_de , BT2SV2_en );
#endif
 
#endif // end: #ifdef USE_PKTTOOLS_SV2
 
//---------------
// Control
//---------------
MenuCtrl_Control( MENUCTRL_EVENT );
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
//#############################################################################################
//# Menu: Menu_Main
//#############################################################################################
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void _DefMenu_Main_NC( void )
{
 
 
MenuCtrl_PushML2_P( ID_OSD , MENU_ITEM, &osd , OSD_de , OSD_en );
 
#ifdef USE_OSDDATA
MenuCtrl_PushML2_P( ID_OSDDATA , MENU_SUB , &Menu_OSDData , OSDDATA_de , OSDDATA_en );
#endif
 
#ifdef USE_MAINMENU_SEPARATOR
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
#endif
 
MenuCtrl_PushML2_P( ID_MKINFO , MENU_ITEM, NOFUNC , MKINFO_de , MKINFO_en );
 
#ifdef USE_MKSETTINGS
if( MKVersion.paramsetOK )
{
MenuCtrl_PushML2_P( ID_MKSETTINGS, MENU_SUB , &MK_Settings , MKSETTINGS_de, MKSETTINGS_en );
}
#endif
 
#ifdef USE_MKDISPLAY
// ACC_Display = false;
MenuCtrl_PushML2_P( ID_MKDISPLAY , MENU_ITEM, &MK_Display , MKDISPLAY_de , MKDISPLAY_en );
#endif
 
#ifdef USE_ACCCALIBRATION
if ((MKVersion_Cmp( MKVersion.FCVer, 2,9,'i') == VERSION_EQUAL) || (MKVersion_Cmp( MKVersion.FCVer, 2,9,'i') == VERSION_GREATER))
{
ACC_Display = true;
MenuCtrl_PushML2_P( ID_MKACCCAL , MENU_ITEM, &MK_Display , MKACCCAL_de , MKACCCAL_en );
}
#endif
 
#ifdef USE_MKDEBUGDATA
MenuCtrl_PushML2_P( ID_MKDEBUGDATA, MENU_ITEM, &MK_DebugData , MKDEBUGDATA_de, MKDEBUGDATA_en );
#endif
 
 
#ifdef USE_MKGPSINFO
MenuCtrl_PushML2_P( ID_MKGPSINFO , MENU_ITEM, &MK_Gps_Info , MKGPSINFO_de , MKGPSINFO_en );
#endif
 
#ifdef USE_MAINMENU_SEPARATOR
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
#endif
 
MenuCtrl_PushML2_P( ID_PKTSPEZIAL , MENU_SUB , &Menu_PKTSpezial , PKTSPEZIAL_de , PKTSPEZIAL_en );
MenuCtrl_PushML2_P( ID_PKTCONNECT , MENU_SUB , &Menu_PKTConnect , PKTCONNECT_de , PKTCONNECT_en );
MenuCtrl_PushML2_P( ID_PKTSETUP , MENU_SUB , NOFUNC , PKTSETUP_de , PKTSETUP_en );
MenuCtrl_PushML2_P( ID_PKTINFO , MENU_ITEM ,&PKT_Info , PKTINFO_de , PKTINFO_en );
 
 
#ifdef DEBUG_PARAMSET
MenuCtrl_Push_P( 0 , MENU_ITEM, &paramsetDEBUG , DEBUG_PARAMSET_Text );
#endif
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void _DefMenu_Main_FC( void )
{
MenuCtrl_PushML2_P( ID_MKINFO , MENU_ITEM, NOFUNC , MKINFO_de , MKINFO_en );
 
#ifdef USE_MKSETTINGS
if( MKVersion.paramsetOK )
{
MenuCtrl_PushML2_P( ID_MKSETTINGS, MENU_SUB , &MK_Settings , MKSETTINGS_de, MKSETTINGS_en );
}
#endif
 
 
 
#ifdef USE_MKDISPLAY
// ACC_Display = false;
MenuCtrl_PushML2_P( ID_MKDISPLAY , MENU_ITEM, &MK_Display , MKDISPLAY_de , MKDISPLAY_en );
#endif
 
#ifdef USE_ACCCALIBRATION
if ((MKVersion_Cmp( MKVersion.FCVer, 2,9,'i') == VERSION_EQUAL) || (MKVersion_Cmp( MKVersion.FCVer, 2,9,'i') == VERSION_GREATER))
{
ACC_Display = true;
MenuCtrl_PushML2_P( ID_MKACCCAL , MENU_ITEM, &MK_Display , MKACCCAL_de , MKACCCAL_en );
}
#endif
 
#ifdef USE_MKDEBUGDATA
MenuCtrl_PushML2_P( ID_MKDEBUGDATA, MENU_ITEM, &MK_DebugData , MKDEBUGDATA_de, MKDEBUGDATA_en );
#endif
 
#ifdef USE_MAINMENU_SEPARATOR
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
#endif
 
MenuCtrl_PushML2_P( ID_PKTSPEZIAL , MENU_SUB , &Menu_PKTSpezial , PKTSPEZIAL_de , PKTSPEZIAL_en );
MenuCtrl_PushML2_P( ID_PKTCONNECT , MENU_SUB , &Menu_PKTConnect , PKTCONNECT_de , PKTCONNECT_en );
MenuCtrl_PushML2_P( ID_PKTSETUP , MENU_SUB , NOFUNC , PKTSETUP_de , PKTSETUP_en );
MenuCtrl_PushML2_P( ID_PKTINFO , MENU_ITEM ,&PKT_Info , PKTINFO_de , PKTINFO_en );
 
 
#ifdef DEBUG_PARAMSET
MenuCtrl_Push_P( 0 , MENU_ITEM, &paramsetDEBUG , DEBUG_PARAMSET_Text );
#endif
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void _DefMenu_Main_NO( void )
{
#ifdef USE_FOLLOWME
#ifdef DEBUG_GPS
MenuCtrl_PushML2_P( ID_DEBUG_GPS , MENU_ITEM, &Debug_GPS , PKTGPS_de , PKTGPS_en );
 
 
#endif
#endif
 
MenuCtrl_PushML2_P( ID_SEARCHMK , MENU_ITEM, NOFUNC , SEARCHMK_de , SEARCHMK_en );
 
#ifdef USE_MAINMENU_SEPARATOR
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
#endif
 
#ifdef USE_OSDDATA
MenuCtrl_PushML2_P( ID_OSDDATA , MENU_SUB , &Menu_OSDData , OSDDATA_de , OSDDATA_en );
#endif
 
#ifdef USE_MAINMENU_SEPARATOR
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
#endif
 
//MenuCtrl_PushML2_P( ID_PKTSPEZIAL, MENU_SUB , &Menu_PKTSpezial, PKTSPEZIAL_de , PKTSPEZIAL_en );
MenuCtrl_PushML2_P( ID_PKTCONNECT, MENU_SUB , &Menu_PKTConnect, PKTCONNECT_de , PKTCONNECT_en );
MenuCtrl_PushML2_P( ID_PKTSETUP , MENU_SUB , NOFUNC , PKTSETUP_de , PKTSETUP_en );
MenuCtrl_PushML2_P( ID_PKTINFO , MENU_ITEM, &PKT_Info , PKTINFO_de , PKTINFO_en );
 
 
#ifdef DEBUG_PARAMSET
MenuCtrl_Push_P( 0 , MENU_ITEM, &paramsetDEBUG , DEBUG_PARAMSET_Text );
#endif
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void _ConfigMenu_Main( void )
{
MenuCtrl_Create();
 
MenuCtrl_SetTitle( titlemain );
//MenuCtrl_SetShowBatt( true );
 
//-----------
// Tasten
//-----------
MenuCtrl_SetKey( KEY_ESC , strGet(OFF), &PKT_SwitchOff );
 
MenuCtrl_SetKey( KEY_ENTER_LONG , NOTEXT, &Menu_PKTConnect );
 
if ( MKVersion.isNC ) _DefMenu_Main_NC();
else if( MKVersion.isFC ) _DefMenu_Main_FC();
else _DefMenu_Main_NO();
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Menu_Main( void )
{
uint8_t itemid;
uint8_t UseBT = Config.UseBT; // merkt sich Bluetooth Einstellung falls durch Setup geaendert
 
uart1_flush();
ADC_Init(); // ADC für Lipomessung // MartinR hierher verschoben
get_key_press(KEY_ALL);
 
strncpy( &titlemain[5], PKTSWVersion, 12); // baue Titel mit PKT-Versionsnummer zusammen
 
MenuCtrl_ShowLevel( true ); // zeige Menuelevel in der Titelzeile aller Menues
_ConfigMenu_Main(); // initialisiert das Menu je nach Hardware (NO,FC,NC) verschieden
 
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT ); // wartet nicht auf Event, springt direkt zurueck (wegen evtl. BT-Aenderung)
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
//--------------
// ID_SEARCHMK
//--------------
if( itemid == ID_SEARCHMK ) // neuer Hardware Modus?
{
if( searchMK(true) ) // true = zeige MK_Info() an
{
MenuCtrl_Destroy(); // Menu verwerfen...
_ConfigMenu_Main(); // ...und neues Menu initialisieren (je nach Hardware: NO,FC,NC)
}
}
 
//--------------
// ID_MKINFO
//--------------
if( itemid == ID_MKINFO )
{
if( MK_Info( 0, true) ) // neuer Hardware Modus? (in MK_Info() kann man eine Neusuche des MK starten) (true = mit Settings-Refresh)
{
MenuCtrl_Destroy(); // Menu verwerfen...
_ConfigMenu_Main(); // ...und neues Menu initialisieren (je nach Hardware: NO,FC,NC)
}
}
 
//--------------
// ID_PKTSETUP
//--------------
if( itemid == ID_PKTSETUP )
{
Setup_MAIN();
}
 
 
//--------------
// Bluetooth geaendert?
//--------------
if( UseBT != Config.UseBT ) // falls sich im PKT-Setup die Einstellung bzgl. installiertem Bluetooth Modul
{ // geaendert hat werden ggf. andere Menuepunkte angezeigt (Tracking, FollowMe)
MenuCtrl_Destroy(); // Menu verwerfen...
_ConfigMenu_Main(); // ...und neues Menu initialisieren (je nach Hardware: NO,FC,NC)
UseBT = Config.UseBT;
}
}
 
MenuCtrl_Destroy();
}
 
 
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/menu.h
0,0 → 1,57
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY menu.h
//#
//# 19.05.2013 OG
//# - chg: main_menu() umbenannt zu Menu_Main()
//#
//# 19.05.2013 OG
//# - chg: Funktionen nach main.h verschoben
//# CheckUpdate(), Update_PKT(), PKT_Info(), PKT_SwitchOff()
//#
//# 18.05.2013 OG
//# - del: Ausgliederung der alten Menue-Funktionen nach utils/menuold.c
//# inkl. not_possible()
//############################################################################
 
#ifndef MENU_H
#define MENU_H
 
 
 
 
void Menu_Main(void);
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/messages.c
0,0 → 1,829
/****************************************************************************************
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Languagesupport: *
* http://www.netrino.com/Embedded-Systems/How-To/Firmware-Internationalization *
* Nigel Jones *
****************************************************************************************/
 
//############################################################################
//# HISTORY messages.c
//#
//# 08.08.2015 cebra
//# - add: STR_WAITNMEA
//#
//# 28.06.2014 OG
//# - chg: Text von ERROR_NODATA statt "Datenverlust!" jetzt "MK Datenverlust!"
//# - chg: Text von OSD_ERROR statt "FEHLER: Datenverlust!" jetzt "MK Datenverlust!"
//#
//# 27.06.2014 OG
//# - add: STR_BT_SEARCHTIME, STR_METERS, STR_BT_LOSTDATA
//#
//# 25.06.2014 OG
//# - add: STR_SEARCH_BT_ASK, STR_SEARCH_BT, STR_NO_BT_FOUND, STR_BT_DEVICES
//#
//# 24.06.2014 OG
//# - add: STR_NOBTM222, STR_NOGPSMOUSE, STR_GPSMOUSECONNECTION
//# - add: STR_GPSMOUSECONNECT, STR_GPSMOUSEDISCONNECT
//#
//# 23.06.2014 OG
//# - add: STR_WAITSATFIX
//#
//# 13.06.2014 OG
//# - add: STR_PKT_SWITCHOFF_NOW, STR_PKT_RESTART_NOW, STR_WI232_ACTIVATE
//# - del: mehrere CONNECT.. Strings
//# - del: DISPLAY3
//#
//# 11.06.2014 OG
//# - add: strGetLanguage()
//# - add: KEYLINE5
//# - del: TESTSTRING
//#
//# 10.06.2014 OG
//# - add: STR_WI232CONFIG, STR_USBCONNECTED, STR_SEEMKWIKI
//# - add: STR_ATTENTION, STR_SWITCHOFFMK
//# - del: CONNECT21, CONNECT22, CONNECT24, CONNECT25
//#
//# 08.06.2014 OG
//# - add: STR_EXTSV2MODULE
//#
//# 04.06.2014 OG
//# - add: STR_DATA
//# - add: STR_READING, STR_LABELS
//#
//# 01.06.2014 OG
//# - del: weitere unbenoetigte Strings geloescht
//#
//# 31.05.2014 OG
//# - add: STR_WITH, STR_WITHOUT
//# - del: etliche Strings die nicht mehr benoetigt werden geloescht
//#
//# 30.05.2014 OG
//# - add: STR_HELP_LIPOOFFSET1, STR_HELP_LIPOOFFSET2
//# - add: STR_HELP_LOWBAT1, STR_HELP_LOWBAT2
//#
//# 29.05.2014 OG
//# - del: etliche Strings die nicht mehr benoetigt werden geloescht
//#
//# 28.05.2014 OG
//# - add: STR_HELP_PKTLIGHTOFF1
//#
//# 26.05.2014 OG
//# - add: STR_OSDSCREEN_WAYPOINTS
//# - del: CHANGENORMREV1, CHANGENORMREV2
//#
//# 11.05.2014 OG
//# - chg: STR_SAVE_de - jetzt "Speichern" statt "speichern"
//#
//# 06.05.2014 OG
//# - add: STR_MENUCTRL_DELITEM, STR_MENUCTRL_DELASK, STR_MENUCTRL_NOTPOSSIBLE
//# - del: STR_FAV_DELETE
//#
//# 03.05.2014 OG
//# - add: STR_FAV_ADD, STR_FAV_DELETE, STR_FAV_FULL, STR_FAV_EXIST, STR_FAV_NOTEXIST
//#
//# 28.04.2014 OG
//# - add: STR_LONGPRESS
//# - chg: OSD_ERROR_de,OSD_ERROR_en Space am Ende entfernt / Ausrufungszeichen hinzugefuegt
//#
//# 09.04.2014 OG
//# - chg: WL1 von "WiFly vorh.:" zu "WiFly Modus:"
//#
//# 04.04.2014 OG
//# - add: STR_SEARCH, STR_FOUND, STR_SET
//#
//# 03.04.2014 OG
//# - add: STR_INITIALIZE
//#
//# 02.04.2014 OG
//# - chg: Text WL1_de gekuerzt
//#
//# 01.04.2014 OG
//# - add: BLE_EXIST, MODULE_EXIST
//#
//# 30.03.2014 OG
//# - chg: Text zu WL1 geaendert von "Wlan eingebaut" zu "WiFly vorhanden"
//# -> das ist ein Aufsteckmodul und wird nicht eingebaut
//# - chg: strGet() angepasst auf 2 Sprachen (Deutsch, Englisch)
//# - del: Hollaendisch vollstaendig geloescht
//#
//# 29.03.2014 OG
//# - chg: Test geaendert von START_LASTPOS2 zu "löschen Nein"
//# - chg: einige Texte bzgl. OSD-Data gekuerzt wegen Umstellung auf lcdx_printp_center()
//#
//# 27.03.2014 OG
//# - add: STR_SAVE, STR_DISCARD, STR_COPY, STR_SWITCHMOTOROFF, STR_SAVING
//#
//# 19.03.2014 OG
//# - add: KEYCANCEL
//#
//# 27.02.2014 OG
//# - add: STR_ACTIVE
//#
//# 20.02.2014 OG
//# - chg: Texte von BOOT1, BOOT2, TESTSTRING
//# - add: STR_VON, STR_NACH, STR_PKT
//#
//# 17.02.2014 OG
//# - add: EDIT_SETTING
//# - add: STR_ERROR, ERROR_NODATA, MSG_LOADSETTINGS, MSG_ACTIVATESETTING
//#
//# 12.02.2014 OG
//# - del: STARTMSG2
//# - add: NOMKFOUND
//#
//# 04.02.2014 OG
//# - add: CHANGENORMREV1, CHANGENORMREV2
//#
//# 03.02.2014 OG
//# - add: SHOWCELLU
//#
//# 02.02.2014 OG
//# - chg: START_LASTPOS
//# - chg: START_LASTPOS1
//# - chg: START_LASTPOS3
//# - del: START_LASTPOSDEL
//#
//# 24.01.2014 OG
//# - del: etliche ":" aus Bezeichnungen geloescht (bei verschiedenen Einstellungen)
//# -> woher kamen die ueberhaupt? In der Historie sehe ich dazu nichts!
//# - add: MSG_WARNUNG, UPDATE3
//# - chg: UPDATE1, UPDATE2 (PKT Update)
//# - chg: SHUTDOWN (Space's entfernt)
//# - chg: START_VERSIONCHECK3: angepasst auf neue flexibilitaet des PKT wenn
//# FC-Revision nicht unterstuetzt wird
//# - chg: OK_de von "Ok" nach "OK"
//#
//# 15.07.2013 Cebra
//# - add: Wlan Security erweitert
//#
//# 07.07.2013 OG
//# - add: OSD-Screen Namen
//#
//# 02.07.2013 Cebra
//# - add: Menuetexte fuer Wlan
//#
//# 27.06.2013 OG
//# - del: OSD_HOMEMKVIEW
//#
//# 26.06.2013 OG
//# - del: einige nicht mehr benoetigte Texte
//# - chg: Texte geaendert von START_VERSIONCHECK...
//# - chg: START_VERSIONCHECK5 zu MSG_FEHLER2
//#
//# 15.06.2013 OG
//# - add: OSD_MKSetting (fuer Setup: ein-/ausschalten der MK-Settingsanzeige)
//# - del: DISPLAY8 (ehemals LCD-Orientierung, nicht mehr benoetigt)
//# - chg: Code-Layout
//#
//# 13.06.2013 OG
//# - chg: kleine Textaenderung an STARTMSG2
//# - chg: Code-Layout
//#
//# 13.06.2013 CB
//# - add: Texte für OSD Statistik erweitert
//#
//# 25.05.2013 OG
//# - chg: redundante Strings durch define ersetzt um Speicherplatz zu sparen
//#
//# 05.05.2013 Cebra
//# - add: Erweiterung PKT Zeitsetup
//#
//# 25.04.2013 Cebra
//# - chg: LIPO entfernt, Text doppelt
//############################################################################
 
#include <avr/pgmspace.h>
#include "eeprom/eeprom.h"
#include "messages.h"
 
 
typedef enum
{
GERMAN,
ENGLISH,
NETHERLAND,
LAST_LANGUAGE,
} LANGUAGE;
 
 
static const char KEYLINE1_de[] PROGMEM = " \x1a \x1b Ende OK";
static const char KEYLINE1_en[] PROGMEM = " \x1a \x1b end OK";
 
static const char KEYLINE2_de[] PROGMEM = " \x18 \x19 Ende OK";
static const char KEYLINE2_en[] PROGMEM = " \x18 \x19 end OK";
 
static const char KEYLINE3_de[] PROGMEM = " \x18 \x19 Ende ";
static const char KEYLINE3_en[] PROGMEM = " \x18 \x19 end ";
 
static const char KEYLINE4_de[] PROGMEM = "Ende OK";
static const char KEYLINE4_en[] PROGMEM = "end OK";
 
static const char KEYLINE5_de[] PROGMEM = " \x18 \x19 Abbr. OK";
static const char KEYLINE5_en[] PROGMEM = " \x18 \x19 cancel OK";
 
static const char KEYCANCEL_de[] PROGMEM = " Abbr.";
static const char KEYCANCEL_en[] PROGMEM = "cancel";
 
static const char BOOT1_de[] PROGMEM = "Taste 1 Sekunde";
static const char BOOT1_en[] PROGMEM = "press button";
 
static const char BOOT2_de[] PROGMEM = "festhalten!";
static const char BOOT2_en[] PROGMEM = "for 1 second!";
 
static const char START_LASTPOS_de[] PROGMEM = "Letzte Position";
static const char START_LASTPOS_en[] PROGMEM = "last position";
 
static const char START_LASTPOS1_de[] PROGMEM = "Breitengr. Längengr.";
static const char START_LASTPOS1_en[] PROGMEM = "latitude longitude";
 
static const char START_LASTPOS2_de[] PROGMEM = "löschen Nein";
static const char START_LASTPOS2_en[] PROGMEM = "delete No";
 
static const char START_LASTPOS3_de[] PROGMEM = "Google Eingabe:";
static const char START_LASTPOS3_en[] PROGMEM = "Google Input:";
 
static const char START_SEARCHFC_de[] PROGMEM = "suche Mikrokopter...";
static const char START_SEARCHFC_en[] PROGMEM = "searching Kopter...";
 
static const char ENDE_de[] PROGMEM = "Ende";
static const char ENDE_en[] PROGMEM = "end";
 
static const char OK_de[] PROGMEM = "OK";
static const char OK_en[] PROGMEM = "ok";
 
static const char FEHLER_de[] PROGMEM = "Fehler";
static const char FEHLER_en[] PROGMEM = "error";
 
static const char AKTIV_de[] PROGMEM = "aktiv";
static const char AKTIV_en[] PROGMEM = "activ";
 
static const char STR_SAVE_de[] PROGMEM = "Speichern";
static const char STR_SAVE_en[] PROGMEM = "save";
 
static const char STR_SAVING_de[] PROGMEM = "wird gespeichert...";
static const char STR_SAVING_en[] PROGMEM = "saving...";
 
static const char STR_DISCARD_de[] PROGMEM = "Verwerfen";
static const char STR_DISCARD_en[] PROGMEM = "discard";
 
static const char STR_COPY_de[] PROGMEM = "Kopieren";
static const char STR_COPY_en[] PROGMEM = "copy";
 
static const char STR_SEARCH_de[] PROGMEM = "suche";
static const char STR_SEARCH_en[] PROGMEM = "search";
 
static const char STR_FOUND_de[] PROGMEM = "gefunden";
static const char STR_FOUND_en[] PROGMEM = "found";
 
static const char STR_SET_de[] PROGMEM = "setze";
static const char STR_SET_en[] PROGMEM = "set";
 
static const char STR_WITH_de[] PROGMEM = "mit";
static const char STR_WITH_en[] PROGMEM = "with";
 
static const char STR_WITHOUT_de[] PROGMEM = "ohne";
static const char STR_WITHOUT_en[] PROGMEM = "without";
 
static const char STR_SWITCHMOTOROFF_de[] PROGMEM = "Motoren ausschalten!";
static const char STR_SWITCHMOTOROFF_en[] PROGMEM = "switch motors off!";
 
static const char ON_de[] PROGMEM = "Ein ";
static const char ON_en[] PROGMEM = "On ";
 
static const char OFF_de[] PROGMEM = "Aus ";
static const char OFF_en[] PROGMEM = "off ";
 
static const char ESC_de[] PROGMEM = "ESC";
#define ESC_en ESC_de
 
static const char SHUTDOWN_de[] PROGMEM = "PKT ausschalten?";
static const char SHUTDOWN_en[] PROGMEM = "shutdown PKT?";
 
static const char YESNO_de[] PROGMEM = "Ja Nein";
static const char YESNO_en[] PROGMEM = "yes no";
 
static const char NOYES_de[] PROGMEM = "Nein Ja";
static const char NOYES_en[] PROGMEM = "no yes";
 
static const char DELETEDATA_de[] PROGMEM = "Daten löschen?";
static const char DELETEDATA_en[] PROGMEM = "delete data?";
 
static const char UPDATE1_de[] PROGMEM = "Verbinde PKT mit PC!";
static const char UPDATE1_en[] PROGMEM = "Connect PKT to PC";
 
static const char UPDATE2_de[] PROGMEM = "Drücke 'Start' für";
static const char UPDATE2_en[] PROGMEM = "Press 'Start' for";
 
static const char UPDATE3_de[] PROGMEM = "min. 2 Sekunden";
static const char UPDATE3_en[] PROGMEM = "min. 2 seconds";
 
static const char ENDSTART_de[] PROGMEM = "Ende Start";
static const char ENDSTART_en[] PROGMEM = "End Start";
 
static const char CONNECT13_de[] PROGMEM = "Modul eingebaut";
static const char CONNECT13_en[] PROGMEM = "Modul built in";
 
static const char KABEL_de[] PROGMEM = "Kabel";
static const char KABEL_en[] PROGMEM = "cable";
 
static const char SLAVE_de[] PROGMEM = "Slave";
#define SLAVE_en SLAVE_de
 
static const char NORMAL_de[] PROGMEM = "Normal";
#define NORMAL_en NORMAL_de
 
static const char REVERSE_de[] PROGMEM = "Reverse";
static const char REVERSE_en[] PROGMEM = "inverse";
 
static const char ENDOK_de[] PROGMEM = "Ende OK";
static const char ENDOK_en[] PROGMEM = "End OK";
 
static const char EEPROM1_de[] PROGMEM = "PKT-EEProm";
static const char EEPROM1_en[] PROGMEM = "Realy delete";
 
static const char EEPROM2_de[] PROGMEM = "wirklich löschen?";
static const char EEPROM2_en[] PROGMEM = "PKT-EEProm?";
 
static const char DEUTSCH_de[] PROGMEM = "deutsch";
static const char DEUTSCH_en[] PROGMEM = "german";
 
static const char ENGLISCH_de[] PROGMEM = "englisch";
static const char ENGLISCH_en[] PROGMEM = "english";
 
static const char YES_de[] PROGMEM = "Ja ";
static const char YES_en[] PROGMEM = "yes ";
 
static const char NOO_de[] PROGMEM = "Nein";
static const char NOO_en[] PROGMEM = "no ";
 
static const char OSD_3D_V_de[] PROGMEM = "V";
static const char OSD_3D_V_en[] PROGMEM = "F";
 
static const char OSD_3D_H_de[] PROGMEM = "H";
static const char OSD_3D_H_en[] PROGMEM = "B";
 
static const char OSD_3D_L_de[] PROGMEM = "L";
#define OSD_3D_L_en OSD_3D_L_de
 
static const char OSD_3D_R_de[] PROGMEM = "R";
#define OSD_3D_R_en OSD_3D_R_de
 
static const char OSD_3D_NICK_de[] PROGMEM = "Ni";
#define OSD_3D_NICK_en OSD_3D_NICK_de
 
static const char OSD_3D_ROLL_de[] PROGMEM = "Ro";
#define OSD_3D_ROLL_en OSD_3D_ROLL_de
 
static const char OSD_ERROR_de[] PROGMEM = "MK Datenverlust!";
static const char OSD_ERROR_en[] PROGMEM = "MK Data lost!";
 
static const char PARA_AKTIVI_de[] PROGMEM = "Aktivieren";
static const char PARA_AKTIVI_en[] PROGMEM = "activate";
 
static const char PARA_COPY_de[] PROGMEM = "Kopiere Setting";
static const char PARA_COPY_en[] PROGMEM = "copy settings";
 
static const char PARA_COPYQ_de[] PROGMEM = "Wirklich kopieren?";
static const char PARA_COPYQ_en[] PROGMEM = "really copy?";
 
static const char GPS2_de[] PROGMEM = "gewähltes GPS Gerät ";
static const char GPS2_en[] PROGMEM = "selected GPS device ";
 
static const char STATS_ITEM_0_de[] PROGMEM = "max Höhe :";
static const char STATS_ITEM_0_en[] PROGMEM = "max altitude:";
 
static const char STATS_ITEM_1_de[] PROGMEM = "max Geschw. :";
static const char STATS_ITEM_1_en[] PROGMEM = "max speed :";
 
static const char STATS_ITEM_2_de[] PROGMEM = "max Entfern.:";
static const char STATS_ITEM_2_en[] PROGMEM = "max distance:";
 
static const char STATS_ITEM_3_de[] PROGMEM = "min Spannung:";
static const char STATS_ITEM_3_en[] PROGMEM = "min voltage :";
 
static const char STATS_ITEM_4_de[] PROGMEM = "max Zeit :";
static const char STATS_ITEM_4_en[] PROGMEM = "max time :";
 
static const char STATS_ITEM_5_de[] PROGMEM = "max Strom :";
static const char STATS_ITEM_5_en[] PROGMEM = "max current :";
 
static const char STATS_ITEM_6_de[] PROGMEM = "Ent.Kapazit.:";
static const char STATS_ITEM_6_en[] PROGMEM = "UsedCapacity:";
 
static const char POTI_de[] PROGMEM = "Poti ";
static const char POTI_en[] PROGMEM = "poti ";
 
static const char TASTER_de[] PROGMEM = "Taster";
static const char TASTER_en[] PROGMEM = "switch";
 
static const char STAT_OSDBL_de[] PROGMEM = "OSD- und BL-Daten";
static const char STAT_OSDBL_en[] PROGMEM = "OSD- and BL-Data";
 
static const char STAT_ERROR_de[] PROGMEM = "MK Fehlerliste";
static const char STAT_ERROR_en[] PROGMEM = "MK errorlist";
 
static const char STAT_GPS_de[] PROGMEM = "User GPS-Daten";
static const char STAT_GPS_en[] PROGMEM = "User GPS-data";
 
static const char STAT_POS_de[] PROGMEM = "letzte Position";
static const char STAT_POS_en[] PROGMEM = "last position";
 
static const char STAT_ALL_de[] PROGMEM = "ALLE Daten";
static const char STAT_ALL_en[] PROGMEM = "ALL data";
 
static const char DELETE_de[] PROGMEM = "löschen?";
static const char DELETE_en[] PROGMEM = "delete?";
 
static const char STR_OSDSCREEN_GENERAL_de[] PROGMEM = "General";
#define STR_OSDSCREEN_GENERAL_en STR_OSDSCREEN_GENERAL_de
 
static const char STR_OSDSCREEN_NAVIGATION_de[] PROGMEM = "Navigation";
#define STR_OSDSCREEN_NAVIGATION_en STR_OSDSCREEN_NAVIGATION_de
 
static const char STR_OSDSCREEN_WAYPOINTS_de[] PROGMEM = "Waypoints";
#define STR_OSDSCREEN_WAYPOINTS_en STR_OSDSCREEN_NAVIGATION_de
 
static const char STR_OSDSCREEN_ELECTRIC_de[] PROGMEM = "Electric";
#define STR_OSDSCREEN_ELECTRIC_en STR_OSDSCREEN_ELECTRIC_de
 
static const char STR_OSDSCREEN_MKSTATUS_de[] PROGMEM = "MK-Status";
#define STR_OSDSCREEN_MKSTATUS_en STR_OSDSCREEN_MKSTATUS_de
 
static const char STR_OSDSCREEN_USERGPS_de[] PROGMEM = "User GPS";
#define STR_OSDSCREEN_USERGPS_en STR_OSDSCREEN_USERGPS_de
 
static const char STR_OSDSCREEN_3DLAGE_de[] PROGMEM = "3D Lage";
#define STR_OSDSCREEN_3DLAGE_en STR_OSDSCREEN_3DLAGE_de
 
static const char STR_OSDSCREEN_STATISTIC_de[] PROGMEM = "Statistics";
#define STR_OSDSCREEN_STATISTIC_en STR_OSDSCREEN_STATISTIC_de
 
static const char STR_OSDSCREEN_OSD0_de[] PROGMEM = "OSD0";
#define STR_OSDSCREEN_OSD0_en STR_OSDSCREEN_OSD0_de
 
static const char STR_OSDSCREEN_OSD1_de[] PROGMEM = "OSD1";
#define STR_OSDSCREEN_OSD1_en STR_OSDSCREEN_OSD1_de
 
static const char STR_OSDSCREEN_OSD2_de[] PROGMEM = "OSD2";
#define STR_OSDSCREEN_OSD2_en STR_OSDSCREEN_OSD2_de
 
static const char NOMKFOUND_de[] PROGMEM = "keinen MK gefunden!";
static const char NOMKFOUND_en[] PROGMEM = "no MK found!";
 
static const char STR_ERROR_de[] PROGMEM = "FEHLER";
static const char STR_ERROR_en[] PROGMEM = "ERROR";
 
static const char ERROR_NODATA_de[] PROGMEM = "MK Datenverlust!";
static const char ERROR_NODATA_en[] PROGMEM = "MK Data lost!";
 
static const char MSG_LOADSETTINGS_de[] PROGMEM = "lade Settings...";
static const char MSG_LOADSETTINGS_en[] PROGMEM = "loading settings...";
 
static const char MSG_ACTIVATESETTING_de[] PROGMEM = "aktiviere Setting...";
static const char MSG_ACTIVATESETTING_en[] PROGMEM = "activate setting...";
 
static const char EDIT_SETTING_de[] PROGMEM = "Bearbeiten";
static const char EDIT_SETTING_en[] PROGMEM = "edit";
 
static const char STR_VON_de[] PROGMEM = "von";
static const char STR_VON_en[] PROGMEM = "from";
 
static const char STR_NACH_de[] PROGMEM = "nach";
static const char STR_NACH_en[] PROGMEM = "to";
 
static const char STR_PKT_de[] PROGMEM = "PKT";
#define STR_PKT_en STR_PKT_de
 
static const char STR_ACTIVE_de[] PROGMEM = "AKTIV!";
static const char STR_ACTIVE_en[] PROGMEM = "ACTIVE!";
 
static const char MODULE_EXIST_de[] PROGMEM = "Modul vorhanden";
static const char MODULE_EXIST_en[] PROGMEM = "Module exist";
 
static const char STR_INITIALIZE_de[] PROGMEM = "Initialisieren";
static const char STR_INITIALIZE_en[] PROGMEM = "Initialize";
 
static const char STR_LONGPRESS_de[] PROGMEM = "langer Tastendruck:";
static const char STR_LONGPRESS_en[] PROGMEM = "long press:";
 
static const char STR_FAV_ADD_de[] PROGMEM = "Fav hinzugefügt!";
static const char STR_FAV_ADD_en[] PROGMEM = "fav added!";
 
static const char STR_FAV_FULL_de[] PROGMEM = "* Fav ist voll *";
static const char STR_FAV_FULL_en[] PROGMEM = "* fav is full *";
 
static const char STR_FAV_EXIST_de[] PROGMEM = "* Fav vorhanden *";
static const char STR_FAV_EXIST_en[] PROGMEM = "* fav exists*";
 
static const char STR_FAV_NOTEXIST_de[] PROGMEM = "kein Fav vorhanden!";
static const char STR_FAV_NOTEXIST_en[] PROGMEM = "no fav exist!";
 
static const char STR_MENUCTRL_DELITEM_de[] PROGMEM = "Eintrag entfernt!";
static const char STR_MENUCTRL_DELITEM_en[] PROGMEM = "item deleted!";
 
static const char STR_MENUCTRL_DELASK_de[] PROGMEM = "Eintrag entfernen?";
static const char STR_MENUCTRL_DELASK_en[] PROGMEM = "delete item?";
 
static const char STR_MENUCTRL_NOTPOSSIBLE_de[] PROGMEM = "nicht möglich!";
static const char STR_MENUCTRL_NOTPOSSIBLE_en[] PROGMEM = "not possible";
 
static const char STR_HELP_PKTOFFTIME1_de[] PROGMEM = "Minuten (0=Aus)";
static const char STR_HELP_PKTOFFTIME1_en[] PROGMEM = "minutes (0=off)";
 
static const char STR_HELP_LOWBAT1_de[] PROGMEM = "<4.20 Einzelzelle ";
static const char STR_HELP_LOWBAT1_en[] PROGMEM = "<4.20 single cell ";
 
static const char STR_HELP_LOWBAT2_de[] PROGMEM = ">4.20 Gesamtspannu.";
static const char STR_HELP_LOWBAT2_en[] PROGMEM = ">4.20 total voltage";
 
static const char STR_HELP_LIPOOFFSET1_de[] PROGMEM = "verstellen, bis die";
static const char STR_HELP_LIPOOFFSET1_en[] PROGMEM = "adjust offset until";
 
static const char STR_HELP_LIPOOFFSET2_de[] PROGMEM = "Spannung passt!";
static const char STR_HELP_LIPOOFFSET2_en[] PROGMEM = "voltage fits!";
 
static const char STR_DATA_de[] PROGMEM = "Daten";
static const char STR_DATA_en[] PROGMEM = "data";
 
static const char STR_READING_de[] PROGMEM = "lese";
static const char STR_READING_en[] PROGMEM = "reading";
 
static const char STR_LABELS_de[] PROGMEM = "Labels";
static const char STR_LABELS_en[] PROGMEM = "labels";
 
static const char STR_EXTSV2MODULE_de[] PROGMEM = "externes SV2-Modul";
static const char STR_EXTSV2MODULE_en[] PROGMEM = "external SV2 module";
 
static const char STR_ATTENTION_de[] PROGMEM = "* ACHTUNG *";
static const char STR_ATTENTION_en[] PROGMEM = "* ATTENTION *";
 
static const char STR_SWITCHOFFMK_de[] PROGMEM = "Kopter ausschalten!";
static const char STR_SWITCHOFFMK_en[] PROGMEM = "switch off kopter!";
 
static const char STR_WI232CONFIG_de[] PROGMEM = "Wi.232 Konfig.";
static const char STR_WI232CONFIG_en[] PROGMEM = "Wi.232 Config";
 
static const char STR_USBCONNECTED_de[] PROGMEM = "mit USB verbunden";
static const char STR_USBCONNECTED_en[] PROGMEM = "connected with USB";
 
static const char STR_SEEMKWIKI_de[] PROGMEM = "siehe MK-Wiki:";
static const char STR_SEEMKWIKI_en[] PROGMEM = "see MK-Wiki:";
 
static const char STR_PKT_SWITCHOFF_NOW_de[] PROGMEM = "jetzt ausschalten?";
static const char STR_PKT_SWITCHOFF_NOW_en[] PROGMEM = "switch off now?";
 
static const char STR_PKT_RESTART_NOW_de[] PROGMEM = "PKT neu starten!";
static const char STR_PKT_RESTART_NOW_en[] PROGMEM = "restart PKT!";
 
static const char STR_WI232_ACTIVATE_de[] PROGMEM = "aktiviere Wi.232!";
static const char STR_WI232_ACTIVATE_en[] PROGMEM = "activate Wi.232!";
 
static const char STR_WAITSATFIX_de[] PROGMEM = "* warte auf Satfix *";
static const char STR_WAITSATFIX_en[] PROGMEM = "* waiting satfix *";
 
static const char STR_GPSMOUSECONNECT_de[] PROGMEM = "verbinde GPS-Maus";
static const char STR_GPSMOUSECONNECT_en[] PROGMEM = "search gps-mouse";
 
static const char STR_GPSMOUSEDISCONNECT_de[] PROGMEM = "trenne GPS-Maus";
static const char STR_GPSMOUSEDISCONNECT_en[] PROGMEM = "disjoin gps-mouse";
 
static const char STR_NOBTM222_de[] PROGMEM = "kein BTM222 vorh.";
static const char STR_NOBTM222_en[] PROGMEM = "no BTM222 installed";
 
static const char STR_NOGPSMOUSE_de[] PROGMEM = "keine GPS-Maus!";
static const char STR_NOGPSMOUSE_en[] PROGMEM = "no gps-mouse!";
 
static const char STR_GPSMOUSECONNECTION_de[] PROGMEM = "GPS-Maus Verbindung";
static const char STR_GPSMOUSECONNECTION_en[] PROGMEM = "gps-mouse connection";
 
static const char STR_SEARCH_BT_ASK_de[] PROGMEM = "BT Geräte suchen?";
static const char STR_SEARCH_BT_ASK_en[] PROGMEM = "search BT devices?";
 
static const char STR_SEARCH_BT_de[] PROGMEM = "suche BT Geräte";
static const char STR_SEARCH_BT_en[] PROGMEM = "search BT devices";
 
static const char STR_NO_BT_FOUND_de[] PROGMEM = "kein Gerät gefunden";
static const char STR_NO_BT_FOUND_en[] PROGMEM = "no device found";
 
static const char STR_BT_DEVICES_de[] PROGMEM = "BT Geräte";
static const char STR_BT_DEVICES_en[] PROGMEM = "BT devices";
 
static const char STR_BT_SEARCHTIME_de[] PROGMEM = "(ca. 2 Minuten)";
static const char STR_BT_SEARCHTIME_en[] PROGMEM = "(ca. 2 minutes)";
 
static const char STR_BT_LOSTDATA_de[] PROGMEM = "BT Datenverlust";
static const char STR_BT_LOSTDATA_en[] PROGMEM = "BT data loss";
 
static const char STR_METERS_de[] PROGMEM = "Meter";
static const char STR_METERS_en[] PROGMEM = "meters";
 
 
static const char STR_WAITNMEA_de[] PROGMEM = "Warte auf GPS Daten";
static const char STR_WAITNMEA_en[] PROGMEM = "waiting for GPS Data";
 
 
//******************************************************************
// hier stehen lassen, alle neuen Strings hier drüber einfügen
static const char LAST_STR_de[] PROGMEM = "Lastring";
#define LAST_STR_en LAST_STR_de
//******************************************************************
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
const char * const strings[] PROGMEM =
{
KEYLINE1_de, KEYLINE1_en,
KEYLINE2_de, KEYLINE2_en,
KEYLINE3_de, KEYLINE3_en,
KEYLINE4_de, KEYLINE4_en,
KEYLINE5_de, KEYLINE5_en,
KEYCANCEL_de, KEYCANCEL_en,
BOOT1_de, BOOT1_en,
BOOT2_de, BOOT2_en,
START_LASTPOS_de, START_LASTPOS_en,
START_LASTPOS1_de, START_LASTPOS1_en,
START_LASTPOS2_de, START_LASTPOS2_en,
START_LASTPOS3_de, START_LASTPOS3_en,
START_SEARCHFC_de, START_SEARCHFC_en,
ENDE_de, ENDE_en,
OK_de, OK_en,
FEHLER_de, FEHLER_en,
AKTIV_de, AKTIV_en,
STR_SAVE_de, STR_SAVE_en,
STR_SAVING_de, STR_SAVING_en,
STR_DISCARD_de, STR_DISCARD_en,
STR_COPY_de, STR_COPY_en,
STR_SEARCH_de, STR_SEARCH_en,
STR_FOUND_de, STR_FOUND_en,
STR_SET_de, STR_SET_en,
STR_WITH_de, STR_WITH_en,
STR_WITHOUT_de, STR_WITHOUT_en,
STR_SWITCHMOTOROFF_de, STR_SWITCHMOTOROFF_en,
ON_de, ON_en,
OFF_de, OFF_en,
ESC_de, ESC_en,
SHUTDOWN_de, SHUTDOWN_en,
YESNO_de, YESNO_en,
NOYES_de, NOYES_en,
DELETEDATA_de, DELETEDATA_en,
UPDATE1_de, UPDATE1_en,
UPDATE2_de, UPDATE2_en,
UPDATE3_de, UPDATE3_en,
ENDSTART_de, ENDSTART_en,
CONNECT13_de, CONNECT13_en,
KABEL_de, KABEL_en,
SLAVE_de, SLAVE_en,
NORMAL_de, NORMAL_en,
REVERSE_de, REVERSE_en,
ENDOK_de, ENDOK_en,
EEPROM1_de, EEPROM1_en,
EEPROM2_de, EEPROM2_en,
DEUTSCH_de, DEUTSCH_en,
ENGLISCH_de, ENGLISCH_en,
YES_de, YES_en,
NOO_de, NOO_en,
OSD_3D_V_de, OSD_3D_V_en,
OSD_3D_H_de, OSD_3D_H_en,
OSD_3D_L_de, OSD_3D_L_en,
OSD_3D_R_de, OSD_3D_R_en,
OSD_3D_NICK_de, OSD_3D_NICK_en,
OSD_3D_ROLL_de, OSD_3D_ROLL_en,
OSD_ERROR_de, OSD_ERROR_en,
PARA_AKTIVI_de, PARA_AKTIVI_en,
PARA_COPY_de, PARA_COPY_en,
PARA_COPYQ_de, PARA_COPYQ_en,
GPS2_de, GPS2_en,
STATS_ITEM_0_de, STATS_ITEM_0_en,
STATS_ITEM_1_de, STATS_ITEM_1_en,
STATS_ITEM_2_de, STATS_ITEM_2_en,
STATS_ITEM_3_de, STATS_ITEM_3_en,
STATS_ITEM_4_de, STATS_ITEM_4_en,
STATS_ITEM_5_de, STATS_ITEM_5_en,
STATS_ITEM_6_de, STATS_ITEM_6_en,
POTI_de, POTI_en,
TASTER_de, TASTER_en,
STAT_OSDBL_de, STAT_OSDBL_en,
STAT_ERROR_de, STAT_ERROR_en,
STAT_GPS_de, STAT_GPS_en,
STAT_POS_de, STAT_POS_en,
STAT_ALL_de, STAT_ALL_en,
DELETE_de, DELETE_en,
STR_OSDSCREEN_GENERAL_de, STR_OSDSCREEN_GENERAL_en,
STR_OSDSCREEN_NAVIGATION_de, STR_OSDSCREEN_NAVIGATION_en,
STR_OSDSCREEN_WAYPOINTS_de, STR_OSDSCREEN_WAYPOINTS_en,
STR_OSDSCREEN_ELECTRIC_de, STR_OSDSCREEN_ELECTRIC_en,
STR_OSDSCREEN_MKSTATUS_de, STR_OSDSCREEN_MKSTATUS_en,
STR_OSDSCREEN_USERGPS_de, STR_OSDSCREEN_USERGPS_en,
STR_OSDSCREEN_3DLAGE_de, STR_OSDSCREEN_3DLAGE_en,
STR_OSDSCREEN_STATISTIC_de, STR_OSDSCREEN_STATISTIC_en,
STR_OSDSCREEN_OSD0_de, STR_OSDSCREEN_OSD0_en,
STR_OSDSCREEN_OSD1_de, STR_OSDSCREEN_OSD1_en,
STR_OSDSCREEN_OSD2_de, STR_OSDSCREEN_OSD2_en,
NOMKFOUND_de, NOMKFOUND_en,
STR_ERROR_de, STR_ERROR_en,
ERROR_NODATA_de, ERROR_NODATA_en,
MSG_LOADSETTINGS_de, MSG_LOADSETTINGS_en,
MSG_ACTIVATESETTING_de, MSG_ACTIVATESETTING_en,
EDIT_SETTING_de, EDIT_SETTING_en,
STR_VON_de, STR_VON_en,
STR_NACH_de, STR_NACH_en,
STR_PKT_de, STR_PKT_en,
STR_ACTIVE_de, STR_ACTIVE_en,
MODULE_EXIST_de, MODULE_EXIST_en,
STR_INITIALIZE_de, STR_INITIALIZE_en,
STR_LONGPRESS_de, STR_LONGPRESS_en,
STR_FAV_ADD_de, STR_FAV_ADD_en,
STR_FAV_FULL_de, STR_FAV_FULL_en,
STR_FAV_EXIST_de, STR_FAV_EXIST_en,
STR_FAV_NOTEXIST_de, STR_FAV_NOTEXIST_en,
STR_MENUCTRL_DELITEM_de, STR_MENUCTRL_DELITEM_en,
STR_MENUCTRL_DELASK_de, STR_MENUCTRL_DELASK_en,
STR_MENUCTRL_NOTPOSSIBLE_de, STR_MENUCTRL_NOTPOSSIBLE_en,
STR_HELP_PKTOFFTIME1_de, STR_HELP_PKTOFFTIME1_en,
STR_HELP_LOWBAT1_de, STR_HELP_LOWBAT1_en,
STR_HELP_LOWBAT2_de, STR_HELP_LOWBAT2_en,
STR_HELP_LIPOOFFSET1_de, STR_HELP_LIPOOFFSET1_en,
STR_HELP_LIPOOFFSET2_de, STR_HELP_LIPOOFFSET2_en,
STR_DATA_de, STR_DATA_en,
STR_READING_de, STR_READING_en,
STR_LABELS_de, STR_LABELS_en,
STR_EXTSV2MODULE_de, STR_EXTSV2MODULE_en,
STR_ATTENTION_de, STR_ATTENTION_en,
STR_SWITCHOFFMK_de, STR_SWITCHOFFMK_en,
STR_WI232CONFIG_de, STR_WI232CONFIG_en,
STR_USBCONNECTED_de, STR_USBCONNECTED_en,
STR_SEEMKWIKI_de, STR_SEEMKWIKI_en,
STR_PKT_SWITCHOFF_NOW_de, STR_PKT_SWITCHOFF_NOW_en,
STR_PKT_RESTART_NOW_de, STR_PKT_RESTART_NOW_en,
STR_WI232_ACTIVATE_de, STR_WI232_ACTIVATE_en,
STR_WAITSATFIX_de, STR_WAITSATFIX_en,
STR_GPSMOUSECONNECT_de, STR_GPSMOUSECONNECT_en,
STR_GPSMOUSEDISCONNECT_de, STR_GPSMOUSEDISCONNECT_en,
STR_NOBTM222_de, STR_NOBTM222_en,
STR_NOGPSMOUSE_de, STR_NOGPSMOUSE_en,
STR_GPSMOUSECONNECTION_de, STR_GPSMOUSECONNECTION_en,
STR_SEARCH_BT_ASK_de, STR_SEARCH_BT_ASK_en,
STR_SEARCH_BT_de, STR_SEARCH_BT_en,
STR_NO_BT_FOUND_de, STR_NO_BT_FOUND_de,
STR_BT_DEVICES_de, STR_BT_DEVICES_en,
STR_BT_SEARCHTIME_de, STR_BT_SEARCHTIME_en,
STR_BT_LOSTDATA_de, STR_BT_LOSTDATA_en,
STR_METERS_de, STR_METERS_en,
STR_WAITNMEA_de, STR_WAITNMEA_en,
 
 
//******************************************************************
// hier stehen lassen, alle neuen Strings hier drüber einfügen
LAST_STR_de, LAST_STR_en,
 
}; // end: strings
 
 
 
//--------------------------------------------------------------
// gibt je nach konfigurierter Sprache den entsprechenden String
// aus der obigen Stringtabelle zureuck
//--------------------------------------------------------------
const char * strGet( int str_no)
{
if( Config.DisplayLanguage > 1 ) Config.DisplayLanguage = 1;
 
if( Config.DisplayLanguage == 1 ) return (const char*) pgm_read_word( &strings[(str_no*2)+1] ); // Englisch (=1)
 
return (const char*) pgm_read_word( &strings[str_no*2] ); // Deutsch (=0)
}
 
 
 
//--------------------------------------------------------------
// gibt je nach konfigurierter Sprache Parameter str_de oder
// Parameter str_en zurueck
//
// wird z.B. in Verbindung mit de/en-Menuetexten verwendet
//--------------------------------------------------------------
const char * strGetLanguage( char const *str_de, char const *str_en)
{
if( Config.DisplayLanguage > 1 ) Config.DisplayLanguage = 1;
 
if( Config.DisplayLanguage == 1 ) return str_en; // Englisch (=1)
 
return str_de; // Deutsch (=0)
}
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/messages.h
0,0 → 1,205
/****************************************************************************************
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Languagesupport: *
* http://www.netrino.com/Embedded-Systems/How-To/Firmware-Internationalization *
* Nigel Jones *
****************************************************************************************/
 
//############################################################################
//# HISTORY messages.h
//#
//# 08.08.2015 cebra
//# - add: STR_WAITNMEA
//#
//# 27.06.2014 OG
//# - add: STR_BT_SEARCHTIME, STR_METERS, STR_BT_LOSTDATA
//#
//# 25.06.2014 OG
//# - add: STR_SEARCH_BT_ASK, STR_SEARCH_BT, STR_NO_BT_FOUND
//#
//# 24.06.2014 OG
//# - add: STR_NOBTM222, STR_NOGPSMOUSE, STR_GPSMOUSECONNECTION
//# - add: STR_GPSMOUSECONNECT, STR_GPSMOUSEDISCONNECT
//#
//# 23.06.2014 OG
//# - add: STR_WAITSATFIX
//#
//# 13.06.2014 OG
//# - add: STR_PKT_SWITCHOFF_NOW, STR_PKT_RESTART_NOW, STR_WI232_ACTIVATE
//# - del: mehrere CONNECT.. Strings
//# - del: DISPLAY3
//#
//# 11.06.2014 OG
//# - add: strGetLanguage()
//# - add: KEYLINE5
//# - del: TESTSTRING
//#
//# 10.06.2014 OG
//# - add: STR_WI232CONFIG, STR_USBCONNECTED, STR_SEEMKWIKI
//# - add: STR_ATTENTION, STR_SWITCHOFFMK
//# - del: CONNECT21, CONNECT22, CONNECT24, CONNECT25
//#
//# 08.06.2014 OG
//# - add: STR_EXTSV2MODULE
//#
//# 04.06.2014 OG
//# - add: STR_DATA
//# - add: STR_READING, STR_LABELS
//#
//# 01.06.2014 OG
//# - del: weitere unbenoetigte Strings geloescht
//#
//# 31.05.2014 OG
//# - add: STR_WITH, STR_WITHOUT
//# - del: etliche Strings die nicht mehr benoetigt werden geloescht
//#
//# 30.05.2014 OG
//# - add: STR_HELP_LIPOOFFSET1, STR_HELP_LIPOOFFSET2
//# - add: STR_HELP_LOWBAT1, STR_HELP_LOWBAT2
//#
//# 29.05.2014 OG
//# - del: etliche Strings die nicht mehr benoetigt werden geloescht
//#
//# 28.05.2014 OG
//# - add: STR_HELP_PKTLIGHTOFF1
//#
//# 26.05.2014 OG
//# - add: STR_OSDSCREEN_WAYPOINTS
//# - del: CHANGENORMREV1, CHANGENORMREV2
//#
//# 06.05.2014 OG
//# - add: STR_MENUCTRL_DELITEM, STR_MENUCTRL_DELASK, STR_MENUCTRL_NOTPOSSIBLE
//# - del: STR_FAV_DELETE
//#
//# 03.05.2014 OG
//# - add: STR_FAV_ADD, STR_FAV_DELETE, STR_FAV_FULL, STR_FAV_EXIST, STR_FAV_NOTEXIST
//#
//# 28.04.2014 OG
//# - add: STR_LONGPRESS
//#
//# 04.04.2014 OG
//# - add: STR_SEARCH, STR_FOUND, STR_SET
//#
//# 03.04.2014 OG
//# - add: STR_INITIALIZE
//#
//# 01.04.2014 OG
//# - add: BLE_EXIST, MODULE_EXIST
//#
//# 30.03.2014 OG
//# - chg: NUM_LANG von 3 auf 2 reduziert (Hollaendisch vollstaendig geloescht)
//#
//# 27.03.2014 OG
//# - add: STR_SAVE, STR_DISCARD, STR_COPY, STR_SWITCHMOTOROFF, STR_SAVING
//#
//# 19.03.2014 OG
//# - add: KEYCANCEL
//#
//# 27.02.2014 OG
//# - add: STR_ACTIVE
//#
//# 20.02.2014 OG
//# - add: STR_VON, STR_NACH
//#
//# 17.02.2014 OG
//# - add: EDIT_SETTING
//# - add: STR_ERROR, ERROR_NODATA, MSG_LOADSETTINGS, MSG_ACTIVATESETTING
//#
//# 12.02.2014 OG
//# - del: START_MSG2
//# - add:: NOMKFOUND
//#
//# 04.02.2014 OG
//# - add: CHANGENORMREV1, CHANGENORMREV2
//#
//# 03.02.2014 OG
//# - add: SHOWCELLU
//#
//# 02.02.2014 OG
//# - del: START_LASTPOSDEL
//#
//# 24.01.2014 OG
//# - add: MSG_WARNUNG, UPDATE3
//#
//# 15.07.2013 Cebra
//# - add: Wlan Security erweitert
//#
//# 07.07.2013 OG
//# - add: OSD-Screen Namen
//#
//# 02.07.2013 Cebra
//# - add: Menuetexte fuer Wlan
//#
//# 27.06.2013 OG
//# - del: OSD_HOMEMKVIEW
//#
//# 26.06.2013 OG
//# - del: einige nicht mehr benoetigte Texte
//# - chg: START_VERSIONCHECK5 zu MSG_FEHLER2
//#
//# 15.06.2013 OG
//# - add: OSD_MKSetting
//#
//# 13.06.2013 CB
//# - add: ENUM Texte für OSD Statistik erweitert
//#
//############################################################################
 
#ifndef MESSAGES_H
#define MESSAGES_H
 
//---------------------------------------------------------------------------------------------------------------------
// Typdefinitionen für alle verwendeten Strings, LAST_STR muss am Ende stehen bleiben
typedef enum
{
KEYLINE1, KEYLINE2, KEYLINE3, KEYLINE4, KEYLINE5, KEYCANCEL, BOOT1, BOOT2,
START_LASTPOS, START_LASTPOS1, START_LASTPOS2, START_LASTPOS3,
START_SEARCHFC, ENDE, OK, FEHLER, AKTIV, STR_SAVE, STR_SAVING, STR_DISCARD, STR_COPY, STR_SEARCH,
STR_FOUND, STR_SET, STR_WITH, STR_WITHOUT, STR_SWITCHMOTOROFF,
ON, OFF, ESC, SHUTDOWN, YESNO, NOYES,DELETEDATA, UPDATE1, UPDATE2, UPDATE3, ENDSTART, CONNECT13,
KABEL, SLAVE, NORMAL, REVERSE, ENDOK, EEPROM1, EEPROM2, DEUTSCH, ENGLISCH,
YES, NOO, OSD_3D_V, OSD_3D_H, OSD_3D_L,
OSD_3D_R, OSD_3D_NICK, OSD_3D_ROLL, OSD_ERROR, PARA_AKTIVI, PARA_COPY, PARA_COPYQ,
GPS2, STATS_ITEM_0, STATS_ITEM_1, STATS_ITEM_2, STATS_ITEM_3, STATS_ITEM_4, STATS_ITEM_5, STATS_ITEM_6,
POTI, TASTER, STAT_OSDBL, STAT_ERROR, STAT_GPS, STAT_POS, STAT_ALL, DELETE,
STR_OSDSCREEN_GENERAL, STR_OSDSCREEN_NAVIGATION, STR_OSDSCREEN_WAYPOINTS, STR_OSDSCREEN_ELECTRIC, STR_OSDSCREEN_MKSTATUS, STR_OSDSCREEN_USERGPS, STR_OSDSCREEN_3DLAGE,
STR_OSDSCREEN_STATISTIC, STR_OSDSCREEN_OSD0, STR_OSDSCREEN_OSD1, STR_OSDSCREEN_OSD2, NOMKFOUND,
STR_ERROR, ERROR_NODATA, MSG_LOADSETTINGS, MSG_ACTIVATESETTING, EDIT_SETTING,
STR_VON, STR_NACH, STR_PKT, STR_ACTIVE, MODULE_EXIST, STR_INITIALIZE, STR_LONGPRESS,
STR_FAV_ADD, STR_FAV_FULL, STR_FAV_EXIST, STR_FAV_NOTEXIST, STR_MENUCTRL_DELITEM, STR_MENUCTRL_DELASK, STR_MENUCTRL_NOTPOSSIBLE,
STR_HELP_PKTOFFTIME1, STR_HELP_LOWBAT1, STR_HELP_LOWBAT2, STR_HELP_LIPOOFFSET1, STR_HELP_LIPOOFFSET2,
STR_DATA, STR_READING, STR_LABELS, STR_EXTSV2MODULE, STR_ATTENTION, STR_SWITCHOFFMK, STR_WI232CONFIG, STR_USBCONNECTED, STR_SEEMKWIKI,
STR_PKT_SWITCHOFF_NOW, STR_PKT_RESTART_NOW, STR_WI232_ACTIVATE,
STR_WAITSATFIX, STR_GPSMOUSECONNECT, STR_GPSMOUSEDISCONNECT, STR_NOBTM222, STR_NOGPSMOUSE, STR_GPSMOUSECONNECTION, STR_SEARCH_BT_ASK,
STR_SEARCH_BT, STR_NO_BT_FOUND, STR_BT_DEVICES, STR_BT_SEARCHTIME, STR_BT_LOSTDATA, STR_METERS,STR_WAITNMEA,
LAST_STR
} STR;
 
 
#define NUM_LANG 2 // German, English
 
 
const char * strGet( int str_no);
const char * strGetLanguage( char const *str_de, char const *str_en);
 
void Test_Language (void); // bleibt für Tests
 
 
 
#endif /* _MESSAGES_H_ */
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mk/mkbase.c
0,0 → 1,825
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY mkbase.c
//#
//# 21.06.2014 OG
//# - chg: searchMK() schaltet am Ende wieder auf die NC um sofern diese
//# vorhanden ist
//#
//# 19.05.2014 OG
//# - chg: MKVersion_Setting_print() umgestellt auf strGet(STR_ERROR) fuer
//# Multi-Sprachenunterstuetzung
//#
//# 14.05.2014 OG
//# - chg: include "paramset.h" geaendert auf "../mksettings/paramset.h"
//#
//# 13.05.2014 OG
//# - chg: MK_Info() - del: MKINFO_AUTO_REFRESH (nicht mehr unterstuetzt)
//# - chg: MK_Setting_write() - del: unused variable 'lsetting'
//#
//# 17.04.2014 OG
//# - chg: MK_Setting_load - Ansprechverhalten verbessert wenn Windows
//# Mikrokoptertool aktiv ist
//#
//# 29.03.2014 OG
//# - del: MK_Show_LastGPS_Position() -> jetzt: OSDDATA_ShowLastGPSPosition()/osddata.c
//#
//# 28.03.2014 OG
//# - add: MK_Show_LastGPS_Position() - ehemals in main.c
//#
//# 24.03.2014 OG
//# - chg: searchMK(): doppeltes MK_SwitchToNC() um evtl. vorhandene NC
//# zuverlaessiger zu erkennen
//# - fix: searchMK(): RetVal initialisiert
//# - chg: Default-Anzeigezeit von MK_Info() in searchMK() auf 5 Sek. reduziert
//#
//# 21.02.2014 OG
//# - fix: MKVersion_Setting_print() Anzeige der Settings-Nummer gekuerzt
//#
//# 20.02.2014 OG
//#- chg: searchMK() auf aktuelle Version von PKT_TitlePKTVersion() angepasst
//#
//# 20.02.2014 OG
//# - chg: MKVersion_Setting_print() um ein paar Bytes zu sparen
//# - chg: MK_Info() um ein paar Bytes zu sparen
//#
//# 16.02.2014 OG
//# - add: MK_SwitchToNC(), MK_SwitchToFC(), MK_SwitchToMAG(), MK_SwitchToGPS()
//# - add: MK_Setting_write(), MK_Setting_change()
//# - chg: umbenannt: MK_load_setting() zu MK_Setting_load()
//#
//# 13.02.2014 OG
//# - add: MKVersion_Cmp() (Anleitung bei der Funktion beachten!)
//# - del: WrongFCVersion
//#
//# 12.02.2014 OG
//# - chg: verschiedene Verbesserungen an MK_Info(), MK_load_settings(), searckMK()
//#
//# 10.02.2014 OG
//# - add: MKVersion_Setting_print()
//#
//# 09.02.2014 OG
//# - add: MK_Info()
//#
//# 08.02.2014 OG
//# - chg: searckMK() Anpassung an MKVersion
//# - chg: MK_load_setting() Anpassung an MKVersion und Parameter geaendert
//# - add: MKVersion_Init(), MKVersion_print_at()
//#
//# 03.02.2014 OG
//# - chg: Titelanzeige in searchMK() umgestellt auf PKT_ShowTitlePKTVersion()
//# - chg: kleine Aenderung in der Anzeige "für FC..." in searchMK()
//#
//# 29.01.2014 OG
//# - Ausgliederungen aus main.c: MK_load_setting(), searchMK()
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <string.h>
#include <util/atomic.h>
#include <avr/wdt.h>
#include <avr/eeprom.h>
 
 
//#include "../lipo/lipo.h"
#include "../main.h"
#include "../lipo/lipo.h"
#include "../lcd/lcd.h"
#include "../uart/usart.h"
 
#include "../uart/uart1.h"
#include "../mk-data-structs.h"
//#include "../menu.h"
#include "../timer/timer.h"
#include "../eeprom/eeprom.h"
#include "../messages.h"
#include "../utils/scrollbox.h"
#include "../utils/xutils.h"
#include "../pkt/pkt.h"
#include "../mksettings/paramset.h"
#include "mkbase.h"
 
 
 
//----------------------------
// MK-Versionsinformationen
// global verfuegbar
//----------------------------
MKVersion_t MKVersion;
 
uint8_t cmd;
 
 
//#############################################################################################
//# 1. MKVersion
//#############################################################################################
 
 
//--------------------------------------------------------------
// MKVersion_Init()
//
// initialisiert MKVersion auf 0
//--------------------------------------------------------------
void MKVersion_Init( void )
{
memset( &MKVersion, 0, sizeof(MKVersion_t) );
}
 
 
 
//--------------------------------------------------------------
// value = MKVersion_Cmp( FC/NCver, SWMajor,SWMinor,SWPatch )
//
// Vergleicht eine uebergebene FC/NC-Version mit der vom MK
// ermittelten Version
//
// Parameter:
//
// FC/NCver: MKVersion.FCVer oder MKVersion.NCVer
//
// SWMajor,SWMinor,SWPatch: siehe nachfolgendes...
//
//---
// Beispiel aus osd.c/OSD_MK_GetData():
//
// v = MKVersion_Cmp( MKVersion.NCVer, 0,30,'g' ); // pruefe auf NC-Version "0.30g"
//
// if( v && (v >= GIVEN_VERSION) ) // wenn aktuelle NC-Version >= "0.30g"...
// { ...
//
// Sowas geht auch:
//
// if( v && (v == GIVEN_VERSION) ) // nur wenn aktuelle NC-Version == "0.30g"...
//
// oder:
//
// if( v && (v < GIVEN_VERSION) ) // nur wenn aktuelle NC-Version kleiner als "0.30g"...
//
//---
// Warum "if( v && ..." ?
//
// Wenn das PKT keine FC/NC-Version ermitteln konnte, und somit kein
// Vergleich moeglich ist, gibt MKVersion_Cmp() false (=0) zurueck!
//--------------------------------------------------------------
uint8_t MKVersion_Cmp( Version_t ver, unsigned char SWMajor, unsigned char SWMinor, unsigned char SWPatch )
{
SWPatch = SWPatch -'a';
 
if( ver.SWMajor > 0 || ver.SWMinor > 0 ) // NC/FC Version erkannt?
{
if( (ver.SWMajor == SWMajor) && (ver.SWMinor == SWMinor) && (ver.SWPatch == SWPatch) )
return VERSION_EQUAL; // ==2
 
if( ver.SWMajor != SWMajor )
{
if( ver.SWMajor < SWMajor )
return VERSION_LOWER; // ==1
else
return VERSION_GREATER; // ==3
}
 
if( ver.SWMinor != SWMinor )
{
if( ver.SWMinor < SWMinor )
return VERSION_LOWER; // ==1
else
return VERSION_GREATER; // ==3
}
 
if( ver.SWPatch < SWPatch )
return VERSION_LOWER; // ==1
else
return VERSION_GREATER; // ==3
}
return VERSION_NO; // ==0
}
 
 
 
//--------------------------------------------------------------
// MKVersion_print_at()
//
// zeigt die aktuelle FC, NC Version auf dem LCD an
//
// Parameter:
// what: NC, FC,
//--------------------------------------------------------------
void MKVersion_print_at( uint8_t x, uint8_t y, uint8_t what, uint8_t drawmode, int8_t xoffs, int8_t yoffs )
{
const char *mask = PSTR("%1u.%02u%c");
const char *nostr = PSTR("-----");
 
switch(what)
{
case FC: if( MKVersion.FCVer.SWMajor > 0 || MKVersion.FCVer.SWMinor > 0 )
lcdx_printf_at_P( x, y, drawmode, xoffs, yoffs, mask, MKVersion.FCVer.SWMajor, MKVersion.FCVer.SWMinor, MKVersion.FCVer.SWPatch+'a' );
else
lcdx_printp_at( x,y, nostr, drawmode, xoffs, yoffs);
break;
 
case NC: if( (MKVersion.NCVer.SWMajor != 0) || (MKVersion.NCVer.SWMinor != 0) )
lcdx_printf_at_P( x, y, drawmode, xoffs, yoffs, PSTR("%1u.%02u%c"), MKVersion.NCVer.SWMajor, MKVersion.NCVer.SWMinor, MKVersion.NCVer.SWPatch+'a' );
else
lcdx_printp_at( x,y, nostr, drawmode, xoffs, yoffs);
break;
}
}
 
 
 
//--------------------------------------------------------------
// MKVersion_Setting_print( y, drawmode, xoffs,yoffs)
//
// Zeigt das aktuelle MK-Setting aus MKVersion zentriert in der
// Zeile y auf dem PKT-Screen an
//--------------------------------------------------------------
void MKVersion_Setting_print( uint8_t y, uint8_t drawmode, uint8_t xoffs, uint8_t yoffs )
{
char buffer[18]; // String Buffer fuer eine Zeile
 
if( MKVersion.mksetting == 0 )
xsnprintf_P( buffer, 18, PSTR("* %S *"), strGet(STR_ERROR) ); // FC Setting konnte NICHT gelesen werden
 
else if( MKVersion.mksetting != 0 && MKVersion.paramsetOK ) // FC-Setting wurde gelesen...
xsnprintf_P( buffer, 18, PSTR("%u %s"), MKVersion.mksetting, MKVersion.mksettingName ); // ... passende FC-Reversion -> Nummer und Name anzeigen
 
else
xsnprintf_P( buffer, 18, PSTR("%u"), MKVersion.mksetting ); // ... aber FALSCHE FC-Version -> nicht den Namen anzeigen (nur die Nummer)
 
lcdx_print_center( y, (unsigned char *)buffer, drawmode, xoffs,yoffs); // Ausgabe Setting-Name (zentriert)
}
 
 
 
 
//#############################################################################################
//# 2. Sonstiges - MK-Suche, Settings laden, MK-Info
//#############################################################################################
 
#define SWITCH_DELAY 25 // alt 50
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void MK_SwitchToNC( void )
{
// switch to NC
USART_putc (0x1b);
USART_putc (0x1b);
USART_putc (0x55);
USART_putc (0xaa);
USART_putc (0x00);
current_hardware = NC;
_delay_ms( SWITCH_DELAY );
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void MK_SwitchToFC( void )
{
// switch to FC
cmd = 0x00; // 0 = FC, 1 = MK3MAG, 2 = MKGPS
SendOutData('u', ADDRESS_NC, 1, &cmd, 1);
current_hardware = FC;
_delay_ms( SWITCH_DELAY );
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void MK_SwitchToMAG( void )
{
// switch to MK3MAG
cmd = 0x01; // 0 = FC, 1 = MK3MAG, 2 = MKGPS
SendOutData('u', ADDRESS_NC, 1, &cmd, 1);
current_hardware = MK3MAG;
_delay_ms( SWITCH_DELAY );
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void MK_SwitchToGPS( void )
{
// switch to MKGPS
cmd = 0x02; // 0 = FC, 1 = MK3MAG, 2 = MKGPS
SendOutData('u', ADDRESS_NC, 1, &cmd, 1);
current_hardware = MKGPS;
_delay_ms( SWITCH_DELAY );
}
 
 
 
//--------------------------------------------------------------
// ret = MK_Setting_load( lsetting, &mk_param_struct, showerror)
//
// holt MK-Settings - es wird auf die FC umgeschaltet!
//--------------------------------------------------------------
uint8_t MK_Setting_load( uint8_t lsetting, uint8_t timeout )
{
// timeout = 15 bis 20 ist meist ein guter Wert
 
//MK_SwitchToFC();
 
mode = 'Q'; // Settings Request
rxd_buffer_locked = FALSE;
 
while( !rxd_buffer_locked && timeout )
{
MK_SwitchToFC();
SendOutData( 'q', ADDRESS_FC, 1, &lsetting, 1); // lsetting == 0xff -> aktuelles MK-Setting laden
 
timer2 = 25; // timer ist ggf. belegt von MK_Info() -> versuchen wir es mit timer2....
while( timer2 > 0 && !rxd_buffer_locked );
 
timeout--;
}
 
mode = 0;
 
// Initialisierungen
paramsetInit(0);
 
if( rxd_buffer_locked )
{
Decode64();
paramsetInit( (unsigned char *) pRxData ); // fuellt u.a. auch MKVersion.paramsetRevision
}
 
return MKVersion.mksetting; // wird von paramsetInit() gesetzt/initialisert
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t MK_Setting_write( uint8_t wsetting, uint8_t timeout)
{
//uint8_t timeout = 50;
uint8_t setting;
 
if( !MKVersion.paramsetOK )
{
return 0; // Error
}
 
//MK_SwitchToFC(); // ?
 
setting = 0;
mode = 'S'; // Settings
 
rxd_buffer_locked = FALSE;
 
while( !rxd_buffer_locked && timeout && !setting)
{
SendOutData( 's', ADDRESS_FC, 2, &wsetting, 1, (pRxData+1), paramsetSize() ); // pRxData+1 = die mk_datastruct beginnt bei +1; bei 0 ist die Settingsnummer
 
timer2 = 70;
while( timer2 > 0 && !rxd_buffer_locked );
timeout--;
 
if( rxd_buffer_locked )
{
Decode64();
setting = *pRxData;
 
if( !setting )
rxd_buffer_locked = FALSE;
}
}
 
setting = MK_Setting_load( 0xff, 15); // damit pRxData & MKVersion initialisiert sind
 
return setting;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t MK_Setting_change( uint8_t setting )
{
uint8_t lsetting = 0;
uint8_t wsetting = 0;
 
lsetting = MK_Setting_load( setting, 20);
 
if( lsetting == setting )
{
wsetting = MK_Setting_write( setting, 50);
}
 
/*
//--------------------
// DEBUG...
//--------------------
lcd_printf_at_P( 0, 1, MNORMAL, PSTR("load : %1u (req:%1u)"), lsetting, setting );
lcd_printf_at_P( 0, 2, MNORMAL, PSTR("write: %1u "), wsetting );
if( (setting != lsetting) || (setting != wsetting) )
set_beep( 1000, 0x0f0f, BeepNormal ); // Error
timer2 = 500; while( timer2 > 0 );
*/
 
return wsetting; // 0 = Fehler; oder 1..5 = geschriebenes Setting
}
 
 
 
//--------------------------------------------------------------
// ok = searchMK( showMKInfo )
//
// Parameter:
// showMKInfo: true/false
//--------------------------------------------------------------
uint8_t searchMK( uint8_t showMKInfo )
{
uint8_t timeout;
//uint8_t setting; // aktuelles FC-Setting (1..5)
uint8_t RetVal = false;
uint8_t redraw = true;
uint8_t searchbar_y;
uint8_t searchbar_w = 0;
 
 
MKVersion_Init();
 
//----------------
// Switch to NC
//----------------
MK_SwitchToNC();
_delay_ms(50); // 24.03.2014 OG: manchmal wurde nicht auf eine vorhandene NC umgeschaltet
MK_SwitchToNC(); // evtl. wird das durch doppeltes Senden verbessert
 
//---------------------------------------
// MK-Suchscreen - Versionsabfrage NC
//---------------------------------------
mode = 'V';
 
rxd_buffer_locked = FALSE;
timeout = 50;
 
//searchbar_y = 5*8-1;
searchbar_y = 5*8+2;
 
while( !rxd_buffer_locked )
{
//------------------------
// MK Suchscreen anzeigen
//------------------------
if( redraw )
{
PKT_TitlePKT(); // Titel mit PKT-Version anzeigen (mit Lipo-Anzeige)
lcdx_printp_center( 2, strGet(STR_PKT), MNORMAL, 0,2); // "PKT"
lcdx_printp_at( 0, 3, strGet(START_SEARCHFC), MNORMAL, 0,8); // "suche Mikrokopter..."
 
lcd_printp_at(12, 7, strGet(ENDE), MNORMAL); // Keyline
 
lcd_rect ( 0, searchbar_y , 126, 8, 1); // Rahmen fuer Bar-Anzeige
 
searchbar_w = 2;
 
redraw = false;
}
 
//------------------------
// PKT-LiPo Anzeige
//------------------------
show_Lipo();
 
//------------------------
// MK Datenanfrage
//------------------------
SendOutData( 'v', ADDRESS_ANY, 0); // Versions-Anfrage an MK senden
 
timer = 16; // kurze Verögerung fuer Datenanfrage und Fortschrittsbalken
while( timer > 0 );
 
//------------------------
// Fortschrittsbalken
//------------------------
lcd_frect( 2, searchbar_y+2, searchbar_w, 4, 1); // Fortschrittsbalken zeichnen...
searchbar_w += 2;
if( searchbar_w >= 125 )
{
searchbar_w = 0;
lcd_frect( 2, searchbar_y+2, 123, 4, 0);
}
 
//------------------------
// Tasten abfragen
//------------------------
if( get_key_press(1 << KEY_ESC) )
{
hardware = NO;
return false;
}
 
//------------------------------------------
// Pruefe PKT-Update oder andere PKT-Aktion
//------------------------------------------
if( PKT_CtrlHook() ) // Update vom Updatetool angefordert?
{
redraw = true;
}
}
 
 
 
//--------------------------
// MK gefunden?
//--------------------------
if( rxd_buffer_locked )
{
Decode64();
 
//---
// TODO OG: testen mit entsprechendem Hardware Setup des MK's!
//---
if( (rxd_buffer[1] - 'a') == ADDRESS_FC )
{
hardware = FC;
current_hardware = hardware;
MKVersion.isFC = true;
RetVal = true;
memcpy( &MKVersion.FCVer, (Version_t *) (pRxData), sizeof(Version_t) );
}
 
if( (rxd_buffer[1] - 'a') == ADDRESS_NC )
{
hardware = NC;
current_hardware = hardware;
MKVersion.isNC = true;
RetVal = true;
memcpy( &MKVersion.NCVer, (Version_t *) (pRxData), sizeof(Version_t) );
}
 
 
//--------------------------
// jetzt: Version der FC abfragen
//--------------------------
if( hardware == NC )
{
MK_SwitchToFC();
 
mode = 'V';
rxd_buffer_locked = FALSE;
timeout = 40;
 
while( !rxd_buffer_locked && timeout)
{
SendOutData( 'v', ADDRESS_FC, 0);
timer = 20;
while( timer > 0 );
timeout--;
}
 
//--------------------------
// FC gefunden!
// -> Version kopieren
//--------------------------
if( rxd_buffer_locked )
{
Decode64();
MKVersion.isFC = true;
memcpy( &MKVersion.FCVer, (Version_t *) (pRxData), sizeof(Version_t) );
}
}
 
} // end: if( rxd_buffer_locked )
 
 
//---------------------------------------
// FC EEprom Version / Struktur pruefen
//---------------------------------------
MK_Setting_load( 0xff, 15 ); // 0xff == aktuelles Parameterset holen; 15 == timeout; Ergebnisse in MKVersion
 
mode = 0;
rxd_buffer_locked = FALSE;
 
if( MKVersion.isNC )
{
MK_SwitchToNC(); // wieder auf NC umschalten als default
}
 
 
if( MKVersion.paramsetOK ) // FC Revision OK?
{
set_beep( 25, 0xffff, BeepNormal ); // kurzer Beep (FC-Revision ok)
if( showMKInfo ) MK_Info( 500, true ); // Anzeige von MK_Info() max. 5 Sekunden (mit Settings-Refresh)
}
else // FC Revision nicht unterstuetzt...
{
set_beep( 1000, 0xffff, BeepNormal ); // langer Error-Beep (FC-Revision nicht unterstuetzt)
if( showMKInfo ) MK_Info( 1600, true ); // Anzeige von MK_Info() max. 16 Sekunden (mit Settings-Refresh)
}
 
 
//timer = 50;
//while (timer > 0);
 
get_key_press(KEY_ALL);
 
return RetVal;
 
} // searchMK()
 
 
 
 
//--------------------------------------------------------------
// chg = MK_Info( displaytimeout, refreshSettings )
//
// Parameter:
// displaytimeout : 0 = kein autom. Timeout
// n = Anzeige verschwindet automatisch nach n Zeit
// (bei z.B. n=600 nach 6 Sekunden)
//
// refreshSettings: true/false
// true = in bestimmten Zeitintervallen (RELOAD_SETTING_TIME)
// wird MK_Setting_load() durchgeführt um ggf. einen Kopterwechsel
// automatisch zu erkennen.
// Dazu muss MKINFO_AUTO_REFRESH in main.h eingeschaltet sein!
//
// Rueckgabe:
// hardwarechange: true/false
//--------------------------------------------------------------
uint8_t MK_Info( uint16_t displaytimeout, uint8_t refreshSettings )
{
uint8_t redraw;
uint8_t old_isFC;
uint8_t old_isNC;
 
old_isFC = MKVersion.isFC;
old_isNC = MKVersion.isNC;
 
 
//displaytimeout = 0;
 
if( displaytimeout )
timer = displaytimeout;
 
#define RELOAD_SETTING_TIME 350 // alle 0.35 sec neue Settings vom MK laden
timer_get_tidata = RELOAD_SETTING_TIME; // ich brauche weitere timer... und bediene mich jetzt mal bei einem osd-timer
// (timer2 ist belegt von MK_Setting_load)
 
//get_key_press(KEY_ALL);
 
 
redraw = true;
 
while( true )
{
//------------------------------------------
// Screen neu zeichnen
//------------------------------------------
if( redraw )
{
if( redraw != 2 )
lcd_cls();
 
show_Lipo(); // LiPo direkt anzeigen damit es nicht flackert
 
lcd_frect( 0, 0, 101, 8, 1); // Headline: Box fill Black mit Platz fuer PKT-LiPo rechts
lcdx_printp_at( 1, 0, PSTR("MK Info"), MINVERS, 0,0); // Titel
 
if( MKVersion.isFC || MKVersion.isNC ) // MK gefunden...
{
lcd_frect_round( 0, 30, 127, 22, 1, R2); // Fill: Anzeigebereich der Settings in Schwarz
 
//--------------------
// FC-Version
//--------------------
lcdx_printp_at( 0, 2, PSTR("FC:") , MNORMAL, 4,-5);
MKVersion_print_at( 4, 2, FC , MNORMAL, 2,-5);
 
//--------------------
// FC-Revision
//--------------------
lcdx_printp_at( 12, 2, PSTR("Rev:"), MNORMAL, 5,-5);
lcdx_printf_at_P( 17, 2, MNORMAL, 2,-5, PSTR("%03u"), MKVersion.paramsetRevision );
 
if( !MKVersion.paramsetOK )
lcdx_printp_at( 11, 3, PSTR(" Rev-ERR!"), MINVERS, 5,-4); // Fehler FC-Revision (nicht vom PKT unterstuetzt)
else
lcd_frect( 11*6+5, 3*8-4, 9*6, 8, 0); // ggf. Fehleranzeige loeschen (nach refreshSettings)
 
 
//--------------------
// NC-Version
//--------------------
lcdx_printp_at( 0, 3, PSTR("NC:") , MNORMAL, 4,-3);
MKVersion_print_at( 4, 3, NC , MNORMAL, 2,-3);
 
 
//--------------------
// aktuelles Setting
//--------------------
lcdx_printp_center( 4, PSTR("MK Setting"), MINVERS, 0,1); // "MK Setting" (zentriert)
 
//lcdx_printp_at( 5, 4, PSTR("MK Setting"), MINVERS, 4,1);
MKVersion_Setting_print( 5, MINVERS, 0,3);
}
else // else: if( MKVersion.isFC || MKVersion.isNC ) // KEINEN MK gefunden...
{
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( strGet(NOMKFOUND), false, 0, true, false ); // FEHLER! nodata (max. 8 Sekunden anzeigen)
 
} // end: if( MKVersion.isFC || MKVersion.isNC )
 
 
//lcd_printp_at( 19, 7, strGet(OK), MNORMAL); // Keyline
lcd_printp_at(12, 7, strGet(ENDE), MNORMAL); // Keyline
 
if( displaytimeout == 0 )
lcd_printp_at( 0, 7, PSTR("Refresh"), MNORMAL); // Keyline: Refresh
 
redraw = false;
 
} // end: if( redraw )
 
 
//------------------------------------------
// PKT-LiPo Anzeige
//------------------------------------------
show_Lipo();
 
 
//------------------------
// Tasten abfragen
//------------------------
if( get_key_press(1 << KEY_MINUS) && (displaytimeout == 0) )
{
searchMK( false ); // false = zeige nicht MK_Info() an
redraw = true;
}
 
if( get_key_short(1 << KEY_ESC) )
{
break;
}
 
 
//------------------------------------------
// Pruefe PKT-Update oder andere PKT-Aktion
//------------------------------------------
if( PKT_CtrlHook() ) // Update vom Updatetool angefordert?
{
redraw = true;
}
 
//------------------------------------------
// displaytimeout?
//------------------------------------------
if( displaytimeout && !timer )
{
break;
}
 
} // end: while( true )
 
get_key_press(KEY_ALL);
 
return( (old_isFC != MKVersion.isFC) || (old_isNC != MKVersion.isNC) );
 
} // MK_Info()
 
 
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mk/mkbase.h
0,0 → 1,143
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2012 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2012 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY mkbase.h
//#
//# 14.05.2014 OG
//# - chg: include "paramset.h" geaendert auf "../mksettings/paramset.h"
//#
//# 29.03.2014 OG
//# - del: MK_Show_LastGPS_Position() -> jetzt: OSDDATA_ShowLastGPSPosition()/osddata.c
//#
//# 28.03.2014 OG
//# - add: MK_Show_LastGPS_Position() - ehemals in main.c
//#
//# 16.02.2014 OG
//# - add: MK_SwitchToNC(), MK_SwitchToFC(), MK_SwitchToMAG(), MK_SwitchToGPS()
//# - add: MK_Setting_write(), MK_Setting_change()
//# - chg: umbenannt: MK_load_setting() zu MK_Setting_load()
//#
//# 13.02.2014 OG
//# - add: MKVersion_Cmp()
//# - add: defines zu VERSION... fuer MKVersion_Cmp()
//# - del: WrongFCVersion
//#
//# 10.02.2014 OG
//# - add: MKVersion_Setting_print()
//#
//# 09.02.2014 OG
//# - add: MK_Info()
//# - add: MKVersion_print_at
//#
//# 08.02.2014 OG
//# - chg: MK_load_setting() Parameter geaendert
//# - add: extern MKVersion_t MKVersion
//#
//# 29.01.2014 OG
//# - Ausgliederungen aus main.c
//############################################################################
 
#ifndef _MKBASE_H
#define _MKBASE_H
 
//#include "../mksettings/paramset.h"
#include "../mk-data-structs.h"
 
 
//-------------------------------------
//-------------------------------------
typedef struct
{
unsigned char isFC; // true / false - FC vorhanden? -> wird gesetzt durch searchMK()
unsigned char isNC; // true / false - NC vorhanden? -> wird gesetzt durch searchMK()
Version_t FCVer; // -> wird gesetzt durch searchMK()
Version_t NCVer; // -> wird gesetzt durch searchMK()
unsigned char paramsetOK; // true wenn Revision in paramset.c vorhanden und initialisiert -> wird gesetzt druch paramsetInit()/paramset.c
unsigned char paramsetRevision; // Revision FC-Parameterset -> wird gesetzt druch paramsetInit()/paramset.c
uint8_t mksetting; // -> wird gesetzt druch paramsetInit()/paramset.c
unsigned char mksettingName[13]; // -> wird gesetzt druch paramsetInit()/paramset.c
} MKVersion_t;
 
 
//-------------------------------------
// zur Orientierung: Version_t
//-------------------------------------
//typedef struct
//{
// unsigned char SWMajor;
// unsigned char SWMinor;
// unsigned char ProtoMajor;
// unsigned char ProtoMinor;
// unsigned char SWPatch;
// unsigned char HardwareError[5];
//} __attribute__((packed)) Version_t;
 
//----------------------------
// MK-Versionsinformationen
// global verfuegbar
//----------------------------
extern MKVersion_t MKVersion;
 
 
//------------------------------------------------------
// defines fuer den Versionsvergleich von FC/NC
// siehe: MKVersion_Cmp()... (mkbase.c)
//------------------------------------------------------
#define GIVEN_VERSION 2 // das macht die Sache leserlicher fuer resultierenden Ergebnisse! => siehe Anmerkungen: MKVersion_Cmp() !
#define VERSION_NO 0
#define VERSION_LOWER 1
#define VERSION_EQUAL 2
#define VERSION_GREATER 3
 
 
void MKVersion_Init( void );
void MKVersion_print_at( uint8_t x, uint8_t y, uint8_t what, uint8_t drawmode, int8_t xoffs, int8_t yoffs );
void MKVersion_Setting_print( uint8_t y, uint8_t drawmode, uint8_t xoffs, uint8_t yoffs );
uint8_t MKVersion_Cmp( Version_t ver, unsigned char SWMajor, unsigned char SWMinor, unsigned char SWPatch );
 
void MK_SwitchToNC( void );
void MK_SwitchToFC( void );
void MK_SwitchToMAG( void );
void MK_SwitchToGPS( void );
 
uint8_t MK_Setting_load( uint8_t lsetting, uint8_t timeout );
uint8_t MK_Setting_write( uint8_t wsetting, uint8_t timeout);
uint8_t MK_Setting_change( uint8_t setting );
 
uint8_t MK_Info( uint16_t displaytimeout, uint8_t refreshSettings );
 
uint8_t searchMK( uint8_t showMKInfo );
 
 
#endif // end: #ifndef _MKBASE_H
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mk/mkdebugdata.c
0,0 → 1,416
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY mkdebugdata.c
//#
//# 04.06.2014 OG
//# komplett neues Layout
//# - chg: MK_DebugData(), GetAnalogNames() umgestellt auf PKT_Message_Datenverlust()
//# - chg: GetAnalogNames() Timeout reduziert
//# - add: #include "../lipo/lipo.h"
//# - add: #include "../pkt/pkt.h"
//# - add: #include <stdbool.h>
//#
//# 29.01.2014 OG
//# - chg: ehemals display_debug() jetzt MK_DebugData()
//# - chg: ehemals 'debug.c' jetzt 'mk/mkdebugdata.c'
//#
//# 03.04.2013 OG
//# - chg: define 'analognames' zu define 'USE_MKDEBUGDATA'
//# - add: Benutzer kann GetAnalogNames() via KEY_ESC abbrechen
//# - chg: Screen-Layout GetAnalogNames()
//# - chg: SwitchToNC/FC Reihenfolge
//#
//# 27.03.2013 OG
//# - chg: auf malloc umgestellt
//# - fix: diverse Anzeigefehler
//# - chg: teilweise redunten Code entfernt
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <stdbool.h>
#include <string.h>
#include "../main.h"
 
#ifdef USE_MKDEBUGDATA
 
#include "../lcd/lcd.h"
#include "../pkt/pkt.h"
#include "../lipo/lipo.h"
#include "../uart/usart.h"
#include "mkdebugdata.h"
#include "../timer/timer.h"
#include "../messages.h"
#include "../mk-data-structs.h"
 
 
//--------------------------------------------------------------
 
 
#define PAGELINES 5 // Anzahl der Zeilen pro Anzeigescreens
#define XOFFS 4
#define YOFFS 12
 
#define TIMEOUT 200 // 2 sec
#define ANALOGTIME 20 // 200 ms
 
#define MKDD_ANALOGNAME_SIZE 2*32*17 // MALLOC: 32 names, 16 characters + 1 0x00
 
// WARNING: this work for NC & FC only
// if current_hardware == MK3MAG or MKGPS the access is outside of the array...
//uint8_t AnalogNames[2][32][16 + 1]; // 32 names, 16 characters + 1 0x00
uint8_t *AnalogNames; // MALLOC: MKDD_ANALOGNAME_SIZE - 32 names, 16 characters + 1 0x00
 
uint8_t AnalogNamesRead[2] = {0,0};
 
static const char strFC[] PROGMEM = "FC";
static const char strNC[] PROGMEM = "NC";
 
 
//--------------------------------------------------------------
// Speicher wieder freigeben
//--------------------------------------------------------------
void MKDD_MemFree( void )
{
free( AnalogNames );
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void showTitle( void )
{
lcdx_printf_at_P( 0, 0, MINVERS, 0,0, PSTR(" %2S %16S"), (current_hardware==FC ? strFC : strNC), strGet(STR_DATA) ); // Titelzeile
show_Lipo();
}
 
 
 
//--------------------------------------------------------------
// lOk = GetAnalogNames()
//
// Return:
// true = OK
// false = User-Abort (KEY_ESC)
//--------------------------------------------------------------
uint8_t GetAnalogNames( void )
{
uint8_t i = AnalogNamesRead[current_hardware - 1];
uint8_t t = 0;
uint8_t lOk = TRUE;
int8_t yoffs = -2; // yoffs der Progress-Bar
 
lcd_cls ();
showTitle(); // Titel
lcdx_printf_center_P( 3, MNORMAL, 0,0, PSTR("%S %S %S"), strGet(STR_READING), (current_hardware==FC ? strFC : strNC), strGet(STR_LABELS) );
 
lcd_rect_round( 13, 40+yoffs, 102, 6, 1, R1); // Rahmen fuer Progress
lcd_printp_at(12, 7, strGet(ENDE), MNORMAL); // Keyline
 
 
mode = 'A'; // read Names
_delay_ms(200);
rxd_buffer_locked = FALSE;
 
timer = ANALOGTIME;
 
while( (i < 32) && lOk )
{
SendOutData ('a', ADDRESS_ANY, 1, &i, 1);
 
while( !rxd_buffer_locked && timer && lOk)
lOk = !get_key_press (1 << KEY_ESC);
 
if( timer )
{
Decode64 ();
if( i == *pRxData )
{
lcd_frect( 16, 42+yoffs, (i+1)*3, 2, 1); // Progress
 
memcpy( (uint8_t *) (AnalogNames+((current_hardware-1)*32*17)+(i*17)), (uint8_t *) pRxData + 1, 16);
*(AnalogNames+((current_hardware-1)*32*17)+(i*17)+16) = 0;
i++;
t = 0;
}
else
{
_delay_ms(100);
}
 
timer = ANALOGTIME;
rxd_buffer_locked = FALSE;
}
else if( lOk )
{ // timeout occured
t++;
timer = ANALOGTIME;
 
if( t >= 15 ) // timeout?
{
//PKT_Message_Datenverlust( timeout, beep)
PKT_Message_Datenverlust( 500, true); // 500 = 5 Sekunden
break;
}
}
else
{
lOk = !get_key_press( 1 << KEY_ESC );
}
}
 
if(lOk) AnalogNamesRead[current_hardware - 1] = i;
 
//_delay_ms(4000); // DEBUG
 
return lOk;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void showLabels( uint8_t page)
{
uint8_t i = 0;
 
for( i = 0; i < PAGELINES; i++ )
{
if( (i + (page * PAGELINES)) >= 32 )
{
//lcdx_cls_rowwidth( y, width, mode, xoffs, yoffs )
lcdx_cls_rowwidth( i, 20, MNORMAL, XOFFS,YOFFS );
}
else
{
lcdx_print_at( 0, i, AnalogNames+((current_hardware-1)*32*17)+(i + page * PAGELINES)*17, MNORMAL, XOFFS,YOFFS);
}
}
}
 
 
//--------------------------------------------------------------
//
//--------------------------------------------------------------
void MK_DebugData(void)
{
uint8_t tmp_dat;
uint8_t i = 0;
uint8_t page = 0;
uint8_t pagemax = (32/PAGELINES);
uint8_t redraw = 2;
 
DebugData_t *DebugData;
 
 
// alloc ram
AnalogNames = malloc( MKDD_ANALOGNAME_SIZE );
 
if( !AnalogNames )
{
Show_PKTError_NoRAM();
return;
}
 
memset( AnalogNames, 0, MKDD_ANALOGNAME_SIZE ); // init: AnalogNames
AnalogNamesRead[0] = 0;
AnalogNamesRead[1] = 0;
 
SwitchToFC();
 
timer = TIMEOUT;
 
if( AnalogNamesRead[current_hardware - 1] < 32 )
{
if( !GetAnalogNames() )
{
MKDD_MemFree();
return;
}
}
 
if( !timer )
{
MKDD_MemFree();
return;
}
 
mode = 'D'; // Debug Data
rxd_buffer_locked = FALSE;
timer = TIMEOUT;
timer1 = 0;
 
tmp_dat = 10;
SendOutData( 'd', ADDRESS_ANY, 1, &tmp_dat, 1);
abo_timer = ABO_TIMEOUT;
 
 
do
{
//------------------------------------------
//------------------------------------------
if( redraw )
{
if( redraw==2 ) lcd_cls();
 
showTitle(); // Titelzeile
lcd_rect_round( 0, (1*8)+1, 127, (6*8)-4, 1, R2); // Rahmen fuer 5 Zeilen Display
 
showLabels( page );
 
lcd_printp_at( 0, 7, strGet(KEYLINE3), 0);
 
lcd_write_number_u_at (5, 7, page + 1);
lcd_printp_at( (current_hardware==FC ? 3 : 19), 7, strFC, 0);
lcd_printp_at( (current_hardware==FC ? 19 : 3), 7, strNC, 0);
 
redraw = false;
}
 
 
if( rxd_buffer_locked )
{
Decode64();
DebugData = (DebugData_t *) pRxData;
 
if( !timer1 )
{
for( i = 0; i < PAGELINES && (i + (page * PAGELINES)) < 32; i++)
{
writex_ndigit_number_s( 21-6, i, DebugData->Analog[i + page * PAGELINES], 5, 0, MNORMAL, XOFFS,YOFFS);
}
timer1 = 25; // Anzeigeverzoegerung damit es nicht flackert
}
 
rxd_buffer_locked = FALSE;
 
timer = TIMEOUT;
}
 
 
if( !abo_timer )
{ // renew abo every ... sec
tmp_dat = 10;
SendOutData( 'd', ADDRESS_ANY, 1, &tmp_dat, 1);
abo_timer = ABO_TIMEOUT;
}
 
 
//------------------------------------------
// PKT LiPo anzeigen
//------------------------------------------
show_Lipo();
 
 
//------------------------------------------
// Pruefe PKT Update oder andere PKT-Aktion
//------------------------------------------
if( PKT_CtrlHook() ) // Update vom Updatetool angefordert?
{
redraw = 2;
timer = TIMEOUT;
}
 
 
//------------------------------------------
// Tasten
//------------------------------------------
if( get_key_press(1 << KEY_MINUS) )
{
page--;
if( page > pagemax ) page = pagemax;
redraw = true;
}
 
if( get_key_press(1 << KEY_PLUS) )
{
page++;
if( page > pagemax ) page = 0;
redraw = true;
}
 
if( (hardware == NC) && get_key_press (1 << KEY_ENTER) )
{
if( current_hardware == NC ) SwitchToFC();
else SwitchToNC();
 
if( AnalogNamesRead[current_hardware - 1] < 32 )
{
if( !GetAnalogNames() )
{
MKDD_MemFree();
return;
}
}
 
mode = 'D'; // Debug Data
rxd_buffer_locked = FALSE;
timer = TIMEOUT;
 
tmp_dat = 10;
SendOutData ('d', ADDRESS_ANY, 1, &tmp_dat, 1);
 
//page = 0;
redraw = true;
}
}
while (!get_key_press(1 << KEY_ESC) && timer); // Taste: Ende oder Timeout
 
 
clear_key_all();
 
tmp_dat = 0;
SendOutData ('d', ADDRESS_ANY, 1, &tmp_dat, 1); // Request Debugdata abschalten
 
mode = 0;
rxd_buffer_locked = FALSE;
 
if( !timer )
{ // timeout occured
//PKT_Message_Datenverlust( timeout, beep)
PKT_Message_Datenverlust( 500, true); // 500 = 5 Sekunden
}
 
//SwitchToNC();
 
// free ram
MKDD_MemFree();
}
 
#endif // end: #ifdef USE_MKDEBUGDATA
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mk/mkdebugdata.h
0,0 → 1,51
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY mkdebugdata.h
//#
//# 29.01.2014 OG
//# - chg: ehemals display_debug() jetzt MK_DebugData()
//# - chg: ehemals 'debug.h' jetzt 'mk/mkdebugdata.h'
//# - add: Source-History ergaenzt
//############################################################################
 
 
#ifndef _MKDEBUGDATA_H
#define _MKDEBUGDATA_H
 
extern uint8_t AnalogNamesRead[2];
 
void MK_DebugData(void);
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mk/mkdisplay.c
0,0 → 1,267
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY mkdisplay.c
//#
//#
//# 05.04.2015 Cebra
//# - chg: SendOutData( 'h', ADDRESS_ANY, 2, &cmd, 1, 0x00 ,1) ergänzt um 2. Parameter wegen Fehlfunktion mit NC 2.09h
//#
//# 04.06.2014 OG
//# - chg: MK_Display() umgestellt auf PKT_Message_Datenverlust()
//#
//# 31.05.2014 OG
//# - chg: MK_Display() - umgestellt auf PKT_KeylineUpDown()
//#
//# 28.04.2014 OG
//# - chg: MK_Display() - leichte Optimierung der Display-Ausgabe um ein paar
//# Bytes Code zu sparen
//#
//# 09.04.2014 OG - vervollstaendigte Steuerung des MK-Display's
//# - chg: die Tasten fuer 'Ende' und NC/FC-Umschaltung muessen jetzt lange
//# gedruekckt werden (get_key_long) - keine Beschriftung mehr dafuer
//# vorhanden da die Beschriftung jetzt hoch/runter zeigt!
//# (aber 'Ende' ist da wo es immer im PKT ist)
//# - add: Unterstuetzung der hoch/runter Tasten
//# - chg: diverse Aenderungen bei der Kommunkation und Einbindung aktueller
//# Funktionen von mkbase.c
//#
//# 29.01.2014 OG
//# - chg: ehemals display_data() jetzt MK_display()
//# - chg: ehemals 'display.c' jetzt 'mk/mkdisplay.c'
//#
//# 25.01.2014 OG
//# - optisches Facelift
//# - PKT_CtrlHook() eingeklinkt
//# - Versionshistorie hinzugefuegt
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <stdbool.h>
 
#include "../main.h"
#include "../lcd/lcd.h"
#include "../uart/usart.h"
#include "../timer/timer.h"
#include "../messages.h"
#include "../lipo/lipo.h"
#include "../pkt/pkt.h"
#include "../mk-data-structs.h"
#include "mkbase.h"
#include "mkdisplay.h"
 
#define TIMEOUT 500 // 5 sec
 
 
uint8_t ACC_Display=false;
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void MK_Display(void)
{
uint8_t cmd;
uint8_t redraw = true;
uint8_t exit = false;
 
mode = 'H';
rxd_buffer_locked = FALSE;
timer = TIMEOUT;
// cmd = 0xfc; // Home = first page
cmd = 0xff; // aktuelle Seite
 
redraw = true;
MK_SwitchToFC(); // add 31.3.2014 Cebra, definierter Zustand
 
if (ACC_Display==true)
{
cmd = 0x06;
SendOutData( 'l', ADDRESS_ANY, 1, &cmd,1);
cmd = 0xff;
if( rxd_buffer_locked )
{
Decode64 ();
//------------------------------------------
// RX-Buffer freigeben
//------------------------------------------
rxd_buffer_locked = FALSE;
timer = TIMEOUT;
 
} // end: if( rxd_buffer_locked )
// _delay_ms(250);
}
 
 
 
do
{
//------------------------------------------
// Screen neu zeichnen
//------------------------------------------
if( redraw )
{
ShowTitle_P( ( current_hardware == NC ? PSTR("NC") : PSTR("FC") ), true );
lcd_printp_at( 4, 0, PSTR("Display"), MINVERS);
 
lcd_rect_round( 0, 2*7-3, 127, 5*7+3+3, 1, R2); // Rahmen
lcdx_printp_at( 2, 7, PSTR("\x18 \x19"), MNORMAL, 0,0); // Keyline: Links / Rechts
PKT_KeylineUpDown( 18, 13, 0,0); // Keyline: Down / Up
 
redraw = false;
}
 
 
show_Lipo();
 
 
SendOutData( 'h', ADDRESS_ANY, 2, &cmd, 1, 0x00 ,1); // 05.04.2015 Cebra, 2.er Parameter wg NC 2.09i
cmd = 0xff;
 
_delay_ms(250);
 
if( rxd_buffer_locked )
{
Decode64 ();
 
//------------------------------------------
// Ausgabe auf PKT-Anzeige
// 4 Zeilen a 20 Zeichen
// (Anzeige von unten nach oben)
//------------------------------------------
rxd_buffer[83] = 0;
lcdx_print_at( 0,5, (uint8_t *) &rxd_buffer[3+60], MNORMAL, 5,2);
 
rxd_buffer[63] = 0;
lcdx_print_at( 0,4, (uint8_t *) &rxd_buffer[3+40], MNORMAL, 5,1);
 
rxd_buffer[43] = 0;
lcdx_print_at( 0,3, (uint8_t *) &rxd_buffer[3+20], MNORMAL, 5,0);
 
rxd_buffer[23] = 0;
lcdx_print_at( 0,2, (uint8_t *) &rxd_buffer[3+ 0], MNORMAL, 5,-1);
 
 
//------------------------------------------
// RX-Buffer freigeben
//------------------------------------------
rxd_buffer_locked = FALSE;
timer = TIMEOUT;
 
} // end: if( rxd_buffer_locked )
 
 
//------------------------------------------
// Pruefe PKT Update oder andere PKT-Aktion
//------------------------------------------
if( PKT_CtrlHook() ) // Update vom Updatetool angefordert?
{
redraw = true;
}
 
 
if( get_key_press(1 << KEY_MINUS) || get_key_long_rpt_sp((1 << KEY_MINUS),2) )
{
cmd = 0xfe; // key: rechts (next page)
}
 
if( get_key_press(1 << KEY_PLUS) || get_key_long_rpt_sp((1 << KEY_PLUS),2) )
{
cmd = 0xfd; // key: links (previous page)
}
 
if( get_key_short(1 << KEY_ESC) )
{
cmd = 0xfb; // key: runter
}
 
if( get_key_short(1 << KEY_ENTER) )
{
cmd = 0xf7; // key: hoch
}
 
 
if( (hardware == NC) && get_key_long(1 << KEY_ENTER) )
{
set_beep( 25, 0xffff, BeepNormal ); // kurzer Bestaetigungs-Beep
 
if( current_hardware == NC )
{
 
MK_SwitchToFC();
redraw = true;
}
else
{
 
MK_SwitchToNC();
 
MK_SwitchToNC();
 
redraw = true;
}
// cmd = 0xff;
 
timer2 = 50;
while( timer2 > 0 );
}
 
 
if( get_key_long(1 << KEY_ESC) )
{
set_beep( 25, 0xffff, BeepNormal ); // kurzer Bestaetigungs-Beep
exit = true;
}
}
while( (!exit) && timer );
 
 
mode = 0;
rxd_buffer_locked = FALSE;
 
 
//------------------------------------------
// Timeout?
//------------------------------------------
if( !timer )
{ // timeout occured
//PKT_Message_Datenverlust( timeout, beep)
PKT_Message_Datenverlust( 500, true); // 500 = 5 Sekunden
}
 
clear_key_all();
}
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mk/mkdisplay.h
0,0 → 1,53
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY mkdisplay.h
//#
//# 29.01.2014 OG
//# - chg: ehemals display_data() jetzt MK_display()
//# - chg: ehemals 'display.h' jetzt 'mk/mkdisplay.h'
//# - add: Source-History ergaenzt
//############################################################################
 
 
#ifndef _DISPLAY_H
#define _DISPLAY_H
 
extern uint8_t ACC_Display;
 
void MK_Display(void);
 
#endif
 
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mk/mkgpsinfo.c
0,0 → 1,425
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY mkgpsinfo.c
//#
//# 04.06.2014 OG
//# - chg: MK_Gps_Info() umgestellt auf PKT_Message_Datenverlust()
//#
//# 14.05.2014 OG
//# - chg: Code-Redesign; neues Screen-Layout; Code-Reduzierung;
//# Anpassungen an neue PKT-Funktionen
//# - chg: umbenannt von 'gps.c' zu 'mkgpsinfo.c'
//# - chg: gps() ist jetzt MK_Gps_Info()
//# - add: Source-Historie ergaenzt
//############################################################################
 
 
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <stdbool.h>
#include <util/delay.h>
 
#include "../main.h"
#include "../lcd/lcd.h"
#include "../timer/timer.h"
#include "../uart/usart.h"
#include "../lipo/lipo.h"
#include "../pkt/pkt.h"
#include "../mk/mkbase.h"
#include "../messages.h"
 
 
//##############################################################
//##############################################################
 
 
//#define DEBUG_MKGPS // erweiterte Anzeigen zum debuggen
 
#define GPSTIMEOUT 300 // 3 Sekunden
#define UBX_BUFFER_SIZE 100 // 100 Byte Buffer fuer GPS-Daten
 
 
uint8_t ck_a = 0;
uint8_t ck_b = 0;
 
union long_union
{
uint32_t dword;
uint8_t byte[4];
} longUnion;
 
 
union int_union
{
uint16_t dword;
uint8_t byte[2];
} intUnion;
 
 
//##############################################################
//##############################################################
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint32_t join_4_bytes(uint8_t Buffer[])
{
longUnion.byte[0] = *Buffer;
longUnion.byte[1] = *(Buffer+1);
longUnion.byte[2] = *(Buffer+2);
longUnion.byte[3] = *(Buffer+3);
return (longUnion.dword);
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void checksum(uint8_t data)
{
ck_a += data;
ck_b += ck_a;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void MK_Gps_Info( void )
{
uint8_t UBX_buffer[UBX_BUFFER_SIZE];
uint8_t UBX_payload_counter = 0;
uint8_t UBX_class = 0;
uint8_t UBX_id = 0;
uint8_t UBX_ck_a = 0;
uint8_t data = 0;
uint8_t length = 0;
uint8_t state = 0;
 
uint8_t redraw = true;
uint8_t refresh = false;
uint8_t yoffs = 1; // Anzeige-Verschiebung: der obere Bereich
uint8_t yoffs2 = 4; // Anzeige-Verschiebung: GPS-Koordinaten
int16_t v_16; // tmp-Variable
int32_t v_32; // tmp-Variable
 
#ifdef DEBUG_MKGPS
uint8_t maxlen = 0;
#endif
 
MK_SwitchToNC(); // Anmerkung OG: warum auch immer es besser ist erst auf die NC
MK_SwitchToGPS(); // umzuschalten... es laeuft so scheinbar zuverlaessiger
MK_SwitchToGPS();
 
timer_mk_timeout = GPSTIMEOUT;
 
do
{
//------------------------
// REDRAW
//------------------------
if( redraw )
{
ShowTitle_P( PSTR("MK GPS Info"), true);
 
lcdx_printp_at( 0,1, PSTR("Fix:"), MNORMAL, 0,yoffs );
lcdx_printp_at( 0,2, PSTR("Sat:"), MNORMAL, 0,yoffs );
lcdx_printp_at( 0,3, PSTR("Alt:"), MNORMAL, 0,yoffs );
 
lcdx_printp_at( 9,1, PSTR("PDOP:"), MNORMAL, 3,yoffs );
lcdx_printp_at( 9,2, PSTR("Accu:"), MNORMAL, 3,yoffs );
lcdx_printp_at( 9,3, PSTR("Sped:"), MNORMAL, 3,yoffs );
 
lcd_frect( 0, (4*7)+4+yoffs2, 127, 7, 1); // GPS: Rect: Invers
lcdx_printp_at(1, 3, strGet(START_LASTPOS1), MINVERS, 0,8+yoffs2); // GPS: "Breitengr Längengr"
lcd_rect( 0, (3*8)+7+yoffs2, 127, (2*8)+4, 1); // GPS: Rahmen
 
lcdx_printp_at(12,7, strGet(ENDE), MNORMAL, 0,1); // KEYLINE
 
redraw = false;
}
 
 
//------------------------
// REFRESH
//------------------------
if( refresh )
{
if((UBX_class == 1) && (UBX_id == 6)) // GPS: SVINFO
{
//--------------
// GPS Status
//--------------
switch( UBX_buffer[10] )
{
case 4:
case 3: lcdx_printp_at( 5, 1, PSTR("3D"), MNORMAL, 1,yoffs); break;
case 2: lcdx_printp_at( 5, 1, PSTR("2D"), MNORMAL, 1,yoffs); break;
default: lcdx_printp_at( 5, 1, PSTR("no"), MNORMAL, 1,yoffs);
}
 
// GPS ok => ein Haken wird angezeigt
if( (UBX_buffer[11] & 1) == 1 ) lcdx_putc( 7, 1, SYMBOL_CHECK, MNORMAL, 3,yoffs );
else lcdx_putc( 7, 1, ' ', MNORMAL, 3,yoffs );
 
//---
// Anzeige von "D" - evtl. DGPS (Differential GPS)?
// aktuell nicht mehr unterstuetzt da kein Platz auf dem Screen
//---
//if( (UBX_buffer[11] & 3) == 3 ) lcd_printp_at (10,0, PSTR("D"), 0);
//else lcd_printp_at (10,0, PSTR(" "), 0);
 
//--------------
// Sat
//--------------
lcdx_printf_at_P( 5, 2, MNORMAL, 0,yoffs, PSTR("%2u"), UBX_buffer[47] );
 
//--------------
// PDOP
//--------------
v_16 = UBX_buffer[44]+UBX_buffer[45]*255;
lcdx_printf_at_P( 15, 1, MNORMAL, 0,yoffs, PSTR("%2.2d"), v_16 );
 
//--------------
// Accuracy
//--------------
v_32 = (int32_t)join_4_bytes(&UBX_buffer[24]);
lcdx_printf_at_P( 15, 2, MNORMAL, 0,yoffs, PSTR("%2.2ldm"), v_32 );
}
 
if((UBX_class == 1) && (UBX_id == 18)) // GPS: VELNED
{
//--------------
// Speed
//--------------
v_16 = (int16_t)((join_4_bytes(&UBX_buffer[20])*60*60)/100000);
lcdx_printf_at_P( 15, 3, MNORMAL, 0,yoffs, PSTR("%3dkmH"), v_16 );
 
//uint16_t speed = (uint16_t)((join_4_bytes(&UBX_buffer[20])*60*60)/100000);
//write_ndigit_number_u (11, 4, speed, 3, 0,0);
//lcd_printp_at (15,4, PSTR("km/h"), 0);
}
 
if((UBX_class == 1) && (UBX_id == 2)) // GPS: POSLLH
{
//--------------
// Altitude
//--------------
v_16 = (int16_t)(join_4_bytes(&UBX_buffer[16])/1000);
//v_16 = v_16 + 3000;
lcdx_printf_at_P( 4, 3, MNORMAL, 1,yoffs, PSTR("%4d"), v_16 );
 
//uint16_t height = (uint16_t)(join_4_bytes(&UBX_buffer[16])/1000);
//write_ndigit_number_u (11, 7, height, 4, 0,0);
//lcd_printp_at(16,7, PSTR("m"), 0);
 
 
//--------------
// Breitengrad - Lat (51.)
//--------------
v_32 = join_4_bytes(&UBX_buffer[8]);
writex_gpspos( 1, 4, v_32 , MNORMAL, 0,10+yoffs2); // Anzeige: Breitengrad
 
//write_ndigit_number_u ( 0, 7, (uint16_t)(lat/10000000), 2, 0,0);
//lcd_printp_at ( 2, 7, PSTR("."), 0);
//write_ndigit_number_u ( 3, 7, (uint16_t)((lat/1000) % 10000), 4, 1,0);
//write_ndigit_number_u ( 7, 7, (uint16_t)((lat/10) % 100), 2, 1,0);
 
 
//--------------
// Laengengrad - Long (7.)
//--------------
v_32 = join_4_bytes(&UBX_buffer[4]);
writex_gpspos( 12, 4, v_32, MNORMAL, -1,10+yoffs2); // Anzeige: Laengengrad
 
//write_ndigit_number_u (10, 7, (uint16_t)(lon/10000000), 2, 0,0);
//lcd_printp_at (12, 7, PSTR("."), 0);
//write_ndigit_number_u (13, 7, (uint16_t)((lon/1000) % 10000), 4, 1,0);
//write_ndigit_number_u (17, 7, (uint16_t)((lon/10) % 100), 2, 1,0);
}
 
//------------------------
// PKT-LiPo Anzeige
//------------------------
show_Lipo();
 
refresh = false;
} // end: if( refresh )
 
 
//--------------------------
// PROCESS DATA
//--------------------------
if( uart_getc_nb( &data ) )
{
switch( state )
{
case 0: if( data == 0xB5 ) // GPS: init 1
{
UBX_payload_counter = 0;
UBX_id = 0;
UBX_class = 0;
ck_a = 0;
ck_b = 0;
state++;
}
break;
 
 
case 1: if( data == 0x62 ) // GPS: init 2
state++;
else
state = 0;
break;
 
 
case 2: if( data != 1 ) // GPS: class
state = 0;
else
{
checksum(data);
UBX_class = data;
state++;
}
break;
 
 
case 3: if( (data != 48) // GPS: id
&&(data != 6 )
&&(data != 18)
&&(data != 2 ))
{
state = 0;
}
else
{
UBX_id = data;
checksum(data);
state++;
}
break;
 
 
case 4: if( data >= UBX_BUFFER_SIZE ) // GPS: length lo
state = 0;
else
{
checksum(data);
length = data;
state++;
}
 
#ifdef DEBUG_MKGPS
// DEBUG - Anzeige der Paketgroesse
if( data > maxlen )
{
// groesstes gemessenes Paket lag bei 181
// ob man das Paket braucht ist eine andere Frage
maxlen = data;
lcdx_printf_at_P( 1, 7, MNORMAL, 0,1, PSTR("%3u"), maxlen );
set_beep( 25, 0xffff, BeepNormal ); // kurzer Beep
}
#endif
break;
 
 
case 5: if( data != 0 ) // GPS: length hi
state = 0;
else
{
checksum(data);
state++;
}
break;
 
 
case 6: UBX_buffer[UBX_payload_counter] = data; // GPS: data
checksum(data);
UBX_payload_counter++;
length--;
if( length == 0 )
{
state++;
};
break;
 
 
case 7: state++; // GPS: check lo
UBX_ck_a = data;
break;
 
 
case 8: state = 0; // GPS: check hi
if((UBX_ck_a == ck_a) && (data == ck_b))
{
timer_mk_timeout = GPSTIMEOUT;
refresh = true;
}
 
} // end: switch( state )
} // end: if( uart_getc_nb(&data) )
 
 
//------------------------------------------
// Pruefe PKT-Update oder andere PKT-Aktion
//------------------------------------------
/*
// funktioniert hier nicht - warum auch immer
if( PKT_CtrlHook() ) // Update vom Updatetool angefordert?
{
redraw = true;
}
*/
 
 
} while( !get_key_press(1 << KEY_ESC) && timer_mk_timeout );
 
 
 
//--------------------------
// in den Timeout gelaufen?
//--------------------------
if( !timer_mk_timeout )
{
//PKT_Message_Datenverlust( timeout, beep)
PKT_Message_Datenverlust( 500, true); // 500 = 5 Sekunden
}
 
clear_key_all();
 
SwitchToNC();
}
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mk/mkgpsinfo.h
0,0 → 1,50
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY mkgpsinfo.h
//#
//# 14.05.2014 OG
//# - chg: umbenannt von 'gps.h' zu 'mkgpsinfo.h'
//# - chg: gps() ist jetzt MK_Gps_Info()
//# - add: Source-Historie ergaenzt
//############################################################################
 
 
 
#ifndef _GPS_H
#define _GPS_H
 
void MK_Gps_Info( void );
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mk
Property changes:
Added: svn:ignore
+_old_source
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mk-data-structs.h
0,0 → 1,501
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY mk_data-stucts.h
//#
//# 16.07.2015 Cebra
//# - chg: Receiver Selection
//# RECEIVER_USER 8 -> RECEIVER_MLINK 8
//# - add: Receiver Selection
//# RECEIVER_USER 9
//#
//# 26.01.2015 Cebra
//# - chg: #defines für ServoCompInvert an aktuelle Syntax angepasst
//# SVNick -> SERVO_NICK_INV
//# SVRoll -> SERVO_ROLL_INV
//# SVRelMov -> SERVO_RELATIVE
//# - add: #define CH_DIRECTION_1 0x08 für ComingHome Ausrichtung
//# #define CH_DIRECTION_2 0x10
//#
//# 19.06.2014 OG
//# - chg: Aktualisiert: struct Point_t (aus Quelle: NaviCtrl V2.06f/waypoints.h - Revision 546)
//#
//# 12.02.2014 OG
//# - del: die alten defines bzgl. MKVERSIONnnn und mk_param_struct_t entfernt
//#
//# 02.12.2013 Cebra
//# - add: #define MKVERSION201f, Erweiterung für FC201f
//#
//# 21.10.2013 Cebra
//# - add: #define MKVERSION201a, Erweiterung für FC201a
//#
//# 26.06.2013 OG
//# - chg: "0.91f" -> "0.91f/l"
//#
//# 13.06.2013 OG
//# - chg: "0.90j" -> "0.90h/j"
//# - chg: Code-Layout
//#
//# 05.06.2013 Cebra
//# - chg: Anpassungen an FC091c
//#
//# 03.06.2013 Cebra
//# - chg: #define Fehler beseitigt
//#
//# 30.05.2013 Cebra
//# - add: #define MKVERSION091a, Erweiterung für FC091a
//#
//# 13.05.2013 Cebra
//# - add: #define MKVERSION090h // wegen GPS-Zeitausgabe NC
//#
//# 11.05.2013 OG
//# - add: DateTime_t
//#
//# 20.03.2013 OG
//# - add: BLData_t (http://www.mikrokopter.de/ucwiki/en/SerialCommands/BLDataStruct)
//############################################################################
 
 
#ifndef _MK_DATA_STRUCTS_H
#define _MK_DATA_STRUCTS_H
 
#include "main.h"
 
//##################################################################################
 
//##################################################################################
 
 
#define u8 uint8_t
#define s8 int8_t
#define u16 uint16_t
#define s16 int16_t
#define u32 uint32_t
#define s32 int32_t
 
#define NUMBER_OF_DEBUG_DATAS 32
#define ANALOG_NAME_LENGTH 16
 
 
// Version of supported serial protocol
#define MIN_VERSION 7
#define MAX_VERSION 10
 
 
// Setting index
#define SETTING_1 1
#define SETTING_2 2
#define SETTING_3 3
#define SETTING_4 4
#define SETTING_5 5
#define SETTING_CURRENT 0xff
 
 
// MikroKopter defines
// taken from
// FC Software eeprom.h
//
 
//GlobalConfig3 aus FC/eeprom.h
#define CFG3_NO_SDCARD_NO_START 0x01
#define CFG3_DPH_MAX_RADIUS 0x02
#define CFG3_VARIO_FAILSAFE 0x04
#define CFG3_MOTOR_SWITCH_MODE 0x08 //FC0.88L 7.5.12
#define CFG3_NO_GPSFIX_NO_START 0x10 //FC0.88L 7.5.12
#define CFG3_USE_NC_FOR_OUT1 0x20
#define CFG3_SPEAK_ALL 0x40
#define CFG3_SERVO_NICK_COMP_OFF 0x80
 
 
//GlobalConfig
#define CFG_HOEHENREGELUNG 0x01
#define CFG_HOEHEN_SCHALTER 0x02
#define CFG_HEADING_HOLD 0x04
#define CFG_KOMPASS_AKTIV 0x08
#define CFG_KOMPASS_FIX 0x10
#define CFG_GPS_AKTIV 0x20
#define CFG_ACHSENKOPPLUNG_AKTIV 0x40
#define CFG_DREHRATEN_BEGRENZER 0x80
 
//Bitconfig MAsk
#define CFG_LOOP_OBEN 0x01
#define CFG_LOOP_UNTEN 0x02
#define CFG_LOOP_LINKS 0x04
#define CFG_LOOP_RECHTS 0x08
#define CFG_MOTOR_BLINK1 0x10
#define CFG_MOTOR_OFF_LED1 0x20
#define CFG_MOTOR_OFF_LED2 0x40
#define CFG_MOTOR_BLINK2 0x80
 
// ServoCompInvert, FC0.89 entfällt und geändert s.u.
 
//#define SVNick 0x01
//#define SVRoll 0x02
//#define SVRelMov 0x04
 
 
//ab FC 209a (26.1.2015 cebra)
 
// bitcoding for EE_Parameter.ServoCompInvert
#define SERVO_NICK_INV 0x01
#define SERVO_ROLL_INV 0x02
#define SERVO_RELATIVE 0x04 // direct poti control or relative moving of the servo value
#define CH_DIRECTION_1 0x08
#define CH_DIRECTION_2 0x10
 
//CH Orientation ServoBits 0x10 0x08
// --> no change 0 0
// --> front to starting point 0 1
// --> rear to to starting point 1 0
//-> start orientation 1 1
 
 
// ExtraConfig
#define CFG2_HEIGHT_LIMIT 0x01
#define CFG2_VARIO_BEEP 0x02
#define CFG_SENSITIVE_RC 0x04 // 26.1.2015 entfällt ab FC 209a, cebra
#define CFG_3_3V_REFERENCE 0x08
#define CFG_NO_RCOFF_BEEPING 0x10
#define CFG_GPS_AID 0x20
#define CFG_LEARNABLE_CAREFREE 0x40
#define CFG_IGNORE_MAG_ERR_AT_STARTUP 0x80
 
// bit mask for ParamSet.Config0
#define CFG0_AIRPRESS_SENSOR 0x01
#define CFG0_HEIGHT_SWITCH 0x02
#define CFG0_HEADING_HOLD 0x04
#define CFG0_COMPASS_ACTIVE 0x08
#define CFG0_COMPASS_FIX 0x10
#define CFG0_GPS_ACTIVE 0x20
#define CFG0_AXIS_COUPLING_ACTIVE 0x40
#define CFG0_ROTARY_RATE_LIMITER 0x80
 
// defines for the receiver selection
#define RECEIVER_PPM 0
#define RECEIVER_SPEKTRUM 1
#define RECEIVER_SPEKTRUM_HI_RES 2
#define RECEIVER_SPEKTRUM_LOW_RES 3
#define RECEIVER_JETI 4
#define RECEIVER_ACT_DSL 5
#define RECEIVER_HOTT 6
#define RECEIVER_SBUS 7
#define RECEIVER_MLINK 8 //FC2.11 16.7.2015 CB
#define RECEIVER_USER 9 //FC2.11 16.7.2015 CB
#define RECEIVER_UNKNOWN 0xFF
 
// MikroKopter Flags
// taken from
// http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=FlightCtrl&path=%2Ftags%2FV0.73d%2Ffc.h
//alt 0.86
//#define FCFLAG_MOTOR_RUN 0x01
//#define FCFLAG_FLY 0x02
//#define FCFLAG_CALIBRATE 0x04
//#define FCFLAG_START 0x08
//#define FCFLAG_NOTLANDUNG 0x10
//#define FCFLAG_LOWBAT 0x20
//#define FCFLAG_SPI_RX_ERR 0x40
//#define FCFLAG_I2CERR 0x80
// FC_StatusFlags 0.88
#define FC_STATUS_MOTOR_RUN 0x01
#define FC_STATUS_FLY 0x02
#define FC_STATUS_CALIBRATE 0x04
#define FC_STATUS_START 0x08
#define FC_STATUS_EMERGENCY_LANDING 0x10
#define FC_STATUS_LOWBAT 0x20
#define FC_STATUS_VARIO_TRIM_UP 0x40
#define FC_STATUS_VARIO_TRIM_DOWN 0x80
 
// FC_StatusFlags2
#define FC_STATUS2_CAREFREE 0x01
#define FC_STATUS2_ALTITUDE_CONTROL 0x02
#define FC_STATUS2_RC_FAILSAVE_ACTIVE 0x04
#define FC_STATUS2_OUT1_ACTIVE 0x08
#define FC_STATUS2_OUT2_ACTIVE 0x10
 
 
 
// NaviCtrl Flags
// taken from
// http://mikrocontroller.cco-ev.de/mikrowebsvn/filedetails.php?repname=NaviCtrl&path=%2Ftags%2FV0.15c%2Fuart1.h
#define NC_FLAG_FREE 0x01
#define NC_FLAG_PH 0x02
#define NC_FLAG_CH 0x04
#define NC_FLAG_RANGE_LIMIT 0x08
#define NC_FLAG_NOSERIALLINK 0x10
#define NC_FLAG_TARGET_REACHED 0x20
#define NC_FLAG_MANUAL_CONTROL 0x40
#define NC_FLAG_GPS_OK 0x80
 
 
typedef struct
{
unsigned char SWMajor;
unsigned char SWMinor;
unsigned char ProtoMajor;
unsigned char ProtoMinor;
unsigned char SWPatch;
unsigned char HardwareError[5];
} __attribute__((packed)) Version_t;
 
 
 
// FC Debug Struct
// portions taken and adapted from
// http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=FlightCtrl&path=%2Ftags%2FV0.72p%2Fuart.h
typedef struct // 0.86
{
uint8_t Digital[2];
// NC: unsigned; FC: signed !!!!
int16_t Analog[32]; // Debugvalues
} __attribute__((packed)) DebugData_t;
 
 
 
//******************************************************************
// uart1.h NC 0.87, zur Zeit hier nicht verwendet 28.01.2012 CB
#define AMPEL_FC 0x01
#define AMPEL_BL 0x02
#define AMPEL_NC 0x04
#define AMPEL_COMPASS 0x08
 
 
 
typedef struct //0.87
{
u8 StatusGreen;
u8 StatusRed;
u16 Analog[32]; // Debugwerte
} __attribute__((packed)) DebugOut_t;
//******************************************************************
 
 
// NaviCtrl OSD Structs
// portions taken and adapted from
// http://svn.mikrokopter.de/mikrowebsvn/filedetails.php?repname=NaviCtrl&path=%2Ftags%2FV0.15c%2Fuart1.h
//
 
typedef struct //NC uart1.h
{
s16 AngleNick; // in 0.1 deg
s16 AngleRoll; // in 0.1 deg
s16 Heading; // in 0.1 deg
u8 StickNick;
u8 StickRoll;
u8 StickYaw;
u8 StickGas;
u8 reserve[4];
} __attribute__((packed)) Data3D_t;
 
 
 
typedef struct
{
s32 Longitude; // in 1E-7 deg
s32 Latitude; // in 1E-7 deg
s32 Altitude; // in mm
u8 Status; // validity of data
} __attribute__((packed)) GPS_Pos_t;
 
 
 
typedef struct
{
u16 Distance; // distance to target in cm
s16 Bearing; // course to target in deg
} __attribute__((packed)) GPS_PosDev_t;
 
 
 
 
//----------------------------
// aus NC waypoint.h
//
// AKTUALISIERT: 18.06.2014 OG
//
// Anmerkung 18.06.2014 OG
// "Name" hinzugefuegt - das gibt es
// seit dem 23.03.2012!
//----------------------------
typedef struct
{
GPS_Pos_t Position; // the gps position of the waypoint, see ubx.h for details
s16 Heading; // orientation, 0 no action, 1...360 fix heading, neg. = Index to POI in WP List
u8 ToleranceRadius; // in meters, if the MK is within that range around the target, then the next target is triggered
u8 HoldTime; // in seconds, if the was once in the tolerance area around a WP, this time defines the delay before the next WP is triggered
u8 Event_Flag; // future implementation
u8 Index; // to indentify different waypoints, workaround for bad communications PC <-> NC
u8 Type; // typeof Waypoint
u8 WP_EventChannelValue; // Will be transferred to the FC and can be used as Poti value there
u8 AltitudeRate; // rate to change the setpoint in steps of 0.1m/s
u8 Speed; // rate to change the Position(0 = max) in steps of 0.1m/s
u8 CamAngle; // Camera servo angle in degree (255 -> POI-Automatic)
u8 Name[4]; // Name of that point (ASCII)
u8 reserve[2]; // reserve
} __attribute__((packed)) Point_t;
 
 
 
 
//----------------------------
// aus NC waypoint.h
// VERALTET! 18.06.2014 OG
//----------------------------
/*
typedef struct
{
GPS_Pos_t Position; // the gps position of the waypoint, see ubx.h for details
s16 Heading; // orientation, 0 no action, 1...360 fix heading, neg. = Index to POI in WP List
u8 ToleranceRadius; // in meters, if the MK is within that range around the target, then the next target is triggered
u8 HoldTime; // in seconds, if the was once in the tolerance area around a WP, this time defines the delay before the next WP is triggered
u8 Event_Flag; // future implementation
u8 Index; // to indentify different waypoints, workaround for bad communications PC <-> NC
u8 Type; // typeof Waypoint
u8 WP_EventChannelValue; //
u8 AltitudeRate; // rate to change the setpoint
u8 Speed; // rate to change the Position
u8 CamAngle; // Camera servo angle
u8 reserve[6]; // reserve
} __attribute__((packed)) Point_t;
*/
 
 
// NaviCtrl struct
// taken from
// http://mikrocontroller.cco-ev.de/mikrowebsvn/filedetails.php?repname=NaviCtrl&path=%2Ftags%2FV0.15c%2Fuart1.h
//
#define NAVIDATA_VERSION 5
 
typedef struct
{
u8 Version; // version of the data structure
GPS_Pos_t CurrentPosition; // see ubx.h for details
GPS_Pos_t TargetPosition;
GPS_PosDev_t TargetPositionDeviation;
GPS_Pos_t HomePosition;
GPS_PosDev_t HomePositionDeviation;
u8 WaypointIndex; // index of current waypoints running from 0 to WaypointNumber-1
u8 WaypointNumber; // number of stored waypoints
u8 SatsInUse; // number of satellites used for position solution
s16 Altimeter; // hight according to air pressure
s16 Variometer; // climb(+) and sink(-) rate
u16 FlyingTime; // in seconds
u8 UBat; // Battery Voltage in 0.1 Volts
u16 GroundSpeed; // speed over ground in cm/s (2D)
s16 Heading; // current flight direction in ° as angle to north
s16 CompassHeading; // current compass value in
s8 AngleNick; // current Nick angle in 1
s8 AngleRoll; // current Roll angle in 1
u8 RC_Quality; // RC_Quality
u8 FCStatusFlags; // Flags from FC
u8 NCFlags; // Flags from NC
u8 Errorcode; // 0 --> okay
u8 OperatingRadius; // current operation radius around the Home Position in m
s16 TopSpeed; // velocity in vertical direction in cm/s
u8 TargetHoldTime; // time in s to stay at the given target, counts down to 0 if target has been reached
u8 FCStatusFlags2; // StatusFlags2 (since version 5 added)
s16 SetpointAltitude; // setpoint for altitude
u8 Gas; // for future use
u16 Current; // actual current in 0.1A steps
u16 UsedCapacity; // used capacity in mAh
} __attribute__((packed)) NaviData_t;
 
 
 
typedef struct
{
uint8_t Version; // the version of the BL (0 = old)
uint8_t SetPoint; // written by attitude controller
uint8_t SetPointLowerBits; // for higher Resolution of new BLs
uint8_t State; // 7 bit for I2C error counter, highest bit indicates if motor is present
uint8_t ReadMode; // select data to read
// the following bytes must be exactly in that order!
uint8_t Current; // in 0.1 A steps, read back from BL
uint8_t MaxPWM; // read back from BL -> is less than 255 if BL is in current limit, not running (250) or starting (40)
int8_t Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in �C
} __attribute__((packed)) MotorData_t;
 
 
 
typedef struct
{
uint8_t Revision; // must be BL_REVISION
uint8_t SetMask; // settings mask
uint8_t PwmScaling; // maximum value of control pwm, acts like a thrust limit
uint8_t CurrentLimit; // current limit in A
uint8_t TempLimit; // in �C
uint8_t CurrentScaling; // scaling factor for current measurement
uint8_t BitConfig; // see defines above
uint8_t crc; // checksum
} __attribute__((packed)) BLConfig_t;
 
 
 
//##############################################################################
//# Datenstruktur von ehemals mk_param_struct_t jetzt via mk/paramset.c !
//##############################################################################
 
 
//-------------------------------------
// 20.03.2013 OG: BLData_t
// aus: http://www.mikrokopter.de/ucwiki/en/SerialCommands/BLDataStruct
//-------------------------------------
typedef struct
{
unsigned char Index; // address of BL-Ctrl
unsigned char Current; // in 0.1 A steps, read back from BL
unsigned char Temperature; // old BL-Ctrl will return a 255 here, the new version (>= V2.0) the temp. in °C
unsigned char MaxPWM; // EVENTUELL: read back from BL -> is less than 255 if BL is in current limit, not running (250) or starting (40)
unsigned char Status; // EVENTUELL: 7 bit for I2C error counter, highest bit indicates if motor is present
} BLData_t;
 
 
 
//-------------------------------------
// 11.05.2013 OG: DateTime_t
// aus: NC v0.30g timer1.h
//-------------------------------------
typedef struct{
u16 Year;
u8 Month;
u8 Day;
u8 Hour;
u8 Min;
u8 Sec;
u16 mSec;
u8 Valid;
} DateTime_t;
 
 
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mksettings/mkparameters.c
0,0 → 1,2692
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY mkparameters.c
//#
//# 16.07.2015 Cebra
//# - add: Erweiterung SingleWpControlChannel; (FC2.11a)
//# MenuKeyChannel; (FC2.11a)
//#
//# 09.04.2015 Cebra
//# - add: Erweiterung paramEditItemTable und ID_MENU_KAMERA_Items[] um neue Parameter (FC2.09j)
//# param_ServoNickFailsave, param_ServoRollFailsave, param_Servo3Failsave, param_Servo4Failsave, param_Servo5Failsave
//#
//# 26.01.2015 Cebra
//# - add: Comming Home Ausrichtung hinzugefügt,
//# neue Einstellungen ab FC 209a im Wert ServoCompInvert, Bit4 + Bit5
//#
//# 26.09.2014 Cebra
//# - add: im Menü Höhe -> param_Hoehe_TiltCompensation, FC207d
//#
//# 04.06.2014 OG
//# - chg: MK_Parameters_MenuMain() eine Menue-Trennlinie hinter Favoriten eingefuegt
//#
//# 14.05.2014 OG
//# - chg: include "mkbase.h" geaendert auf "../mk/mkbase.h"
//#
//# 11.05.2014 OG
//# - chg: Menu_Favoriten() umgestellt auf MenuCtrl_SetTitleFromParentItem()
//# - chg: Menu_EditCategory() umgestellt auf MenuCtrl_SetTitleFromParentItem()
//#
//# 10.05.2014 OG
//# - del: editDisableDeclCalc() - wurde ersetzt durch eine Transform-Funktion
//# in paramset.c und wird jetzt von editGeneric() bearbeitet
//#
//# 07.05.2014 OG
//# - chg: Menu_Favoriten() - uebernimmt den gegebenen Menuetitel vom
//# uebergeordneten Eintrag aus mkparameters_messages.h (also Multilanguage)
//# - chg: fav_add() - erweitert um Menue-Separatoren (Trennlinien) aufzunehmen
//# - chg: Menu_EditCategory() umgestellt auf MenuCtrl_PushSeparatorID()
//#
//# 06.05.2014 OG
//# - add: Favoriten-Verwaltung implementiert (Aenderungen an verschiedenen Funktionen)
//#
//# 18.04.2014 OG
//# - fix: im ID_MENU_NAVICTRL fehlten param_NaviStickThreshold ("GPS Stick-Schwelle")
//# und param_NaviGpsMinSat ("Min. Sat")
//#
//# 17.04.2014 OG
//# - add: param_Servo3OnValue, param_Servo3OffValue, param_Servo4OnValue
//# param_Servo4OffValue
//# - add: param_NaviMaxFlyingRange, param_NaviDescendRange
//# - chg: Menu_EditCategory() blendet ggf. doppelt aufeinanderfolgenden
//# Menue-Separatoren aus
//#
//# 30.03.2014 OG
//# - chg: Sprache Hollaendisch vollstaendig entfernt
//# - chg: MenuCtrl_PushML_P() umgestellt auf MenuCtrl_PushML2_P()
//#
//# 29.03.2014 OG
//# - chg: versch. Funktioionen del: MenuCtrl_SetShowBatt() wegen Aenderung Default auf true
//# - add: Unterstuetzung fuer Rev. 100
//# (param_AutoPhotoDistance, param_AutoPhotoAtitudes, param_SingleWpSpeed)
//#
//# 27.03.2014 OG
//# kompletter neuer Code fuer ein erstes Release
//#
//# 23.02.2014 OG
//# - chg: MK_Parameters_Menu() umbenannt zu MK_Parameters()
//#
//# 20.02.2014 OG
//# - chg: MK_Parameters_Menu() meldet "nicht verfügbar"
//#
//# 12.02.2014 OG - NEU
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <avr/wdt.h>
#include <util/delay.h>
#include <avr/eeprom.h>
#include <util/delay.h>
#include <string.h>
#include <util/atomic.h>
 
//#include "../lipo/lipo.h"
#include "../main.h"
#include "../lipo/lipo.h"
#include "../lcd/lcd.h"
#include "../uart/usart.h"
#include "../utils/menuctrl.h"
#include "../utils/xutils.h"
 
#include "../uart/uart1.h"
#include "../mk-data-structs.h"
//#include "../menu.h"
#include "../timer/timer.h"
#include "../eeprom/eeprom.h"
#include "../messages.h"
#include "../pkt/pkt.h"
#include "../mk/mkbase.h"
#include "paramset.h"
#include "mkparameters.h"
#include "mkparameters_messages.h"
 
 
//#############################################################################################
//# Strukturen; Forward-Deklarationen
//#############################################################################################
 
#define DEBUG_PARAMEDIT // schaltet zusaetzliche Debug-Ausgaben ein
 
#define EOF 255 // End Of File (bzw. end of Table...)
 
#define SEPARATOR 254 // ID fuer einen Separator in einem Menue (Trennlinie)
 
 
#define SCREEN_REFRESH 1 // neuzeichnen/refresh der Anzeige
#define SCREEN_REDRAW 2 // neuzeichnen/refresh der Anzeige
 
 
//--------------------------------------------
// editGenericCode_t
// deklariert ein einzelnes Code-Zeichen fuer Edit-Generic
//--------------------------------------------
typedef struct
{
unsigned char code; // z.B. '0', '1', 'v', 'P', 'C' ... (einzelnes Zeichen aus paramEditItem_t.format )
unsigned char min;
unsigned char max;
const char *shortText_de; //
const char *shortText_en;
const char *longText_de;
const char *longText_en;
} editGenericCode_t;
 
 
 
//---------------------------------------------
//----- globale Modulvariablen
//---------------------------------------------
 
editGenericCode_t genericCode; // Daten eines einzelnen Code-Zeichen (im RAM)
paramEditItem_t paramEditItem; // RAM Buffer: fuer ein Element von paramEditDef
char paramEditFormat[MKPARAM_STRBUFFER_LEN]; // RAM Buffer: fuer 'str' von paramEdit (Format; editGeneric)
char mkparam_strValueBuffer[MKPARAM_STRBUFFER_LEN]; // Anzeige eines Values als Klartext; Kurz (fuer das Menue) oder Lang (in der Edit-Funktion)
 
 
 
//#############################################################################################
//#
//#############################################################################################
 
static const char GENERIC_SHORT_VALUE_de[] PROGMEM = "%3u"; // nur Wert anzeigen - min/max wird uebergeordnet definiert
#define GENERIC_SHORT_VALUE_en GENERIC_SHORT_VALUE_de
#define GENERIC_LONG_VALUE_de GENERIC_SHORT_VALUE_de
#define GENERIC_LONG_VALUE_en GENERIC_SHORT_VALUE_de
//
//static const char GENERIC_SHORT_VALUE_ACCZ_de[] PROGMEM = "%4u"; // nur Wert anzeigen - min/max wird uebergeordnet definiert
//#define GENERIC_SHORT_VALUE_ACCZ_en GENERIC_SHORT_VALUE_ACCZ_de
//#define GENERIC_LONG_VALUE_ACCZ_de GENERIC_SHORT_VALUE_ACCZ_de
//#define GENERIC_LONG_VALUE_ACCZ_en GENERIC_SHORT_VALUE_ACCZ_de
 
 
static const char GENERIC_SHORT_NO_de[] PROGMEM = " N";
#define GENERIC_SHORT_NO_en GENERIC_SHORT_NO_de
static const char GENERIC_LONG_NO_de[] PROGMEM = "Nein";
static const char GENERIC_LONG_NO_en[] PROGMEM = "No";
 
static const char GENERIC_SHORT_YES_de[] PROGMEM = " J";
static const char GENERIC_SHORT_YES_en[] PROGMEM = " Y";
static const char GENERIC_LONG_YES_de[] PROGMEM = "Ja";
static const char GENERIC_LONG_YES_en[] PROGMEM = "Yes";
 
static const char GENERIC_SHORT_POTI_de[] PROGMEM = " P%u";
#define GENERIC_SHORT_POTI_en GENERIC_SHORT_POTI_de
static const char GENERIC_LONG_POTI_de[] PROGMEM = "Poti %u";
#define GENERIC_LONG_POTI_en GENERIC_LONG_POTI_de
 
static const char GENERIC_SHORT_CHANNEL_de[] PROGMEM = "C%2u";
#define GENERIC_SHORT_CHANNEL_en GENERIC_SHORT_CHANNEL_de
static const char GENERIC_LONG_CHANNEL_de[] PROGMEM = "Kanal %u";
static const char GENERIC_LONG_CHANNEL_en[] PROGMEM = "Channel %u";
 
static const char GENERIC_SHORT_SERCHANNEL_de[] PROGMEM = "S%2u";
#define GENERIC_SHORT_SERCHANNEL_en GENERIC_SHORT_SERCHANNEL_de
static const char GENERIC_LONG_SERCHANNEL_de[] PROGMEM = "Ser. Kanal %u";
static const char GENERIC_LONG_SERCHANNEL_en[] PROGMEM = "Ser. Channel %u";
 
static const char GENERIC_SHORT_AUS_de[] PROGMEM = "Aus";
static const char GENERIC_SHORT_AUS_en[] PROGMEM = "Off";
#define GENERIC_LONG_AUS_de GENERIC_SHORT_AUS_de
#define GENERIC_LONG_AUS_en GENERIC_SHORT_AUS_en
 
static const char GENERIC_SHORT_INACTIV_de[] PROGMEM = "Ina";
#define GENERIC_SHORT_INACTIV_en GENERIC_SHORT_INACTIV_de
static const char GENERIC_LONG_INACTIV_de[] PROGMEM = "Inaktiv";
#define GENERIC_LONG_INACTIV_en GENERIC_LONG_INACTIV_de
 
static const char GENERIC_SHORT_WPEVENT_de[] PROGMEM = "WPE";
#define GENERIC_SHORT_WPEVENT_en GENERIC_SHORT_WPEVENT_de
static const char GENERIC_LONG_WPEVENT_de[] PROGMEM = "WP-Event";
#define GENERIC_LONG_WPEVENT_en GENERIC_LONG_WPEVENT_de
 
static const char GENERIC_SHORT_MINIMUM_de[] PROGMEM = "Min";
#define GENERIC_SHORT_MINIMUM_en GENERIC_SHORT_MINIMUM_de
static const char GENERIC_LONG_MINIMUM_de[] PROGMEM = "Minimum";
#define GENERIC_LONG_MINIMUM_en GENERIC_LONG_MINIMUM_de
 
static const char GENERIC_SHORT_MIDDLE_de[] PROGMEM = "Mid";
#define GENERIC_SHORT_MIDDLE_en GENERIC_SHORT_MIDDLE_de
static const char GENERIC_LONG_MIDDLE_de[] PROGMEM = "Mitte";
static const char GENERIC_LONG_MIDDLE_en[] PROGMEM = "Middle";
 
static const char GENERIC_SHORT_MAXIMUM_de[] PROGMEM = "Max";
#define GENERIC_SHORT_MAXIMUM_en GENERIC_SHORT_MAXIMUM_de
static const char GENERIC_LONG_MAXIMUM_de[] PROGMEM = "Maximum";
#define GENERIC_LONG_MAXIMUM_en GENERIC_LONG_MAXIMUM_de
 
static const char GENERIC_SHORT_AN_de[] PROGMEM = " An";
static const char GENERIC_SHORT_AN_en[] PROGMEM = " On";
#define GENERIC_LONG_AN_de GENERIC_SHORT_AN_de
#define GENERIC_LONG_AN_en GENERIC_SHORT_AN_en
 
static const char GENERIC_SHORT_FREE_de[] PROGMEM = "Fre"; // z.b. "GPS Modus Steuerung"
#define GENERIC_SHORT_FREE_en GENERIC_SHORT_FREE_de
static const char GENERIC_LONG_FREE_de[] PROGMEM = "Free";
#define GENERIC_LONG_FREE_en GENERIC_LONG_FREE_de
 
static const char GENERIC_SHORT_CH_de[] PROGMEM = " CH"; // z.b. "GPS Modus Steuerung"
#define GENERIC_SHORT_CH_en GENERIC_SHORT_CH_de
static const char GENERIC_LONG_CH_de[] PROGMEM = "Coming Home (CH)";
#define GENERIC_LONG_CH_en GENERIC_LONG_CH_de
 
static const char GENERIC_SHORT_PH_de[] PROGMEM = " PH"; // z.b. "GPS Modus Steuerung"
#define GENERIC_SHORT_PH_en GENERIC_SHORT_PH_de
static const char GENERIC_LONG_PH_de[] PROGMEM = "Position Hold (PH)";
#define GENERIC_LONG_PH_en GENERIC_LONG_PH_de
 
static const char GENERIC_SHORT_DISABLED_de[] PROGMEM = "Dis"; // z.b. "Auto Start / Land"
#define GENERIC_SHORT_DISABLED_en GENERIC_SHORT_DISABLED_de
static const char GENERIC_LONG_DISABLED_de[] PROGMEM = "Disabled";
#define GENERIC_LONG_DISABLED_en GENERIC_LONG_DISABLED_de
 
static const char GENERIC_SHORT_OUT_de[] PROGMEM = "Ou%1u"; // z.B. Servo 3 und Servo 4
#define GENERIC_SHORT_OUT_en GENERIC_SHORT_OUT_de
static const char GENERIC_LONG_OUT_de[] PROGMEM = "Out %1u";
#define GENERIC_LONG_OUT_en GENERIC_LONG_OUT_de
 
static const char GENERIC_SHORT_CH_OR_NC_de[] PROGMEM = "kÄn";
static const char GENERIC_SHORT_CH_OR_NC_en[] PROGMEM = "nCh";
static const char GENERIC_LONG_CH_OR_NC_de[] PROGMEM = "Keine Änderung";
static const char GENERIC_LONG_CH_OR_NC_en[] PROGMEM = "no change";
 
static const char GENERIC_SHORT_CH_OR_FH_de[] PROGMEM = "FzH";
static const char GENERIC_SHORT_CH_OR_FH_en[] PROGMEM = "FtH";
static const char GENERIC_LONG_CH_OR_FH_de[] PROGMEM = "Front zu Home";
static const char GENERIC_LONG_CH_OR_FH_en[] PROGMEM = "front to home";
 
static const char GENERIC_SHORT_CH_OR_RH_de[] PROGMEM = "HzH";
static const char GENERIC_SHORT_CH_OR_RH_en[] PROGMEM = "RtH";
static const char GENERIC_LONG_CH_OR_RH_de[] PROGMEM = "Heck zu Home";
static const char GENERIC_LONG_CH_OR_RH_en[] PROGMEM = "rear to home";
 
static const char GENERIC_SHORT_CH_OR_SO_de[] PROGMEM = "wSt";
static const char GENERIC_SHORT_CH_OR_SO_en[] PROGMEM = "sOr";
static const char GENERIC_LONG_CH_OR_SO_de[] PROGMEM = "wie beim Start";
static const char GENERIC_LONG_CH_OR_SO_en[] PROGMEM = "same as start";
 
 
 
//------------------------------------------------
 
 
 
/*************************************************
//-------------
// ZUR INFO
//-------------
typedef struct
{
unsigned char code; // '0', '1', 'v', 'P', 'C' ...
unsigned char min;
unsigned char max;
const char *shortText_de;
const char *shortText_en;
const char *longText_de;
const char *longText_en;
} editGenericCode_t;
*************************************************/
 
// Anmerkung: kann bei Bedarf evtl. zu PROGMEM umschreiben
//editGenericCode_t const editGenericCode[] PROGMEM =
 
editGenericCode_t editGenericCode[] =
{
{ 'v', 0, 0, GENERIC_SHORT_VALUE_de, GENERIC_SHORT_VALUE_en, GENERIC_LONG_VALUE_de, GENERIC_LONG_VALUE_en }, // nur Wert anzeigen - min/max wird uebergeordnet definiert
// { 'z', 0, 0, GENERIC_SHORT_VALUE_ACCZ_de, GENERIC_SHORT_VALUE_ACCZ_en, GENERIC_LONG_VALUE_ACCZ_de, GENERIC_LONG_VALUE_ACCZ_en }, // nur Wert anzeigen x 4- min/max wird uebergeordnet definiert
{ '0', 0, 0, GENERIC_SHORT_NO_de, GENERIC_SHORT_NO_en, GENERIC_LONG_NO_de, GENERIC_LONG_NO_en },
{ '1', 1, 1, GENERIC_SHORT_YES_de, GENERIC_SHORT_YES_en, GENERIC_LONG_YES_de, GENERIC_LONG_YES_en },
{ 'P', 255,248, GENERIC_SHORT_POTI_de, GENERIC_SHORT_POTI_en, GENERIC_LONG_POTI_de, GENERIC_LONG_POTI_en },
{ 'C', 1, 16, GENERIC_SHORT_CHANNEL_de, GENERIC_SHORT_CHANNEL_en, GENERIC_LONG_CHANNEL_de, GENERIC_LONG_CHANNEL_en },
{ 'S', 17, 28, GENERIC_SHORT_SERCHANNEL_de, GENERIC_SHORT_SERCHANNEL_en, GENERIC_LONG_SERCHANNEL_de, GENERIC_LONG_SERCHANNEL_en },
{ 'A', 0, 0, GENERIC_SHORT_AUS_de, GENERIC_SHORT_AUS_en, GENERIC_LONG_AUS_de, GENERIC_LONG_AUS_en },
{ 'I', 0, 0, GENERIC_SHORT_INACTIV_de, GENERIC_SHORT_INACTIV_en, GENERIC_LONG_INACTIV_de, GENERIC_LONG_INACTIV_en },
{ 'W', 29, 29, GENERIC_SHORT_WPEVENT_de, GENERIC_SHORT_WPEVENT_en, GENERIC_LONG_WPEVENT_de, GENERIC_LONG_WPEVENT_en },
{ 'U', 30, 30, GENERIC_SHORT_MINIMUM_de, GENERIC_SHORT_MINIMUM_en, GENERIC_LONG_MINIMUM_de, GENERIC_LONG_MINIMUM_en },
{ 'M', 31, 31, GENERIC_SHORT_MIDDLE_de, GENERIC_SHORT_MIDDLE_en, GENERIC_LONG_MIDDLE_de, GENERIC_LONG_MIDDLE_en },
{ 'X', 32, 32, GENERIC_SHORT_MAXIMUM_de, GENERIC_SHORT_MAXIMUM_en, GENERIC_LONG_MAXIMUM_de, GENERIC_LONG_MAXIMUM_en },
{ 'O', 30, 30, GENERIC_SHORT_AUS_de, GENERIC_SHORT_AUS_en, GENERIC_LONG_AUS_de, GENERIC_LONG_AUS_en }, // ein weiteres "Aus"; z.b. "Motors-Sicherheitsschalter"
{ 'N', 31, 31, GENERIC_SHORT_AN_de, GENERIC_SHORT_AN_en, GENERIC_LONG_AN_de, GENERIC_LONG_AN_en }, // z.b. "Carefree"
{ 'F', 30, 30, GENERIC_SHORT_FREE_de, GENERIC_SHORT_FREE_en, GENERIC_LONG_FREE_de, GENERIC_LONG_FREE_en }, // Free - z.b. "Carefree"
{ 'H', 31, 31, GENERIC_SHORT_CH_de, GENERIC_SHORT_CH_en, GENERIC_LONG_CH_de, GENERIC_LONG_CH_en }, // Coming Home - z.b. "Carefree"
{ 'Q', 32, 32, GENERIC_SHORT_PH_de, GENERIC_SHORT_PH_en, GENERIC_LONG_PH_de, GENERIC_LONG_PH_en }, // Positiosn Hold - z.b. "Carefree"
{ 'D', 0, 0, GENERIC_SHORT_DISABLED_de, GENERIC_SHORT_DISABLED_en, GENERIC_LONG_DISABLED_de, GENERIC_LONG_DISABLED_en }, // Inaktiv - z.b. "Auto Start / Land"
{ 'T', 247,246, GENERIC_SHORT_OUT_de, GENERIC_SHORT_OUT_en, GENERIC_LONG_OUT_de, GENERIC_LONG_OUT_en },
{ 'K', 0, 0, GENERIC_SHORT_CH_OR_NC_de, GENERIC_SHORT_CH_OR_NC_en, GENERIC_LONG_CH_OR_NC_de, GENERIC_LONG_CH_OR_NC_en }, // CommingHome Orientation,
{ 'V', 1, 1, GENERIC_SHORT_CH_OR_FH_de, GENERIC_SHORT_CH_OR_FH_en, GENERIC_LONG_CH_OR_FH_de, GENERIC_LONG_CH_OR_FH_en }, // CommingHome Orientation,
{ 'R', 2, 2, GENERIC_SHORT_CH_OR_RH_de, GENERIC_SHORT_CH_OR_RH_en, GENERIC_LONG_CH_OR_RH_de, GENERIC_LONG_CH_OR_RH_en }, // CommingHome Orientation,
{ 'G', 3, 3, GENERIC_SHORT_CH_OR_SO_de, GENERIC_SHORT_CH_OR_SO_en, GENERIC_LONG_CH_OR_SO_de, GENERIC_LONG_CH_OR_SO_en }, // CommingHome Orientation,
 
{ EOF, 0, 0, 0,0,0,0 } // END OF LIST - MUST BE THE LAST!!
};
 
 
 
 
 
 
 
//#############################################################################################
//#
//#############################################################################################
 
 
static const char GENERIC_NoYes[] PROGMEM = "01"; // Nein, Ja (z.B. (fast) alle Checkboxen)
static const char GENERIC_Value[] PROGMEM = "v"; // value mit min,max aus paramEditItem (in paramEditItemTable) (z.B. Nick/Roll P (0..20) / Min. Gas (0..247) )
static const char GENERIC_ValueACCZ[] PROGMEM = "D"; // value mit min,max aus paramEditItem (in paramEditItemTable) x 4 (ACC Z Landing pulse )
static const char GENERIC_ValuePoti[] PROGMEM = "vP"; // value, Poti (z.B. Gyro Gier P)
static const char GENERIC_ValueOutPoti[] PROGMEM = "vTP"; // value, Out, Poti (z.B. Servo 3 & 4)
static const char GENERIC_Cannel[] PROGMEM = "C"; // Channel (z.B. Gas / Gier / Nick / Roll)
static const char GENERIC_AusChSerWpeMMM[] PROGMEM = "ACSWUMX"; // Aus, Channel, Ser. Channel, WP Event, Minimum, Mitte, Maximum (z.B. Poti 1..8)
static const char GENERIC_DisChSerWpeOff[] PROGMEM = "DCSWO"; // Disabled, Channel, Ser. Channel, WP Event, Off (z.B. Motors-Sicherheitsschalter)
static const char GENERIC_DisChSerWpeOffOn[] PROGMEM = "DCSWON"; // Disabled, Channel, Ser. Channel, WP Event, Off, On (z.B. Carefree)
static const char GENERIC_DisChSerWpeFreeCHPH[] PROGMEM = "DCSWFHQ"; // Disabled, Channel, Ser. Channel, WP Event, Free, CH, PH (z.B. GPS Modus Steuerung)
static const char GENERIC_DisChSer[] PROGMEM = "DCS"; // Disabled, Channel, Ser. Channel (z.B. Auto Start / Land)
static const char GENERIC_CH_Orientation[] PROGMEM = "KVRG"; // Keine Änderung, vorne Home, Heck Home, gleiche Richtung (Comming Home Orientation
static const char GENERIC_InaChSerWpeMMM[] PROGMEM = "ICSWUMX"; // Inactiv, Channel, Ser. Channel, WP Event, Minimum, Mitte, Maximum(z.B. Menu Key Channel
 
 
 
 
/*************************************************
//-------------
// ZUR INFO
//-------------
typedef struct
{
unsigned char paramID; // paramID aus paramset.h
void (*editfunc)(unsigned char paramID, uint8_t cmd); // Edit-Funktion - z.B. editGeneric(); cmd = MKPARAM_EDIT oder MKPARAM_SHORTVALUE
const char *format; // Parameter: String (PROGMEM) (vorallem fuer editGeneric() )
unsigned char min; // Parameter: min (P1)
unsigned char max; // Parameter: max (P2)
const char *title_de; // Text in PROGMEM - Menuetext und Beschreibung im Edit-Screen
const char *title_en; // Text in PROGMEM
} paramEditItem_t;
*************************************************/
 
//----------------------
// HINWEIS!
// Die unten stehende Aufgliederung in die verschiedenen Menue-Bereiche ist nur zur ORIENTIERUNG!
// Jede paramID wird nur EINMAL deklariert - die Zuordnung in die Menues erfolgt in den
// nachfolgenden ID_MENU_xyz_Items Strukturen!
//----------------------
paramEditItem_t const paramEditItemTable[] PROGMEM =
{
//-----------------------------------
// Menue: ID_MENU_KANAELE (Kanäle)
//-----------------------------------
{ param_Kanalbelegung_Gas , &editGeneric, GENERIC_Cannel , 0, 0, param_Kanalbelegung_Gas_de, param_Kanalbelegung_Gas_en },
{ param_Kanalbelegung_Gear , &editGeneric, GENERIC_Cannel , 0, 0, param_Kanalbelegung_Gear_de, param_Kanalbelegung_Gear_en },
{ param_Kanalbelegung_Nick , &editGeneric, GENERIC_Cannel , 0, 0, param_Kanalbelegung_Nick_de, param_Kanalbelegung_Nick_en },
{ param_Kanalbelegung_Roll , &editGeneric, GENERIC_Cannel , 0, 0, param_Kanalbelegung_Roll_de, param_Kanalbelegung_Roll_en },
{ param_Kanalbelegung_Poti1 , &editGeneric, GENERIC_AusChSerWpeMMM , 0, 0, param_Kanalbelegung_Poti1_de, param_Kanalbelegung_Poti1_en },
{ param_Kanalbelegung_Poti2 , &editGeneric, GENERIC_AusChSerWpeMMM , 0, 0, param_Kanalbelegung_Poti2_de, param_Kanalbelegung_Poti2_en },
{ param_Kanalbelegung_Poti3 , &editGeneric, GENERIC_AusChSerWpeMMM , 0, 0, param_Kanalbelegung_Poti3_de, param_Kanalbelegung_Poti3_en },
{ param_Kanalbelegung_Poti4 , &editGeneric, GENERIC_AusChSerWpeMMM , 0, 0, param_Kanalbelegung_Poti4_de, param_Kanalbelegung_Poti4_en },
{ param_Kanalbelegung_Poti5 , &editGeneric, GENERIC_AusChSerWpeMMM , 0, 0, param_Kanalbelegung_Poti5_de, param_Kanalbelegung_Poti5_en },
{ param_Kanalbelegung_Poti6 , &editGeneric, GENERIC_AusChSerWpeMMM , 0, 0, param_Kanalbelegung_Poti6_de, param_Kanalbelegung_Poti6_en },
{ param_Kanalbelegung_Poti7 , &editGeneric, GENERIC_AusChSerWpeMMM , 0, 0, param_Kanalbelegung_Poti7_de, param_Kanalbelegung_Poti7_en },
{ param_Kanalbelegung_Poti8 , &editGeneric, GENERIC_AusChSerWpeMMM , 0, 0, param_Kanalbelegung_Poti8_de, param_Kanalbelegung_Poti8_en },
{ param_MotorSafetySwitch , &editGeneric, GENERIC_DisChSerWpeOff , 0, 0, param_MotorSafetySwitch_de, param_MotorSafetySwitch_en },
{ param_GlobalConfig3_MotorSwitchMode , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig3_MotorSwitchMode_de, param_GlobalConfig3_MotorSwitchMode_en },
{ param_ExtraConfig_SensitiveRc , &editGeneric, GENERIC_NoYes , 0, 0, param_ExtraConfig_SensitiveRc_de, param_ExtraConfig_SensitiveRc_en },
{ param_GlobalConfig3_SpeakAll , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig3_SpeakAll_de, param_GlobalConfig3_SpeakAll_en },
 
 
//-----------------------------------
// Menue: ID_MENU_KONFIGURATION (Konfiguration)
//-----------------------------------
{ param_GlobalConfig_HoehenRegelung , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig_HoehenRegelung_de, param_GlobalConfig_HoehenRegelung_en },
{ param_GlobalConfig_GpsAktiv , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig_GpsAktiv_de, param_GlobalConfig_GpsAktiv_en },
{ param_GlobalConfig_KompassAktiv , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig_KompassAktiv_de, param_GlobalConfig_KompassAktiv_en },
{ param_GlobalConfig_KompassFix , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig_KompassFix_de, param_GlobalConfig_KompassFix_en },
// param_ExtraConfig_SensitiveRc
{ param_GlobalConfig_AchsenkopplungAktiv , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig_AchsenkopplungAktiv_de, param_GlobalConfig_AchsenkopplungAktiv_en },
{ param_GlobalConfig_DrehratenBegrenzer , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig_DrehratenBegrenzer_de, param_GlobalConfig_DrehratenBegrenzer_en },
{ param_GlobalConfig_HeadingHold , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig_HeadingHold_de, param_GlobalConfig_HeadingHold_en },
 
 
//-----------------------------------
// Menue: ID_MENU_STICK (Stick)
//-----------------------------------
{ param_Stick_P , &editGeneric, GENERIC_Value , 0, 20, param_Stick_P_de, param_Stick_P_en },
{ param_Stick_D , &editGeneric, GENERIC_Value , 0, 20, param_Stick_D_de, param_Stick_D_en },
{ param_StickGier_P , &editGeneric, GENERIC_ValuePoti , 0, 247, param_Gyro_Gier_P_de, param_Gyro_Gier_P_en },
{ param_ExternalControl , &editGeneric, GENERIC_ValuePoti , 0, 247, param_ExternalControl_de, param_ExternalControl_en },
 
 
//-----------------------------------
// Menue: ID_MENU_LOOPING (Looping)
//-----------------------------------
{ param_BitConfig_LoopOben , &editGeneric, GENERIC_NoYes , 0, 0, param_BitConfig_LoopOben_de, param_BitConfig_LoopOben_en },
{ param_BitConfig_LoopUnten , &editGeneric, GENERIC_NoYes , 0, 0, param_BitConfig_LoopUnten_de, param_BitConfig_LoopUnten_en },
{ param_BitConfig_LoopLinks , &editGeneric, GENERIC_NoYes , 0, 0, param_BitConfig_LoopLinks_de, param_BitConfig_LoopLinks_en },
{ param_BitConfig_LoopRechts , &editGeneric, GENERIC_NoYes , 0, 0, param_BitConfig_LoopRechts_de, param_BitConfig_LoopRechts_en },
{ param_LoopGasLimit , &editGeneric, GENERIC_ValuePoti , 0, 247, param_LoopGasLimit_de, param_LoopGasLimit_en },
{ param_LoopThreshold , &editGeneric, GENERIC_Value , 0, 247, param_LoopThreshold_de, param_LoopThreshold_en },
{ param_LoopHysterese , &editGeneric, GENERIC_Value , 0, 247, param_LoopHysterese_de, param_LoopHysterese_en },
{ param_WinkelUmschlagNick , &editGeneric, GENERIC_Value , 0, 247, param_WinkelUmschlagNick_de, param_WinkelUmschlagNick_en },
{ param_WinkelUmschlagRoll , &editGeneric, GENERIC_Value , 0, 247, param_WinkelUmschlagRoll_de, param_WinkelUmschlagRoll_en },
 
 
//-----------------------------------
// Menue: ID_MENU_HOEHE (Höhe)
//-----------------------------------
{ param_GlobalConfig_HoehenRegelung , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig_HoehenRegelung_de, param_GlobalConfig_HoehenRegelung_en},
{ param_ExtraConfig_HeightLimit , &editGeneric, GENERIC_NoYes , 0, 0, param_ExtraConfig_HeightLimit_de, param_ExtraConfig_HeightLimit_en },
{ param_ExtraConfig_HeightVario , &editGeneric, GENERIC_NoYes , 0, 0, param_ExtraConfig_HeightVario_de, param_ExtraConfig_HeightVario_en }, // negiertes param_ExtraConfig_HeightLimit
{ param_GlobalConfig_HoehenSchalter , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig_HoehenSchalter_de, param_GlobalConfig_HoehenSchalter_en},
{ param_ExtraConfig_VarioBeep , &editGeneric, GENERIC_NoYes , 0, 0, param_ExtraConfig_VarioBeep_de, param_ExtraConfig_VarioBeep_en },
{ param_HoeheChannel , &editGeneric, GENERIC_DisChSerWpeOffOn, 0, 0, param_HoeheChannel_de, param_HoeheChannel_en },
{ param_Hoehe_MinGas , &editGeneric, GENERIC_Value , 0, 247, param_Hoehe_MinGas_de, param_Hoehe_MinGas_en },
{ param_Hoehe_P , &editGeneric, GENERIC_ValuePoti , 0, 247, param_Hoehe_P_de, param_Hoehe_P_en },
{ param_Luftdruck_D , &editGeneric, GENERIC_ValuePoti , 0, 247, param_Luftdruck_D_de, param_Luftdruck_D_en },
{ param_Hoehe_ACC_Wirkung , &editGeneric, GENERIC_ValuePoti , 0, 247, param_Hoehe_ACC_Wirkung_de, param_Hoehe_ACC_Wirkung_en },
{ param_MaxAltitude , &editGeneric, GENERIC_ValuePoti , 0, 247, param_MaxAltitude_de, param_MaxAltitude_en },
{ param_Hoehe_Verstaerkung , &editGeneric, GENERIC_Value , 0, 247, param_Hoehe_Verstaerkung_de, param_Hoehe_Verstaerkung_en },
{ param_Hoehe_HoverBand , &editGeneric, GENERIC_Value , 0, 247, param_Hoehe_HoverBand_de, param_Hoehe_HoverBand_en },
{ param_Hoehe_GPS_Z , &editGeneric, GENERIC_ValuePoti , 0, 247, param_Hoehe_GPS_Z_de, param_Hoehe_GPS_Z_en },
{ param_Hoehe_TiltCompensation , &editGeneric, GENERIC_ValuePoti , 0, 247, param_Hoehe_Tilt_Comp_de, param_Hoehe_Tilt_Comp_en },
{ param_Hoehe_StickNeutralPoint , &editGeneric, GENERIC_Value , 0, 160, param_Hoehe_StickNeutralPoint_de, param_Hoehe_StickNeutralPoint_en },
{ param_StartLandChannel , &editGeneric, GENERIC_DisChSer , 0, 0, param_StartLandChannel_de, param_StartLandChannel_en },
{ param_LandingSpeed , &editGeneric, GENERIC_Value , 0, 247, param_LandingSpeed_de, param_LandingSpeed_en },
{ param_LandingPulse , &editACCZLandingPulse, GENERIC_ValueACCZ , 0, 0, param_LandingPulse_de, param_LandingPulse_en },
 
 
//-----------------------------------
// Menue: ID_MENU_KAMERA (Kamera)
//-----------------------------------
{ param_ServoNickControl , &editGeneric, GENERIC_ValuePoti , 0, 247, param_ServoNickControl_de, param_ServoNickControl_en },
{ param_ServoNickComp , &editGeneric, GENERIC_ValuePoti , 0, 247, param_ServoNickComp_de, param_ServoNickComp_en },
{ param_ServoNickFailsave , &editGeneric, GENERIC_Value , 0, 247, param_ServoNickFails_de, param_ServoNickFails_en },
{ param_GlobalConfig3_ServoNickCompOff , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig3_ServoNickCompOff_de, param_GlobalConfig3_ServoNickCompOff_en }, // TODO: pruefen: ab welcher Version ist das drin ???
{ param_ServoCompInvert_SERVO_NICK_INV , &editGeneric, GENERIC_NoYes , 0, 0, param_ServoCompInvert_SVNick_de, param_ServoCompInvert_SVNick_en },
{ param_ServoCompInvert_SERVO_RELATIVE , &editGeneric, GENERIC_NoYes , 0, 0, param_ServoCompInvert_SVRelMov_de, param_ServoCompInvert_SVRelMov_en },
{ param_ServoNickMin , &editGeneric, GENERIC_Value , 0, 247, param_ServoNickMin_de, param_ServoNickMin_en },
{ param_ServoNickMax , &editGeneric, GENERIC_Value , 0, 247, param_ServoNickMax_de, param_ServoNickMax_en },
{ param_ServoFilterNick , &editGeneric, GENERIC_Value , 0, 25, param_ServoFilterNick_de, param_ServoFilterNick_en },
{ param_ServoRollControl , &editGeneric, GENERIC_ValuePoti , 0, 247, param_ServoRollControl_de, param_ServoRollControl_en },
{ param_ServoRollComp , &editGeneric, GENERIC_ValuePoti , 0, 247, param_ServoRollComp_de, param_ServoRollComp_en },
{ param_ServoRollFailsave , &editGeneric, GENERIC_Value , 0, 247, param_ServoRollFails_de, param_ServoRollFails_en },
{ param_ServoCompInvert_SERVO_ROLL_INV , &editGeneric, GENERIC_NoYes , 0, 0, param_ServoCompInvert_SVRoll_de, param_ServoCompInvert_SVRoll_en },
{ param_ServoRollMin , &editGeneric, GENERIC_Value , 0, 247, param_ServoRollMin_de, param_ServoRollMin_en },
{ param_ServoRollMax , &editGeneric, GENERIC_Value , 0, 247, param_ServoRollMax_de, param_ServoRollMax_en },
{ param_ServoFilterRoll , &editGeneric, GENERIC_Value , 0, 25, param_ServoFilterRoll_de, param_ServoFilterRoll_en },
{ param_ServoNickRefresh , &editGeneric, GENERIC_Value , 2, 8, param_ServoNickRefresh_de, param_ServoNickRefresh_en },
{ param_ServoManualControlSpeed , &editGeneric, GENERIC_Value , 0, 247, param_ServoManualControlSpeed_de, param_ServoManualControlSpeed_en },
{ param_Servo3 , &editGeneric, GENERIC_ValueOutPoti , 0, 245, param_Servo3_de, param_Servo3_en },
{ param_Servo3Failsave , &editGeneric, GENERIC_Value , 0, 247, param_Servo3Fails_de, param_Servo3Fails_en },
{ param_Servo4 , &editGeneric, GENERIC_ValueOutPoti , 0, 245, param_Servo4_de, param_Servo4_en },
{ param_Servo4Failsave , &editGeneric, GENERIC_Value , 0, 247, param_Servo4Fails_de, param_Servo4Fails_en },
{ param_Servo5 , &editGeneric, GENERIC_ValuePoti , 0, 247, param_Servo5_de, param_Servo5_en },
{ param_Servo5Failsave , &editGeneric, GENERIC_Value , 0, 247, param_Servo5Fails_de, param_Servo5Fails_en },
 
{ param_Servo3OnValue , &editGeneric, GENERIC_Value , 0, 247, param_Servo3OnValue_de, param_Servo3OnValue_en },
{ param_Servo3OffValue , &editGeneric, GENERIC_Value , 0, 247, param_Servo3OffValue_de, param_Servo3OffValue_en },
{ param_Servo4OnValue , &editGeneric, GENERIC_Value , 0, 247, param_Servo4OnValue_de, param_Servo4OnValue_en },
{ param_Servo4OffValue , &editGeneric, GENERIC_Value , 0, 247, param_Servo4OffValue_de, param_Servo4OffValue_en },
//{ param_CamOrientation , &editNA , 0 , 0, 0, param_CamOrientation_de, param_CamOrientation_en }, // wird evtl. nicht mehr unterstuetzt
 
 
//-----------------------------------
// Menue: ID_MENU_NAVICTRL (NaviCtrl)
//-----------------------------------
{ param_GlobalConfig_GpsAktiv , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig_GpsAktiv_de, param_GlobalConfig_GpsAktiv_en },
{ param_NaviGpsModeChannel , &editGeneric, GENERIC_DisChSerWpeFreeCHPH , 0, 0, param_NaviGpsModeChannel_de, param_NaviGpsModeChannel_en },
{ param_NaviGpsGain , &editGeneric, GENERIC_ValuePoti , 0, 247, param_NaviGpsGain_de, param_NaviGpsGain_en },
{ param_NaviStickThreshold , &editGeneric, GENERIC_Value , 0, 247, param_NaviStickThreshold_de, param_NaviStickThreshold_en },
{ param_NaviGpsMinSat , &editGeneric, GENERIC_Value , 0, 247, param_NaviGpsMinSat_de, param_NaviGpsMinSat_en },
{ param_NaviGpsP , &editGeneric, GENERIC_ValuePoti , 0, 247, param_NaviGpsP_de, param_NaviGpsP_en },
{ param_NaviGpsI , &editGeneric, GENERIC_ValuePoti , 0, 247, param_NaviGpsI_de, param_NaviGpsI_en },
{ param_NaviGpsD , &editGeneric, GENERIC_ValuePoti , 0, 247, param_NaviGpsD_de, param_NaviGpsD_en },
{ param_NaviGpsPLimit , &editGeneric, GENERIC_ValuePoti , 0, 247, param_NaviGpsPLimit_de, param_NaviGpsPLimit_en },
{ param_NaviGpsILimit , &editGeneric, GENERIC_ValuePoti , 0, 247, param_NaviGpsILimit_de, param_NaviGpsILimit_en },
{ param_NaviGpsDLimit , &editGeneric, GENERIC_ValuePoti , 0, 247, param_NaviGpsDLimit_de, param_NaviGpsDLimit_en },
{ param_NaviGpsA , &editGeneric, GENERIC_ValuePoti , 0, 247, param_NaviGpsA_de, param_NaviGpsA_en },
{ param_NaviWindCorrection , &editGeneric, GENERIC_ValuePoti , 0, 247, param_NaviWindCorrection_de, param_NaviWindCorrection_en },
{ param_NaviAccCompensation , &editGeneric, GENERIC_ValuePoti , 0, 247, param_NaviAccCompensation_de, param_NaviAccCompensation_en },
{ param_NaviMaxFlyingRange , &editGeneric, GENERIC_Value , 0, 250, param_NaviMaxFlyingRange_de, param_NaviMaxFlyingRange_en },
{ param_NaviOperatingRadius , &editGeneric, GENERIC_ValuePoti , 0, 247, param_NaviOperatingRadius_de, param_NaviOperatingRadius_en },
{ param_NaviAngleLimitation , &editGeneric, GENERIC_ValuePoti , 0, 247, param_NaviAngleLimitation_de, param_NaviAngleLimitation_en },
{ param_NaviPH_LoginTime , &editGeneric, GENERIC_Value , 0, 247, param_NaviPH_LoginTime_de, param_NaviPH_LoginTime_en },
{ param_ExtraConfig_GpsAid , &editGeneric, GENERIC_NoYes , 0, 0, param_ExtraConfig_GpsAid_de, param_ExtraConfig_GpsAid_en },
{ param_GlobalConfig3_DphMaxRadius , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig3_DphMaxRadius_de, param_GlobalConfig3_DphMaxRadius_en },
{ param_ComingHomeAltitude , &editGeneric, GENERIC_Value , 0, 247, param_ComingHomeAltitude_de, param_ComingHomeAltitude_en },
{ param_ComingHomeOrientation , &editGeneric, GENERIC_CH_Orientation , 0, 3, param_ComingHomeOrientation_de, param_ComingHomeOrientation_en },
{ param_SingleWpControlChannel , &editGeneric, GENERIC_InaChSerWpeMMM , 0, 0, param_SingleWpControlChannel_de, param_SingleWpControlChannel_en }, //ab Rev.106
{ param_MenuKeyChannel , &editGeneric, GENERIC_InaChSerWpeMMM , 0, 0, param_MenuKeyChannel_de, param_MenuKeyChannel_en },
{ param_SingleWpSpeed , &editGeneric, GENERIC_ValuePoti , 0, 247, param_SingleWpSpeed_de, param_SingleWpSpeed_en }, // ab Rev. 100
{ param_NaviDescendRange , &editGeneric, GENERIC_Value , 0, 250, param_NaviDescendRange_de, param_NaviDescendRange_en },
 
 
//-----------------------------------
// Menue: ID_MENU_AUSGAENGE (Ausgänge)
//-----------------------------------
{ param_J16Bitmask , &editBitmask, 0 , 0, 0, param_J16Bitmask_de, param_J16Bitmask_en },
{ param_J16Timing , &editGeneric, GENERIC_ValuePoti , 0, 247, param_J16Timing_de, param_J16Timing_en },
{ param_BitConfig_MotorBlink1 , &editGeneric, GENERIC_NoYes , 0, 0, param_BitConfig_MotorBlink1_de, param_BitConfig_MotorBlink1_en }, // "nur nach Start der Motoren aktiv"
{ param_BitConfig_MotorOffLed1 , &editGeneric, GENERIC_NoYes , 0, 0, param_BitConfig_MotorOffLed1_de, param_BitConfig_MotorOffLed1_en }, // nur wenn "nur nach Start der Motoren aktiv" = JA ist -> bestimmt ob LED's an oder aus sind wenn die Motoren aus sind
{ param_GlobalConfig3_UseNcForOut1 , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig3_UseNcForOut1_de, param_GlobalConfig3_UseNcForOut1_en }, // "mit WP-Event verknüpfen"
{ param_NaviOut1Parameter , &editGeneric, GENERIC_ValuePoti , 0, 247, param_NaviOut1Parameter_de, param_NaviOut1Parameter_en }, // "AutoTrigger alle...[meter]" (bis Rev.98)
{ param_AutoPhotoDistance , &editGeneric, GENERIC_ValuePoti , 0, 247, param_AutoPhotoDistance_de, param_AutoPhotoDistance_en }, // "AutoTrigger alle [meter] in Distance" (ab Rev.100)
{ param_AutoPhotoAtitudes , &editGeneric, GENERIC_ValuePoti , 0, 247, param_AutoPhotoAtitudes_de, param_AutoPhotoAtitudes_en }, // "AutoTrigger alle [meter] in Altitude" (ab Rev.100)
 
{ param_J17Bitmask , &editBitmask, 0 , 0, 0, param_J17Bitmask_de, param_J17Bitmask_en },
{ param_J17Timing , &editGeneric, GENERIC_ValuePoti , 0, 247, param_J17Timing_de, param_J17Timing_en },
{ param_BitConfig_MotorBlink2 , &editGeneric, GENERIC_NoYes , 0, 0, param_BitConfig_MotorBlink2_de, param_BitConfig_MotorBlink2_en }, // "nur nach Start der Motoren aktiv"
{ param_BitConfig_MotorOffLed2 , &editGeneric, GENERIC_NoYes , 0, 0, param_BitConfig_MotorOffLed2_de, param_BitConfig_MotorOffLed2_en }, // nur wenn "nur nach Start der Motoren aktiv" = JA ist -> bestimmt ob LED's an oder aus sind wenn die Motoren aus sind
 
{ param_WARN_J16_Bitmask , &editBitmask, 0 , 0, 0, param_WARN_J16_Bitmask_de, param_WARN_J16_Bitmask_en }, // Bitmaske fuer Unterspannungswarnung
{ param_WARN_J17_Bitmask , &editBitmask, 0 , 0, 0, param_WARN_J17_Bitmask_de, param_WARN_J17_Bitmask_en }, // Bitmaske fuer Unterspannungswarnung
 
 
//-----------------------------------
// Menue: ID_MENU_VERSCHIEDENES (Verschiedenes)
//-----------------------------------
{ param_Gas_Min , &editGeneric, GENERIC_Value , 0, 247, param_Gas_Min_de, param_Gas_Min_en },
{ param_Gas_Max , &editGeneric, GENERIC_Value , 0, 247, param_Gas_Max_de, param_Gas_Max_en },
{ param_KompassWirkung , &editGeneric, GENERIC_ValuePoti , 0, 247, param_KompassWirkung_de, param_KompassWirkung_en },
//{ param_CompassOffset , &editGeneric, GENERIC_Value , 0, 255, param_CompassOffset_de, param_CompassOffset_en }, // TODO: +/- Werte sind dort kodiert
{ param_CompassOffset , &editCompassOffset, 0 , 0, 0, param_CompassOffset_de, param_CompassOffset_en }, // TODO: +/- Werte sind dort kodiert
{ param_CompassOffset_DisableDeclCalc , &editGeneric, GENERIC_NoYes , 0, 0, param_CompassOffset_DisableDeclCalc_de, param_CompassOffset_DisableDeclCalc_en }, // TODO: +/- Werte sind dort kodiert
{ param_CareFreeChannel , &editGeneric, GENERIC_DisChSerWpeOffOn , 0, 0, param_CareFreeChannel_de, param_CareFreeChannel_en },
{ param_ExtraConfig_LearnableCarefree , &editGeneric, GENERIC_NoYes , 0, 0, param_ExtraConfig_LearnableCarefree_de, param_ExtraConfig_LearnableCarefree_en },
 
{ param_UnterspannungsWarnung , &editGeneric, GENERIC_Value , 0, 247, param_UnterspannungsWarnung_de, param_UnterspannungsWarnung_en },
{ param_ComingHomeVoltage , &editGeneric, GENERIC_Value , 0, 247, param_ComingHomeVoltage_de, param_ComingHomeVoltage_en },
{ param_AutoLandingVoltage , &editGeneric, GENERIC_Value , 0, 247, param_AutoLandingVoltage_de, param_AutoLandingVoltage_en },
 
//{ param_ExtraConfig_33vReference , &editGeneric, GENERIC_NoYes , 0, 0, param_ExtraConfig_33vReference_de, param_ExtraConfig_33vReference_en }, // nicht mehr unterstuetzt!
{ param_NotGasZeit , &editGeneric, GENERIC_Value , 0, 247, param_NotGasZeit_de, param_NotGasZeit_en },
{ param_GlobalConfig3_VarioFailsafe , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig3_VarioFailsafe_de, param_GlobalConfig3_VarioFailsafe_en },
{ param_NotGas , &editGeneric, GENERIC_Value , 0, 247, param_NotGas_de, param_NotGas_en },
{ param_FailSafeTime , &editGeneric, GENERIC_Value , 0, 247, param_FailSafeTime_de, param_FailSafeTime_en },
{ param_FailsafeChannel , &editGeneric, GENERIC_Value , 0, 16, param_FailsafeChannel_de, param_FailsafeChannel_en },
 
{ param_ExtraConfig_NoRcOffBeeping , &editGeneric, GENERIC_NoYes , 0, 0, param_ExtraConfig_NoRcOffBeeping_de, param_ExtraConfig_NoRcOffBeeping_en },
{ param_ExtraConfig_IgnoreMagErrAtStartup , &editGeneric, GENERIC_NoYes , 0, 0, param_ExtraConfig_IgnoreMagErrAtStartup_de, param_ExtraConfig_IgnoreMagErrAtStartup_en },
{ param_GlobalConfig3_NoSdCardNoStart , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig3_NoSdCardNoStart_de, param_GlobalConfig3_NoSdCardNoStart_en },
{ param_GlobalConfig3_NoGpsFixNoStart , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig3_NoGpsFixNoStart_de, param_GlobalConfig3_NoGpsFixNoStart_en },
 
 
//-----------------------------------
// Menue: ID_MENU_GYRO (Gyro)
//-----------------------------------
{ param_Gyro_P , &editGeneric, GENERIC_ValuePoti , 0, 247, param_Gyro_P_de, param_Gyro_P_en },
{ param_Gyro_Gier_P , &editGeneric, GENERIC_ValuePoti , 0, 247, param_Gyro_Gier_P_de, param_Gyro_Gier_P_en },
{ param_Gyro_I , &editGeneric, GENERIC_ValuePoti , 0, 247, param_Gyro_I_de, param_Gyro_I_en },
{ param_Gyro_Gier_I , &editGeneric, GENERIC_ValuePoti , 0, 247, param_Gyro_Gier_I_de, param_Gyro_Gier_I_en },
{ param_Gyro_D , &editGeneric, GENERIC_ValuePoti , 0, 247, param_Gyro_D_de, param_Gyro_D_en },
 
{ param_DynamicStability , &editGeneric, GENERIC_ValuePoti , 0, 247, param_DynamicStability_de, param_DynamicStability_en },
{ param_GlobalConfig_DrehratenBegrenzer , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig_DrehratenBegrenzer_de, param_GlobalConfig_DrehratenBegrenzer_en },
 
{ param_GyroAccFaktor , &editGeneric, GENERIC_Value , 0, 247, param_GyroAccFaktor_de, param_GyroAccFaktor_en },
{ param_GyroAccAbgleich , &editGeneric, GENERIC_Value , 0, 247, param_GyroAccAbgleich_de, param_GyroAccAbgleich_en },
 
{ param_I_Faktor , &editGeneric, GENERIC_ValuePoti , 0, 247, param_I_Faktor_de, param_I_Faktor_en },
{ param_Driftkomp , &editGeneric, GENERIC_Value , 0, 247, param_Driftkomp_de, param_Driftkomp_en },
{ param_Gyro_Stability , &editGeneric, GENERIC_Value , 0, 247, param_Gyro_Stability_de, param_Gyro_Stability_en },
{ param_MotorSmooth , &editGeneric, GENERIC_Value , 0, 247, param_MotorSmooth_de, param_MotorSmooth_en },
 
 
//-----------------------------------
// Menue: ID_MENU_BENUTZER (Benutzer)
//-----------------------------------
{ param_UserParam1 , &editGeneric, GENERIC_ValuePoti , 0, 247, param_UserParam1_de, param_UserParam1_en },
{ param_UserParam2 , &editGeneric, GENERIC_ValuePoti , 0, 247, param_UserParam2_de, param_UserParam2_en },
{ param_UserParam3 , &editGeneric, GENERIC_ValuePoti , 0, 247, param_UserParam3_de, param_UserParam3_en },
{ param_UserParam4 , &editGeneric, GENERIC_ValuePoti , 0, 247, param_UserParam4_de, param_UserParam4_en },
{ param_UserParam5 , &editGeneric, GENERIC_ValuePoti , 0, 247, param_UserParam5_de, param_UserParam5_en },
{ param_UserParam6 , &editGeneric, GENERIC_ValuePoti , 0, 247, param_UserParam6_de, param_UserParam6_en },
{ param_UserParam7 , &editGeneric, GENERIC_ValuePoti , 0, 247, param_UserParam7_de, param_UserParam7_en },
{ param_UserParam8 , &editGeneric, GENERIC_ValuePoti , 0, 247, param_UserParam8_de, param_UserParam8_en },
 
 
//-----------------------------------
// Menue: ID_MENU_ACHSKOPPLUNG (Achskopplung)
//-----------------------------------
{ param_GlobalConfig_AchsenkopplungAktiv , &editGeneric, GENERIC_NoYes , 0, 0, param_GlobalConfig_AchsenkopplungAktiv_de, param_GlobalConfig_AchsenkopplungAktiv_en },
{ param_AchsKopplung1 , &editGeneric, GENERIC_ValuePoti , 0, 247, param_AchsKopplung1_de, param_AchsKopplung1_en },
{ param_AchsKopplung2 , &editGeneric, GENERIC_ValuePoti , 0, 247, param_AchsKopplung2_de, param_AchsKopplung2_en },
{ param_CouplingYawCorrection , &editGeneric, GENERIC_ValuePoti , 0, 247, param_CouplingYawCorrection_de, param_CouplingYawCorrection_en },
 
 
//-----------------------------------
// ENDE
//-----------------------------------
{ param_EOF, NOFUNC, 0,0,0, 0,0 } // END OF LIST - MUST BE THE LAST!!
};
 
 
/************************************************************
NICHT MEHR UNTERSTUEZT:
param_Receiver (Empfänger Typ: Hott, Jeti, Spektrum,...)
************************************************************/
 
 
 
 
 
//#############################################################################################
//# Menue's und Menuezuordnung
//#############################################################################################
 
//-----------------------------------
// Menue ID's: Parameters Hauptmenue
//-----------------------------------
#define ID_MENU_FAVORITEN 1 // fuer spaeter reserviert....
#define ID_MENU_KANAELE 2
#define ID_MENU_KONFIGURATION 3
#define ID_MENU_STICK 4
#define ID_MENU_LOOPING 5
#define ID_MENU_HOEHE 6
#define ID_MENU_KAMERA 7
#define ID_MENU_NAVICTRL 8
#define ID_MENU_AUSGAENGE 9
#define ID_MENU_VERSCHIEDENES 10
#define ID_MENU_GYRO 11
#define ID_MENU_BENUTZER 12
#define ID_MENU_ACHSKOPPLUNG 13
#define ID_MENU_MIXERSETUP 14 // nicht verwendet / unterstuetzt
#define ID_MENU_EASYSETUP 15
 
#define ID_MENU_TEST 66 // TEST / DEBUG
 
 
//-----------------------------------
// Zuordnungen von paramID's zu den jeweiligen Menue's
//
// Eintrag "SEPARATOR" - damit wird eine Trennlinie
// im Menue dargestellt
//-----------------------------------
 
//-------------------------------
// Menue: ID_MENU_KANAELE
//-------------------------------
unsigned char const ID_MENU_KANAELE_Items[] =
{
param_Kanalbelegung_Gas,
param_Kanalbelegung_Gear,
param_Kanalbelegung_Nick,
param_Kanalbelegung_Roll,
param_Kanalbelegung_Poti1,
param_Kanalbelegung_Poti2,
param_Kanalbelegung_Poti3,
param_Kanalbelegung_Poti4,
param_Kanalbelegung_Poti5,
param_Kanalbelegung_Poti6,
param_Kanalbelegung_Poti7,
param_Kanalbelegung_Poti8,
SEPARATOR,
param_MotorSafetySwitch,
param_GlobalConfig3_MotorSwitchMode,
SEPARATOR,
param_ExtraConfig_SensitiveRc,
param_GlobalConfig3_SpeakAll,
 
 
EOF // *** MUST BE THE LAST! ***
};
 
 
//-------------------------------
// Menue: ID_MENU_KONFIGURATION
//-------------------------------
unsigned char const ID_MENU_KONFIGURATION_Items[] =
{
param_GlobalConfig_HoehenRegelung,
param_GlobalConfig_GpsAktiv,
param_GlobalConfig_KompassAktiv,
param_GlobalConfig_KompassFix,
param_ExtraConfig_SensitiveRc,
param_GlobalConfig_AchsenkopplungAktiv,
param_GlobalConfig_DrehratenBegrenzer,
param_GlobalConfig_HeadingHold,
 
EOF // *** MUST BE THE LAST! ***
};
 
 
//-------------------------------
// Menue: ID_MENU_STICK
//-------------------------------
unsigned char const ID_MENU_STICK_Items[] =
{
param_Stick_P,
param_Stick_D,
param_StickGier_P,
SEPARATOR,
param_ExternalControl,
 
EOF // *** MUST BE THE LAST! ***
};
 
 
//-------------------------------
// Menue: ID_MENU_LOOPING
//-------------------------------
unsigned char const ID_MENU_LOOPING_Items[] =
{
param_BitConfig_LoopOben,
param_BitConfig_LoopUnten,
param_BitConfig_LoopLinks,
param_BitConfig_LoopRechts,
SEPARATOR,
param_LoopGasLimit,
param_LoopThreshold,
param_LoopHysterese,
param_WinkelUmschlagNick,
param_WinkelUmschlagRoll,
 
EOF // *** MUST BE THE LAST! ***
};
 
 
//-------------------------------
// Menue: ID_MENU_HOEHE
//-------------------------------
unsigned char const ID_MENU_HOEHE_Items[] =
{
param_GlobalConfig_HoehenRegelung,
param_ExtraConfig_HeightLimit,
param_ExtraConfig_HeightVario,
param_GlobalConfig_HoehenSchalter,
param_ExtraConfig_VarioBeep,
SEPARATOR,
param_HoeheChannel,
param_Hoehe_Verstaerkung,
param_Hoehe_MinGas,
param_Hoehe_HoverBand,
param_Hoehe_P,
param_Hoehe_GPS_Z,
param_Hoehe_TiltCompensation,
param_Luftdruck_D,
param_Hoehe_StickNeutralPoint,
param_Hoehe_ACC_Wirkung,
param_MaxAltitude,
SEPARATOR,
param_StartLandChannel,
param_LandingSpeed,
param_LandingPulse,
EOF // *** MUST BE THE LAST! ***
};
 
 
 
//-------------------------------
// Menue: ID_MENU_KAMERA
//-------------------------------
unsigned char const ID_MENU_KAMERA_Items[] =
{
param_ServoNickControl,
param_ServoNickComp,
param_ServoNickFailsave,
param_GlobalConfig3_ServoNickCompOff, // erst ab FC-Rev 96
param_ServoCompInvert_SERVO_NICK_INV,
param_ServoCompInvert_SERVO_RELATIVE,
param_ServoNickMin,
param_ServoNickMax,
param_ServoFilterNick,
SEPARATOR,
param_ServoRollControl,
param_ServoRollComp,
param_ServoRollFailsave,
param_ServoCompInvert_SERVO_ROLL_INV,
param_ServoRollMin,
param_ServoRollMax,
param_ServoFilterRoll,
SEPARATOR,
param_ServoNickRefresh,
param_ServoManualControlSpeed,
param_Servo3,
param_Servo3Failsave,
param_Servo4,
param_Servo4Failsave,
param_Servo5,
param_Servo5Failsave,
SEPARATOR,
param_Servo3OnValue,
param_Servo3OffValue,
param_Servo4OnValue,
param_Servo4OffValue,
 
EOF // *** MUST BE THE LAST! ***
};
 
 
 
//-------------------------------
// Menue: ID_MENU_NAVICTRL
//-------------------------------
unsigned char const ID_MENU_NAVICTRL_Items[] =
{
param_GlobalConfig_GpsAktiv,
param_NaviGpsModeChannel,
param_NaviGpsGain,
param_NaviStickThreshold,
param_NaviGpsMinSat,
param_NaviGpsP,
param_NaviGpsPLimit,
param_NaviGpsI,
param_NaviGpsILimit,
param_NaviGpsD,
param_NaviGpsDLimit,
param_NaviGpsA,
SEPARATOR,
param_NaviWindCorrection,
param_NaviAccCompensation,
param_NaviMaxFlyingRange,
param_NaviOperatingRadius,
param_NaviAngleLimitation,
param_NaviPH_LoginTime,
param_ExtraConfig_GpsAid,
param_GlobalConfig3_DphMaxRadius,
SEPARATOR,
param_ComingHomeAltitude,
param_ComingHomeOrientation,
SEPARATOR,
param_SingleWpControlChannel,
param_MenuKeyChannel,
param_SingleWpSpeed,
SEPARATOR,
param_NaviDescendRange,
 
EOF // *** MUST BE THE LAST! ***
};
 
 
//-------------------------------
// Menue: ID_MENU_AUSGAENGE
//-------------------------------
unsigned char const ID_MENU_AUSGAENGE_Items[] =
{
param_J16Bitmask, // LED 1 Bitmaske
param_J16Timing,
param_BitConfig_MotorBlink1,
param_BitConfig_MotorOffLed1,
param_GlobalConfig3_UseNcForOut1,
param_NaviOut1Parameter,
param_AutoPhotoDistance,
param_AutoPhotoAtitudes,
SEPARATOR,
param_J17Bitmask, // LED 2 Bitmaske
param_J17Timing,
param_BitConfig_MotorBlink2,
param_BitConfig_MotorOffLed2,
SEPARATOR,
param_WARN_J16_Bitmask,
param_WARN_J17_Bitmask,
 
EOF // *** MUST BE THE LAST! ***
};
 
 
//-------------------------------
// Menue: ID_MENU_VERSCHIEDENES
//-------------------------------
unsigned char const ID_MENU_VERSCHIEDENES_Items[] =
{
param_Gas_Min,
param_Gas_Max,
param_KompassWirkung,
param_CompassOffset,
param_CompassOffset_DisableDeclCalc,
param_CareFreeChannel,
param_ExtraConfig_LearnableCarefree,
SEPARATOR,
param_UnterspannungsWarnung,
param_ComingHomeVoltage,
param_AutoLandingVoltage,
SEPARATOR,
param_NotGasZeit,
param_GlobalConfig3_VarioFailsafe, // Nutze "Vario-Höhe" für "Not-Gas" -> beeinflusst 'param_NotGas' bzgl. "%"
param_NotGas,
param_FailSafeTime,
param_FailsafeChannel,
param_ExtraConfig_NoRcOffBeeping,
SEPARATOR,
param_ExtraConfig_IgnoreMagErrAtStartup,
param_GlobalConfig3_NoSdCardNoStart,
param_GlobalConfig3_NoGpsFixNoStart,
 
EOF // *** MUST BE THE LAST! ***
};
 
 
//-------------------------------
// Menue: ID_MENU_GYRO
//-------------------------------
unsigned char const ID_MENU_GYRO_Items[] =
{
param_Gyro_P,
param_Gyro_I,
param_Gyro_D,
param_Gyro_Gier_P,
param_Gyro_Gier_I,
SEPARATOR,
param_DynamicStability,
param_GlobalConfig_DrehratenBegrenzer,
SEPARATOR,
param_GyroAccFaktor,
param_GyroAccAbgleich,
SEPARATOR,
param_I_Faktor,
param_Driftkomp,
param_Gyro_Stability,
param_MotorSmooth,
 
EOF // *** MUST BE THE LAST! ***
};
 
 
//-------------------------------
// Menue: ID_MENU_BENUTZER
//-------------------------------
unsigned char const ID_MENU_BENUTZER_Items[] =
{
param_UserParam1,
param_UserParam2,
param_UserParam3,
param_UserParam4,
param_UserParam5,
param_UserParam6,
param_UserParam7,
param_UserParam8,
 
EOF // *** MUST BE THE LAST! ***
};
 
 
//-------------------------------
// Menue: ID_MENU_ACHSKOPPLUNG
//-------------------------------
unsigned char const ID_MENU_ACHSKOPPLUNG_Items[] =
{
param_GlobalConfig_AchsenkopplungAktiv,
param_AchsKopplung1,
param_AchsKopplung2,
param_CouplingYawCorrection,
 
EOF // *** MUST BE THE LAST! ***
};
 
 
//-------------------------------
// Menue: ID_MENU_EASYSETUP
//-------------------------------
unsigned char const ID_MENU_EASYSETUP_Items[] =
{
param_GlobalConfig_HoehenRegelung,
param_HoeheChannel,
param_Hoehe_StickNeutralPoint,
param_StartLandChannel,
SEPARATOR,
param_GlobalConfig_GpsAktiv,
param_NaviGpsModeChannel,
param_ExtraConfig_GpsAid,
param_ComingHomeAltitude,
SEPARATOR,
param_CareFreeChannel,
param_ExtraConfig_LearnableCarefree,
 
EOF // *** MUST BE THE LAST! ***
};
 
 
 
 
//#############################################################################################
//# Error-Handling
//#############################################################################################
//# mittels des auf dem PKT angezeigten Errocodes (z.B. "E32") kann man hier schauen was bzw.
//# wo (in welcher Funktion) der Fehler aufgetreten ist.
//#
//# Im Menue wird der Fehlercode rechts bei den Values dargestellt (dabei ertönen immer wieder
//# Fehler-Beep's).
//# In der Vollbildanzeige wird zusaetzlich ein uebergebener Wert (value) angezeigt - im Code
//# kann man ermitteln was der Wert darstellt.
//#############################################################################################
 
#define E01_PARAMID_MENUEDITCATEGORY 1 // Menu_EditCategory() - FEHLER: paramEditItem (=paramID) nicht in Tabelle paramEditItemTable gefunden
 
#define E11_PARAMID_EDITGENERIC 11 // editGeneric() - FEHLER: paramEditItem (=paramID) nicht in Tabelle paramEditItemTable gefunden
#define E12_PARAMID_EDITBITMASK 12 // editBitmask() - FEHLER: paramEditItem (=paramID) nicht in Tabelle paramEditItemTable gefunden
 
#define E30_CODECHAR_NOT_FOUND 30 // find_genericCode() - FEHLER: Code-Zeichen nicht in Tabelle editGenericCode gefunden
#define E31_PARAMEDIT_ITEM_NOT_FOUND 31 // find_genericCodeByValue() - FEHLER: paramEditItem (=paramID) nicht in Tabelle paramEditItemTable gefunden
#define E32_CODECHAR_NOT_FOUND 32 // find_genericCodeByValue() - FEHLER: Code-Zeichen nicht in Tabelle editGenericCode gefunden
#define E33_VALUE_NOT_IN_FORMAT 33 // find_genericCodeByValue() - FEHLER: Ende des Format-Strings erreicht - fuer das gegebene value konnte kein passender Code im Format-String gefunden werden
 
#define E41_VALUE_MIN_MAX_RANGE 41 // strValueGeneric() - FEHLER: fuer die Range von 'v' (Value) wurde max < min angegeben bei Generic -> nicht unterstuetzt
 
 
 
 
//--------------------------------------------------------------
// _error( errorcode, value, showscreen)
//
// zeigt Fehlermeldungen an
//
// PARAMETER:
// errorcode : siehe Error-defines
// value : zusaetzlicher Anzeigeparameter (nur in Screen-Anzeige)
// showscreen: true = Fehlermeldung wird vollstaendig angezeigt.
// - er Screen wird dabei geloescht
// - Ende mit Taste 'Ende'
// - langer Fehler-Beep
//
// false = es wird nur der Buffer mkparam_strValueBuffer
// mit dem Fehlercode befuellt
// - Anzeige im Menue ganz recht als "Enn"
// - kurzer Fehler-Beep der jedoch bei jeder
// Aktion im Menue zu hoeren ist
// => dann auf Anzeige "Enn" achten!
//--------------------------------------------------------------
void _error( uint8_t errorcode, uint8_t value, uint8_t showscreen)
{
xsnprintf_P( mkparam_strValueBuffer, MKPARAM_STRBUFFER_LEN, PSTR("E%02u"), errorcode); // in mkparam_strValueBuffer ausgeben fuer das Menue
 
if( showscreen )
{
lcd_cls();
 
lcdx_printp_center( 1, PSTR(" ERROR "), MINVERS, 0,-3);
lcdx_printp_center( 2, PSTR("mkparameters.c"), MNORMAL, 0,0);
 
lcd_printf_at_P( 0, 4, MNORMAL, PSTR("Code : E%02u"), errorcode );
lcd_printf_at_P( 0, 5, MNORMAL, PSTR("Value: %3u"), value );
 
lcd_printp_at(11, 7, strGet(ENDE), MNORMAL );
 
set_beep( 500, 0x000f, BeepNormal); // Beep Error
 
while( !get_key_press(1 << KEY_ESC) )
{
//--------------------------------
// Anmerkung: OG 25.03.2014
//
// Ohne diese Verzoegerung funkioniert die Update-Erkennung via PKT-UpdateTool
// meist nicht - ist das PKT zu schnell?
// Kann man evtl. das PKT-UpdateTool diesbezueglich mal ueberpruefen ob man
// Timings/Timeout's anpassen kann?
//
// Hinweis dazu: PKT_CtrlHook() bzw. die dort enthaltene Update-Anforderungspruefung
// ist in den letzten Wochen beschleunigt geworden da unnoetiger Code fuer nicht
// benoetigte Bildschirmausgaben entfernt wurde - das ist grundsaetzlich fuer das PKT
// besser.
//
// Um das nachzustellen:
// Unten das Delay auskommentieren und einen Fehler in Menu_EditCategory() provozieren
// indem "paramID = 0;" einkommentiert wird (ist dort beschrieben)
// Dann den Fehlerscreen im PKT anzeigen lassen und ein Update via PKT-UpdateTool initiieren,
//--------------------------------
_delay_ms(150);
 
PKT_CtrlHook();
}
}
else
{
// kurzer Fehler-Beep - der kann wiederholt im Menue auftreten bei jedem Refresh des Menues
set_beep( 160, 0x000f, BeepNormal); // Beep Error
}
}
 
 
 
 
//#############################################################################################
//# Edit-Funktionen
//#############################################################################################
 
 
//--------------------------------------------------------------
// ok = find_paramEditItem( paramID )
//
// sucht in paramEditItemTable (PROGMEM) eine paramID und
// kopiert den Eintrag in das RAM
//
// PARAMETER:
// paramID
//
// RUECKGABE:
// true = paramID gefunden
// false = nicht gefunden (Fehler)
//
// -- globale Modulvariablen --
// Ergebnisse in:
//
// paramEditItem : der gefundene Eintrag vom Typ paramEditItem_t (im RAM)
// paramEditFormat: der Format-String paramEditItem.format im RAM
//--------------------------------------------------------------
unsigned char find_paramEditItem( unsigned char paramID )
{
unsigned char id;
unsigned char *p;
 
p = (unsigned char *) paramEditItemTable;
 
while( true )
{
id = pgm_read_byte(p); // die aktuelle paramID aus paramEditDef
 
if( id == paramID || id == param_EOF )
break;
 
p += sizeof( paramEditItem_t );
}
 
//-----
// wenn die gesuchte paramID nicht gefunden wurde steht
// im RAM-Buffer paramEdit.paramID == param_EOF !!
//-----
memcpy_P ( &paramEditItem , p, sizeof(paramEditItem_t) ); // die Struktur -> in den RAM-Buffer kopieren (Zugriff: paramEditItem)
strncpy_P( paramEditFormat, paramEditItem.format, MKPARAM_STRBUFFER_LEN); // format String -> in den RAM-Buffer kopieren (Zugriff: paramEditFormat)
 
return( id!=param_EOF );
}
 
 
 
//--------------------------------------------------------------
// ptrP = paramEditItemTitle()
//
// gibt einen Zeiger in PROGMEM auf den Titel/Bezeichnung eines
// paramID's in der richtigen Sprache zurueck
//
// ACHTUNG! paramEditItem muss vorher initialisert worden sein!
//--------------------------------------------------------------
/*
const char * paramEditItemTitle( void )
{
if( Config.DisplayLanguage == 0 )
return( paramEditItem.title_de );
else
return( paramEditItem.title_en );
}
*/
 
 
 
//--------------------------------------------------------------
// print_paramEditItemTitle()
//
// gibt Titel/Bezeichnung auf den Bildschirm bei x=0, y=2 aus
//
// ACHTUNG! paramEditItem muss vorher initialisert worden sein!
//--------------------------------------------------------------
void print_paramEditItemTitle( void )
{
lcd_printp_at( 0, 2, (Config.DisplayLanguage == 0 ? paramEditItem.title_de : paramEditItem.title_en ), MNORMAL); // Bezeichnung des paramID's
}
 
 
 
//--------------------------------------------------------------
// ok = find_genericCode( code )
//
// Ergebnis steht in: (globale Modulvariablen)
// genericCode
//--------------------------------------------------------------
unsigned char find_genericCode( unsigned char code )
{
unsigned char codeIdx;
 
codeIdx = 0;
while( (editGenericCode[codeIdx].code != code ) && (editGenericCode[codeIdx].code != EOF) )
codeIdx++;
 
//-----------------------------
// find_genericCode() - FEHLER: Code-Zeichen nicht in Tabelle editGenericCode gefunden
//-----------------------------
if( editGenericCode[codeIdx].code == EOF )
{
_error( E30_CODECHAR_NOT_FOUND, code, false);
return false;
}
 
memcpy( &genericCode, &editGenericCode[codeIdx], sizeof(editGenericCode_t) ); // die gefundene Struktur in den RAM-Buffer kopieren
 
return true;
}
 
 
 
//--------------------------------------------------------------
// ok = find_genericCode( paramID, &v, &min, &max, pFormat)
//
// PARAMETER:
// paramID
// *v
// *min
// *max
// *pFormat
//
// Ergebnis steht in: (globale Modulvariablen)
// paramEditItem
// paramEditFormat: der zugehoerige Format-String
// genericCode
//--------------------------------------------------------------
unsigned char find_genericCodeByValue( unsigned char paramID, unsigned char *v, unsigned char *min, unsigned char *max )
{
unsigned char codeIdx;
char *pFormat;
 
 
//-------------------------------------------------
// 1. finde paramID in der paramEditItem-Tabelle
//
// sollte der RAM-Buffer paramEditItem bereits das
// gesuchte enthalten dann ok
//-------------------------------------------------
if( paramEditItem.paramID != paramID )
find_paramEditItem( paramID );
 
//---
// FEHLER: paramEditItem nicht in Tabelle paramEditItemTable gefunden
//---
if( paramEditItem.paramID == param_EOF )
{
_error( E31_PARAMEDIT_ITEM_NOT_FOUND, paramID, false);
return false;
}
 
pFormat = paramEditFormat; // Zeiger auf das erste Zeichen vom Format-String (z.B. "DCSWFHQ")
*v = paramGet( paramID ); // der aktuelle Wert des paraID
 
while( true )
{
//------
// suche editGenericCode mittels aktuelles Zeichens *pFormat
//------
codeIdx = 0;
while( (editGenericCode[codeIdx].code != *pFormat) && (editGenericCode[codeIdx].code != EOF) )
codeIdx++;
 
 
//------
// FEHLER: Code-Zeichen nicht in Tabelle editGenericCode gefunden
//------
if( editGenericCode[codeIdx].code == EOF )
{
_error( E32_CODECHAR_NOT_FOUND, *pFormat, false);
return false;
}
 
 
//------
// suche den Value-Bereich (min/max) fuer das Code-Zeichen
//------
if( editGenericCode[codeIdx].code == 'v' )
{
// bei code 'v' kommt min/max aus paramEditItem
*min = paramEditItem.min;
*max = paramEditItem.max;
}
else
{
// ansonsten kommt min/max aus dem Code selber
*min = editGenericCode[codeIdx].min;
*max = editGenericCode[codeIdx].max;
}
 
// value gefunden (innerhalb von min/max)?
// beruecksichtigt 'gedrehte' min/max (z.B. Poti1..8)
if( (*min <= *max && *v >= *min && *v <= *max) || (*min > *max && *v >= *max && *v <= *min) )
{
// gefunden - Schleife verlassen
break;
}
 
 
//------
// naechstes Code-Zeichen aus der Format-Maske
//------
pFormat++;
 
 
//------
// FEHLER: Ende des Format-Strings erreicht - fuer das gegebene value konnte kein passender Code im Format-String gefunden werden
//------
if( *pFormat == 0 ) // Ende des Format-Strings erreicht - Fehler...
{
_error( E33_VALUE_NOT_IN_FORMAT, *v, false);
return false;
}
}
 
memcpy( &genericCode, &editGenericCode[codeIdx], sizeof(editGenericCode_t) ); // die gefundene Struktur in den RAM-Buffer kopieren
 
genericCode.min = *min; // ggf. min/max ueberschreiben durch min/max von paramEditItem
genericCode.max = *max;
 
return true;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
const char * get_genericCodeText( uint8_t cmd )
{
if( cmd == MKPARAM_LONGVALUE )
{
if( Config.DisplayLanguage == 0 ) return genericCode.longText_de;
else return genericCode.longText_en;
}
else
{
if( Config.DisplayLanguage == 0 ) return genericCode.shortText_de;
else return genericCode.shortText_en;
}
return 0;
}
 
 
 
//--------------------------------------------------------------
// ok = strValueGeneric( paramID, cmd )
//
// erstellt die String Representation des Wertes von paramID
// im Buffer mkparam_strValueBuffer.
//
// Mit 'cmd' wird gesteuert ob es der Lang-Text oder der
// Kurztext (3 Zeichen) ist.
//
// PARAMETER:
// paramID:
// cmd: MKPARAM_SHORTVALUE oder MKPARAM_LONGVALUE
//--------------------------------------------------------------
uint8_t strValueGeneric( unsigned char paramID, uint8_t cmd )
{
unsigned char v;
unsigned char min;
unsigned char max;
 
if( find_genericCodeByValue( paramID, &v, &min, &max) )
{
//-------------------
// value gefunden!
//-------------------
if( genericCode.code == 'v' ) // Code 'v' (Value) - keine Umrechnung von min/max
{
if( max < min )
{
// max < min bei 'v' (Value) wird aktuell nicht unterstuezt da
// kein Beispiel vorhanden ist was damit ggf. gemeint ist.
// Wenn das irgendwann benoetigt wird muss das hier gecoded werden.
// Bis dahin wird das als Fehler angesehen (ggf. vertippt beim coden).
_error( E41_VALUE_MIN_MAX_RANGE, v, false);
return false;
}
}
else // alles andere ausser 'v' - der Wert wird in die Range von min/max umgerechnet
{
if( min <= max )
v = v-min;
else
v = min-v; // OG Notiz: v = 248 = 8 # 248 = 8, 255 = 1 # min 255 max = 248
v++; // fuer Anzeige +1: statt '0' eine '1' anzeigen - Beispiel: statt "Poti0" zeige "Poti1"
}
 
 
//-------------------
// ertstelle String
//-------------------
xsnprintf_P( mkparam_strValueBuffer, MKPARAM_STRBUFFER_LEN, get_genericCodeText(cmd), v); // erzeuge den Ausgabestring in mkparam_strValueBuffer
 
return true;
}
 
return false;
}
 
 
 
 
//--------------------------------------------------------------
// ok = getGenericNextValue( paramID, vInc )
//
// PARAMETER:
//--------------------------------------------------------------
uint8_t getGenericNextValue( unsigned char paramID, int8_t vInc )
{
int v; // value von paramID - signed int: damit -1 und >255 ausgewertet werden kann
unsigned char value; // zum holen von v via find_genericCodeByValue()
unsigned char min;
unsigned char max;
unsigned char codeIdx;
char *pFormat;
 
 
if( find_genericCodeByValue( paramID, &value, &min, &max) )
{
v = (int)value; // value vom paramID wird gecastet auf int um -1 und >255 fuer edit zu erkennen
 
//------------------------------------------------------
// Pointer auf das Zeichen im Format-String ermitteln
//------------------------------------------------------
pFormat = paramEditFormat;
while( *pFormat != genericCode.code ) pFormat++;
 
 
if( min > max ) // 'umgedrehte' min/max Werte wie bei Poti1..8
vInc = vInc * -1;
 
 
v = v + vInc;
 
 
//------------------------------------------------------
// min/max Grenzen des Code-Zeichens ueberschritten?
//------------------------------------------------------
if( (min <= max && v < min) || (min > max && v > min) )
{
if( pFormat == paramEditFormat ) // Anfang vom Code-String? -> dann gehe zum Ende (letztes Zeichen)
{
while( *(pFormat+1) ) pFormat++;
}
else
{
pFormat--; // vorheriges Format-Zeichen = vorheriger Code
}
 
 
codeIdx = 0; // code-Zeichen suchen in Tabelle editGenericCode
while( (editGenericCode[codeIdx].code != *pFormat) && (editGenericCode[codeIdx].code != EOF) )
codeIdx++;
 
if( editGenericCode[codeIdx].code == EOF ) // Fehler? -> exit
{
return false;
}
 
if( editGenericCode[codeIdx].code == 'v' )
v = paramEditItem.max;
else
v = editGenericCode[codeIdx].max;
 
}
else if( (min <= max && v > max) || (min > max && v < max) )
{
pFormat++; // naechstes Format-Zeichen = naechster Code
if( *pFormat == 0 ) // Ende des Format-Strings?
pFormat = paramEditFormat;
 
codeIdx = 0; // code-Zeichen suchen in Tabelle editGenericCode
while( (editGenericCode[codeIdx].code != *pFormat) && (editGenericCode[codeIdx].code != EOF) )
codeIdx++;
 
if( editGenericCode[codeIdx].code == EOF ) // Fehler? -> exit
{
return false;
}
 
if( editGenericCode[codeIdx].code == 'v' )
v = paramEditItem.min;
else
v = editGenericCode[codeIdx].min;
}
 
 
//------------------------------------------------------
// neuen Wert setzen
//------------------------------------------------------
paramSet( paramID, (unsigned char)v );
 
return true;
 
} // end: if( find_genericCode( paramID, &v, &min, &max) )
 
 
return false;
}
 
 
 
//--------------------------------------------------------------
// editGeneric( paramID, cmd )
//
// PARAMETER:
// cmd: MKPARAM_EDIT oder MKPARAM_SHORTVALUE oder MKPARAM_LONGVALUE
//--------------------------------------------------------------
void editGeneric( unsigned char paramID, uint8_t cmd )
{
unsigned char v_org;
uint8_t redraw;
int8_t vInc;
 
if( cmd != MKPARAM_EDIT )
{
// wenn cmd = MKPARAM_SHORTVALUE oder MKPARAM_LONGVALUE
strValueGeneric( paramID, cmd); // Ergebnis in: mkparam_strValueBuffer
return;
}
 
find_paramEditItem( paramID );
 
//------------------------
// editGeneric() - FEHLER: paramEditItem (=paramID) nicht in Tabelle paramEditItemTable gefunden
//------------------------
if( paramEditItem.paramID == param_EOF )
{
_error( E11_PARAMID_EDITGENERIC, paramID, true);
return;
}
 
lcd_cls();
 
v_org = paramGet( paramID );
redraw = SCREEN_REDRAW;
vInc = 0; // 0, +1, -1 (inc/dec)
 
while( true )
{
//-----------------------
// Anzeige: Titel, usw..
//-----------------------
if( redraw == SCREEN_REDRAW )
{
lcd_frect( 0, 0, 127, 7, 1); // Headline: Box fill
lcdx_printp_at( 1, 0, PSTR("Ändern"), MINVERS, 0,0); // Titel
lcd_printp_at( 0, 7, strGet(KEYLINE2), MNORMAL); // Keyline: <- -> Ende OK
lcd_printp_at(11, 7, strGet(KEYCANCEL), MNORMAL); // Keyline: "Abbr." statt "Ende" einsetzen
 
print_paramEditItemTitle(); // Bezeichnung des paramID's anzeigen
 
redraw = SCREEN_REFRESH;
}
 
 
//---------------
// LiPo Anzeigen
//---------------
show_Lipo(); // LiPo anzeigen
 
 
//-----------------------
// Anzeige: nur Wert
//-----------------------
if( redraw == SCREEN_REFRESH )
{
strValueGeneric( paramID, MKPARAM_LONGVALUE); // Lang-Text des Values anzeigen
// nach strValueGeneric() ist auch genericCode initialisiert!
lcd_printf_at_P( 0, 4, MNORMAL, PSTR("> %18s"), mkparam_strValueBuffer );
 
 
// DEBUG...
#ifdef DEBUG_PARAMEDIT
//lcd_printf_at_P( 16, 1, MNORMAL, PSTR("%c %3u"), genericCode.code, paramGet(paramID) );
#endif
 
//lcd_printf_at_P( 16, 4, MNORMAL, PSTR("= %03u"), v );
 
 
if( abs(genericCode.max-genericCode.min) <= 20 )
_delay_ms( 200 ); // Verzoegerung
 
vInc = 0;
redraw = 0;
}
 
 
//-----------------
// TASTEN
//-----------------
if( get_key_press(1 << KEY_ESC) ) // Key: Cancel
{
paramSet( paramID, v_org ); // org. Wert wieder herstellen
break;
}
 
if( get_key_press(1 << KEY_ENTER) ) // Key: OK
{
break;
}
 
if( get_key_press(1 << KEY_PLUS) || get_key_long_rpt_sp( (1 << KEY_PLUS),2) ) // Key: rechts / +1
{
vInc = +1;
}
 
 
if( get_key_press(1 << KEY_MINUS) || get_key_long_rpt_sp( (1 << KEY_MINUS),2) ) // Key: links / -1
{
vInc = -1;
}
 
if( vInc != 0 )
{
getGenericNextValue( paramID, vInc );
redraw = SCREEN_REFRESH;
}
 
 
//------------------------------------------
// Pruefe PKT-Update oder andere PKT-Aktion
//------------------------------------------
if( PKT_CtrlHook() ) // Update vom Updatetool angefordert?
{
lcd_cls();
redraw = SCREEN_REDRAW;
}
 
} // end: while( true )
 
}
 
 
 
//--------------------------------------------------------------
// editBitmask( paramID, cmd )
//
// PARAMETER:
// paramID: die paramID
// cmd: MKPARAM_EDIT oder MKPARAM_SHORTVALUE oder MKPARAM_LONGVALUE
//--------------------------------------------------------------
void editBitmask( unsigned char paramID, uint8_t cmd )
{
unsigned char v;
uint8_t redraw;
uint8_t i;
int8_t pos;
 
find_paramEditItem( paramID );
 
//-----------------------
// editBitmask() - FEHLER: paramEditItem (=paramID) nicht in Tabelle paramEditItemTable gefunden
//-----------------------
if( paramEditItem.paramID == param_EOF )
{
_error( E12_PARAMID_EDITBITMASK, paramID, (cmd==MKPARAM_EDIT) );
return;
}
 
 
//-----------------------
// nur Rueckgabe des Wertes in mkparam_strValueBuffer ?
//-----------------------
if( cmd != MKPARAM_EDIT )
{
v = paramGet( paramID );
xsnprintf_P( mkparam_strValueBuffer, MKPARAM_STRBUFFER_LEN, PSTR("%03u"), v); // erzeuge den Ausgabestring in mkparam_strValueBuffer
return;
}
 
 
lcd_cls();
 
v = paramGet( paramID );
redraw = SCREEN_REDRAW;
pos = 0;
 
while( true )
{
//-----------------------
// Anzeige: Titel, usw..
//-----------------------
if( redraw == SCREEN_REDRAW )
{
lcd_frect( 0, 0, 127, 7, 1); // Headline: Box fill
lcdx_printp_at( 1, 0, PSTR("Ändern"), MINVERS, 0,0); // Titel
lcd_printp_at( 1, 7, PSTR("0/1 \x19 OK"), MNORMAL); // Keyline: -> 0/1 OK
lcd_printp_at( 11, 7, strGet(KEYCANCEL), MNORMAL); // Keyline: "Abbr." bzw "Cancel"
lcdx_printp_at( 7, 6, PSTR("\x18"), MNORMAL, -2,2); // Keyline langer Tastendruck: -> 0/1 OK
 
if( (paramID == param_J16Bitmask) || (paramID == param_J17Bitmask) )
{
lcdx_printp_at( 10, 5, PSTR("(Bit1=Idle)"), MNORMAL, 0,2); //
}
 
print_paramEditItemTitle(); // Bezeichnung des paramID's (Stelle x=0, y=2)
 
redraw = SCREEN_REFRESH;
}
 
 
//---------------
// LiPo Anzeigen
//---------------
show_Lipo(); // LiPo anzeigen
 
 
//-----------------------
// Anzeige: nur Wert
//-----------------------
if( redraw == SCREEN_REFRESH )
{
for(i = 0; i < 8; i++)
{
lcd_putc( 8-i, 4, ( (v & (1 << i)) ? '1' : '0'), MNORMAL);
}
 
lcd_frect( 0, (8*5), 125-(11*6), 7, 0); // clear: Eingabemarkierung
lcd_printp_at (pos+1, 5,PSTR("\x12"), MNORMAL); // Eingabemarkierung (Pfeil nach oben)
 
lcd_printf_at_P( 15, 4, MNORMAL, PSTR("= %03u"), v ); // Anzeige des aktuellen Wertes Dezimal
 
// _delay_ms( 200 ); // Verzoegerung
redraw = 0;
}
 
 
//-----------------
// TASTEN
//-----------------
if( get_key_short(1 << KEY_ESC) ) // Key: Cancel
{
break; // verlassen
}
 
if (get_key_short(1 << KEY_ENTER)) // Key: OK
{
paramSet( paramID, v ); // Wert speichern
break; // und verlassen
}
 
if( get_key_short(1 << KEY_PLUS) )
{
if(pos == 7) pos = 0;
else pos++;
redraw = SCREEN_REFRESH;
}
 
if( get_key_long(1 << KEY_PLUS) )
{
if(pos == 0) pos = 7;
else pos--;
redraw = SCREEN_REFRESH;
}
 
 
if( get_key_short (1 << KEY_MINUS) )
{
v ^= (1<<(7-pos));
redraw = SCREEN_REFRESH;
}
 
 
//------------------------------------------
// evtl. weitere lange Tasten abfangen, da es
// ansonsten ggf. Nebeneffekte bzgl. dem Menue
// beim verlassen der Funktion gibt
//------------------------------------------
get_key_long_rpt_sp( KEY_ALL,2);
 
 
//------------------------------------------
// Pruefe PKT-Update oder andere PKT-Aktion
//------------------------------------------
if( PKT_CtrlHook() ) // Update vom Updatetool angefordert?
{
lcd_cls();
redraw = SCREEN_REDRAW;
}
 
} // end: while( true )
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void editCompassOffset( unsigned char paramID, uint8_t cmd )
{
unsigned char vu; // unsigned byte
int v; // signed
uint8_t redraw;
uint8_t bit7;
uint8_t bit8;
uint8_t lDisDeclCalc;
 
find_paramEditItem( paramID );
 
//-----------------------
// editCompassOffset() - FEHLER: paramEditItem (=paramID) nicht in Tabelle paramEditItemTable gefunden
//-----------------------
if( paramEditItem.paramID == param_EOF )
{
// TODO: Fehlercode anpassen!
_error( E12_PARAMID_EDITBITMASK, paramID, (cmd==MKPARAM_EDIT) );
return;
}
 
 
//-----------------------
// Wert ermitteln (-60 bis 60)
//-----------------------
vu = paramGet( paramID );
 
bit7 = ((vu & 0x40) ? true : false); // Bit 7: 1 = negativ; 0 = positiv
bit8 = ((vu & 0x80) ? true : false); // Bit 8 in Kombination mit Bit 7 = "Disable dec. Calc"
 
// Bit 8 == Bit 7: "Disable dec. Calc" AUS
// Bit 8 != Bit 7: "Disable dec. Calc" AN
lDisDeclCalc = ((bit8 == bit7) ? 0 : 1); // merken um das spaeter wieder in den Wert einzubauen
 
vu = (vu & (0x80 ^ 0xff)); // Bit 8 loeschen
 
if( bit7 ) // Wert negativ?
{
vu = vu - 1; // Umrechnung: 7-Bit Zweierkomplement
vu = (vu ^ 0xff); // invertieren
vu = (vu & (0x80 ^ 0xff)); // Bit 8 loeschen
v = (int)vu;
v = v * -1;
}
else // Wert ist positiv
{
v = (int)vu;
}
 
 
//-----------------------
// nur Rueckgabe des Wertes in mkparam_strValueBuffer ?
//-----------------------
if( cmd != MKPARAM_EDIT )
{
xsnprintf_P( mkparam_strValueBuffer, MKPARAM_STRBUFFER_LEN, PSTR("%3d"), v ); // erzeuge den Ausgabestring in mkparam_strValueBuffer
return;
}
 
 
//-----------------------
// Wert Editieren
//-----------------------
lcd_cls();
 
redraw = SCREEN_REDRAW;
 
while( true )
{
//-----------------------
// Anzeige: Titel, usw..
//-----------------------
if( redraw == SCREEN_REDRAW )
{
lcd_frect( 0, 0, 127, 7, 1); // Headline: Box fill
lcdx_printp_at( 1, 0, PSTR("Ändern") , MINVERS, 0,0); // Titel
lcd_printp_at( 0, 7, strGet(KEYLINE2) , MNORMAL); // Keyline: <- -> Ende OK
lcd_printp_at( 11, 7, strGet(KEYCANCEL), MNORMAL); // Keyline: "Abbr." statt "Ende" einsetzen
 
print_paramEditItemTitle(); // Bezeichnung des paramID's anzeigen
 
redraw = SCREEN_REFRESH;
}
 
 
//---------------
// LiPo Anzeigen
//---------------
show_Lipo(); // LiPo anzeigen
 
 
//-----------------------
// Anzeige: Wert
//-----------------------
if( redraw == SCREEN_REFRESH )
{
lcd_printf_at_P( 0, 4, MNORMAL, PSTR("> %3d"), v );
redraw = false;
}
 
 
//-----------------
// TASTEN
//-----------------
if( get_key_short(1 << KEY_ESC) ) // Key: Cancel
{
break; // verlassen
}
 
if( get_key_short(1 << KEY_ENTER) ) // Key: OK
{
//-------------------------------------
// signed int in unsigned byte wandeln
//-------------------------------------
if( v < 0 ) // Wert negativ?
{
// Umwandeln in 7-Bit Zweierkomplement
v = v * -1; // Wert positiv machen
vu = (unsigned char)v; // in unsigned Byte speichern
vu = (vu ^ 0xff); // invertieren
vu = vu + 1; // +1
}
else // Wert ist positiv
{
vu = (unsigned char)v; // in unsigned Byte speichern
}
 
//-------------------------------------
// "Disable declination calc" wieder einrechnen
//-------------------------------------
bit7 = ((vu & 0x40) ? true : false); // Bit 7: 1 = negativ; 0 = positiv
 
if( lDisDeclCalc ) bit8 = !bit7; // Bit 8 != Bit 7: "Disable dec. Calc" AN
else bit8 = bit7; // Bit 8 == Bit 7: "Disable dec. Calc" AUS
 
if( bit8 ) vu = (vu | 0x80); // Bit 8 setzen
else vu = (vu & (0x80 ^ 0xff)); // Bit 8 loeschen
 
//-------------------------------------
// Wert speichern
//-------------------------------------
paramSet( paramID, vu ); // Wert speichern
break; // und verlassen
} // end: KEY_ENTER
 
 
if( get_key_short(1 << KEY_MINUS) || get_key_long_rpt_sp( (1 << KEY_MINUS),2) )
{
if( v <= -60 ) v = 60;
else v = v - 1;
redraw = SCREEN_REFRESH;
}
 
 
if( get_key_short(1 << KEY_PLUS) || get_key_long_rpt_sp( (1 << KEY_PLUS),2) )
{
if( v >= 60 ) v = -60;
else v = v + 1;
redraw = SCREEN_REFRESH;
}
 
//------------------------------------------
// evtl. weitere lange Tasten abfangen, da es
// ansonsten ggf. Nebeneffekte bzgl. dem Menue
// beim verlassen der Funktion gibt
//------------------------------------------
get_key_long_rpt_sp( KEY_ALL,2);
 
 
//------------------------------------------
// Pruefe PKT-Update oder andere PKT-Aktion
//------------------------------------------
if( PKT_CtrlHook() ) // Update vom Updatetool angefordert?
{
lcd_cls();
redraw = SCREEN_REDRAW;
}
 
} // end: while( true )
}
 
//--------------------------------------------------------------
void editACCZLandingPulse( unsigned char paramID, uint8_t cmd )
{
unsigned char vu; // unsigned byte
// int v; // signed
uint8_t redraw;
// uint8_t bit7;
// uint8_t bit8;
// uint8_t lDisDeclCalc;
 
find_paramEditItem( paramID );
 
//-----------------------
// editACCZLandingPulse() - FEHLER: paramEditItem (=paramID) nicht in Tabelle paramEditItemTable gefunden
//-----------------------
if( paramEditItem.paramID == param_EOF )
{
// TODO: Fehlercode anpassen!
_error( E12_PARAMID_EDITBITMASK, paramID, (cmd==MKPARAM_EDIT) );
return;
}
 
vu = paramGet( paramID );
 
//-----------------------
// nur Rueckgabe des Wertes in mkparam_strValueBuffer ?
//-----------------------
if( cmd != MKPARAM_EDIT )
{
xsnprintf_P( mkparam_strValueBuffer, MKPARAM_STRBUFFER_LEN, PSTR("%4d"), vu*4 ); // erzeuge den Ausgabestring in mkparam_strValueBuffer
return;
}
 
 
//-----------------------
// Wert Editieren
//-----------------------
lcd_cls();
 
redraw = SCREEN_REDRAW;
 
while( true )
{
//-----------------------
// Anzeige: Titel, usw..
//-----------------------
if( redraw == SCREEN_REDRAW )
{
lcd_frect( 0, 0, 127, 7, 1); // Headline: Box fill
lcdx_printp_at( 1, 0, PSTR("Ändern") , MINVERS, 0,0); // Titel
lcd_printp_at( 0, 7, strGet(KEYLINE2) , MNORMAL); // Keyline: <- -> Ende OK
lcd_printp_at( 11, 7, strGet(KEYCANCEL), MNORMAL); // Keyline: "Abbr." statt "Ende" einsetzen
 
print_paramEditItemTitle(); // Bezeichnung des paramID's anzeigen
 
redraw = SCREEN_REFRESH;
}
 
 
//---------------
// LiPo Anzeigen
//---------------
show_Lipo(); // LiPo anzeigen
 
 
//-----------------------
// Anzeige: Wert
//-----------------------
if( redraw == SCREEN_REFRESH )
{
lcd_printf_at_P( 0, 4, MNORMAL, PSTR("> %4d"), vu *4 );
redraw = false;
}
 
 
//-----------------
// TASTEN
//-----------------
if( get_key_short(1 << KEY_ESC) ) // Key: Cancel
{
break; // verlassen
}
 
if( get_key_short(1 << KEY_ENTER) ) // Key: OK
{
// //-------------------------------------
// // signed int in unsigned byte wandeln
// //-------------------------------------
// if( v < 0 ) // Wert negativ?
// {
// // Umwandeln in 7-Bit Zweierkomplement
// v = v * -1; // Wert positiv machen
// vu = (unsigned char)v; // in unsigned Byte speichern
// vu = (vu ^ 0xff); // invertieren
// vu = vu + 1; // +1
// }
// else // Wert ist positiv
// {
// vu = (unsigned char)v; // in unsigned Byte speichern
// }
//
// //-------------------------------------
// // "Disable declination calc" wieder einrechnen
// //-------------------------------------
// bit7 = ((vu & 0x40) ? true : false); // Bit 7: 1 = negativ; 0 = positiv
//
// if( lDisDeclCalc ) bit8 = !bit7; // Bit 8 != Bit 7: "Disable dec. Calc" AN
// else bit8 = bit7; // Bit 8 == Bit 7: "Disable dec. Calc" AUS
//
// if( bit8 ) vu = (vu | 0x80); // Bit 8 setzen
// else vu = (vu & (0x80 ^ 0xff)); // Bit 8 loeschen
 
//-------------------------------------
// Wert speichern
//-------------------------------------
paramSet( paramID, vu ); // Wert speichern
break; // und verlassen
} // end: KEY_ENTER
 
 
if( get_key_short(1 << KEY_MINUS) || get_key_long_rpt_sp( (1 << KEY_MINUS),2) )
{
// if( v <= -60 ) v = 60;
// else v = v - 1;
//
if( vu < 191 ) vu = 190;
else vu = vu -1;
 
redraw = SCREEN_REFRESH;
}
 
 
if( get_key_short(1 << KEY_PLUS) || get_key_long_rpt_sp( (1 << KEY_PLUS),2) )
{
// if( v >= 60 ) v = -60;
// else v = v + 1;
if( vu >= 255 ) vu = 255;
// if( vu == 1 ) vu = 191;
else vu = vu +1;
redraw = SCREEN_REFRESH;
}
 
//------------------------------------------
// evtl. weitere lange Tasten abfangen, da es
// ansonsten ggf. Nebeneffekte bzgl. dem Menue
// beim verlassen der Funktion gibt
//------------------------------------------
get_key_long_rpt_sp( KEY_ALL,2);
 
 
//------------------------------------------
// Pruefe PKT-Update oder andere PKT-Aktion
//------------------------------------------
if( PKT_CtrlHook() ) // Update vom Updatetool angefordert?
{
lcd_cls();
redraw = SCREEN_REDRAW;
}
 
} // end: while( true )
}
 
//--------------------------------------------------------------
 
 
//--------------------------------------------------------------
// editNA( paramID, cmd )
//
// Hilfsfunktion die nur "nicht verfügbar" anzeigt wenn die
// paramID noch nicht implementiert ist
//
// PARAMETER:
// paramID: die paramID
// cmd: MKPARAM_EDIT oder MKPARAM_SHORTVALUE oder MKPARAM_LONGVALUE
//--------------------------------------------------------------
void editNA( unsigned char paramID, uint8_t cmd )
{
if( cmd != MKPARAM_EDIT )
{
strncpy_P( mkparam_strValueBuffer, PSTR("NA!"), MKPARAM_STRBUFFER_LEN); // "NA!" bzw, "not available"
return;
}
 
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( PSTR("nicht verfügbar"), false, 2000, true, true ); // "nicht verfügbar"
}
 
 
 
 
//#############################################################################################
//# TEST / DEBUG
//#############################################################################################
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void editGenericTEST( unsigned char paramID )
{
lcd_cls();
 
//lcdx_printp_at( 0, 0, PSTR("NEW PARAM TEST..."), MNORMAL, 0,0);
lcd_printp_at(12, 7, strGet(ENDE), MNORMAL); // Keyline
 
find_paramEditItem( paramID ); // Ergebnis in paramEditItem (RAM)
 
if( paramEditItem.paramID == paramID )
{
lcd_printf_at_P( 0, 1, MNORMAL, PSTR("%S"), paramEditItem.title_de );
 
lcd_printf_at_P( 0, 2, MNORMAL, PSTR("format: %s"), paramEditFormat );
 
lcd_printf_at_P( 0, 3, MNORMAL, PSTR("value:%u"), paramGet(paramID) );
 
strValueGeneric( paramID, MKPARAM_LONGVALUE);
lcd_printf_at_P( 0, 4, MNORMAL, PSTR("vstr: %s"), mkparam_strValueBuffer );
 
strValueGeneric( paramID, MKPARAM_SHORTVALUE);
lcd_printf_at_P( 0, 5, MNORMAL, PSTR("vstr: %s"), mkparam_strValueBuffer );
}
 
 
if( paramEditItem.paramID == param_EOF )
{
lcd_printf_at_P( 0, 5, MNORMAL, PSTR("! ERROR !") );
}
 
 
//-----------------------------------------
// Tasten...
while( true )
{
PKT_CtrlHook();
if (get_key_press (1 << KEY_ESC))
{
break;
}
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void TEST(void)
{
//editGeneric( param_Gyro_Gier_P, MKPARAM_EDIT );
editGeneric( param_Kanalbelegung_Gas, MKPARAM_EDIT );
}
 
 
 
 
//#############################################################################################
//# Menues & Favoriten
//#############################################################################################
 
 
//--------------------------------------------------------------
// fav_add()
//
// einen Favoriten hinzufuegen
//
// Aufruf durch: wird durch den Menu-Controller aufgerufen
//--------------------------------------------------------------
void fav_add( void )
{
uint8_t paramID;
uint8_t i;
 
 
//------------------------------
// welche paramID wurde gewaehlt?
//------------------------------
paramID = MenuCtrl_GetItemId(); // gewaehlter Menuepunkt bzw. paramID (0 = keine itemID)
 
 
//------------------------------
// ungueltige paramID?
//------------------------------
if( paramID==0 || paramID==EOF )
{
return; // keine gueltige paramID gewaehlt -> ZURUECK
}
 
 
//------------------------------
// Duplikatsuche bzgl. paramID
// (gilt nicht fuer SEPARATOR)
//------------------------------
if( paramID!=SEPARATOR )
{
//------------------------------
// suche Duplikate fuer paramID
//------------------------------
for( i=0; (i<MAX_MKPARAM_FAVORITES) && (Config.MKParam_Favs[i]!=paramID); i++);
 
//------------------------------
// Favoriten bereits vorhanden?
// -> exit
//------------------------------
if( Config.MKParam_Favs[i] == paramID )
{
set_beep( 300, 0x000f, BeepNormal); // Error Beep kurz
PKT_Popup_P( 400, strGet(STR_FAV_EXIST),0,0,0); // "* Fav vorhanden *" (ca. 4 sec max.)
return;
}
} // end: if( paramID!=SEPARATOR )
 
 
//------------------------------
// suche freien Speicherplatz fuer paramID
//------------------------------
for( i=0; (i<MAX_MKPARAM_FAVORITES) && (Config.MKParam_Favs[i]!=0); i++);
 
//------------------------------
// Favoriten voll?
// -> exit
//------------------------------
if( i >= MAX_MKPARAM_FAVORITES )
{
set_beep( 500, 0x000f, BeepNormal); // Error Beep lang
PKT_Popup_P( 400, strGet(STR_FAV_FULL),0,0,0); // "* Fav ist voll *" (ca. 4 sec max.)
return;
}
 
//------------------------------
// neuen Fav merken
//------------------------------
Config.MKParam_Favs[i] = paramID;
set_beep( 25, 0xffff, BeepNormal ); // kurzer Bestaetigungs-Beep
PKT_Popup_P( 400, strGet(STR_FAV_ADD),0,0,0); // "Fav hinzugefügt!" (ca. 4 sec max.)
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Menu_Favoriten( void )
{
uint8_t paramID;
uint8_t i;
 
//unsigned char MKParam_Favs[MAX_MKPARAM_FAVORITES]; // Array von MK-Parameter Favoriten des Benutzers
 
if( Config.MKParam_Favs[0] == 0 ) // Favoriten vorhanden
{
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( strGet(STR_FAV_NOTEXIST), false, 500, true, true ); // Anzeige "nicht verfügbar" (max. 2 Sekunden anzeigen)
return;
}
 
 
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // uebernimmt den Titel vom uebergeordneten Menuepunkt
MenuCtrl_ShowLevel( false );
MenuCtrl_SetDelete( true ); // Menueeintraege loeschen (langer Druck auf "OK")
MenuCtrl_SetMove( true ); // Menueeintraege verschieben (langer Druck auf hoch/runter)
//MenuCtrl_SetShowBatt( true );
//MenuCtrl_SetCycle( false );
//MenuCtrl_SetBeep( true );
 
 
//---------------
// Menu-Items
//---------------
i = 0;
while( (i<MAX_MKPARAM_FAVORITES) && (Config.MKParam_Favs[i]!=0) )
{
paramID = Config.MKParam_Favs[i];
 
if( paramID == SEPARATOR )
{
MenuCtrl_PushSeparatorID( SEPARATOR ); // Trennlinie im Menue hinzufuegen
}
else
{
find_paramEditItem( paramID );
 
//--------
// FEHLER: paramEditItem (=paramID) nicht in Tabelle paramEditItemTable gefunden - Menu_EditCategory()
//--------
if( paramEditItem.paramID == param_EOF )
{
_error( E01_PARAMID_MENUEDITCATEGORY, paramID, true);
MenuCtrl_Destroy();
return;
}
 
MenuCtrl_PushParamEdit( paramID );
 
// existiert die paramID in der Firmware des Kopters?
if( !paramExist(paramID) )
{
MenuCtrl_ItemActive( paramID, false ); // paramID deaktivieren
}
 
// DEBUG! (Simulation eines deaktivierten Fav's)
// if( i==2 ) MenuCtrl_ItemActive( paramID, false ); // paramID deaktivieren
 
} // end: else: if( paramID == SEPARATOR )
 
i++;
} // end: while(..)
 
 
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
if( MenuCtrl_GetKey() == KEY_ESC ) break; // KEY_ESC = Menue beenden
 
paramID = MenuCtrl_GetItemId(); // welcher Menu-Punkt (= paramID)
 
find_paramEditItem( paramID ); // Edit-Definitionen heraussuchen (initialisiert: paramEditItem)
 
paramEditItem.editfunc( paramID, MKPARAM_EDIT ); // zugeordnete Edit-Funktion aufrufen
}
 
 
//---------------
// ggf. neue Menuereihenfolge
// in der Config speichern
//---------------
for( i=0; (i<MAX_MKPARAM_FAVORITES); i++)
{
Config.MKParam_Favs[i] = MenuCtrl_GetItemIdByIndex( i );
}
 
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Menu_EditCategory( const unsigned char *menuitems )
{
unsigned char paramID;
unsigned char lastmenuitem = 0;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
 
//---------------
// Einstellungen
//---------------
MenuCtrl_SetTitleFromParentItem(); // uebernimmt den Titel vom uebergeordneten Menuepunkt
MenuCtrl_ShowLevel( false );
//MenuCtrl_SetShowBatt( true );
//MenuCtrl_SetCycle( false );
//MenuCtrl_SetBeep( true );
 
//MenuCtrl_SetKey( uint8_t key, const char *keytext, void (*keyfunc)(void) )
MenuCtrl_SetKey( KEY_ENTER_LONG, 0, &fav_add );
 
 
//---------------
// Menuitems
//---------------
while( *menuitems != EOF )
{
paramID = *menuitems;
 
if( paramID == SEPARATOR )
{
// wenn der vorherige Menueeintrag bereits ein SEPARATOR war
// dann nicht erneut einen Separator anzeigen!
//
// Das kann ggf. passieren wenn z.B. aufgrund der FC-Revision
// alle Zwischeneintraege ausgeblendet wurden
if( lastmenuitem != SEPARATOR )
{
MenuCtrl_PushSeparatorID( SEPARATOR ); // Trennlinie im Menue hinzufuegen
lastmenuitem = paramID;
}
}
else
{
//------------------------------------------------------
// TEST / DEBUG fuer beschriebenes Problem in _error()
//
// Wenn man das dortige Problem nachstellen will kann
// man hier einen Fehlerscreen provozieren!
//------------------------------------------------------
//paramID = 0;
 
 
find_paramEditItem( paramID );
 
//--------
// FEHLER: paramEditItem (=paramID) nicht in Tabelle paramEditItemTable gefunden - Menu_EditCategory()
//--------
if( paramEditItem.paramID == param_EOF )
{
_error( E01_PARAMID_MENUEDITCATEGORY, paramID, true);
MenuCtrl_Destroy();
return;
}
 
// existiert die paramID in der Firmware des Kopters?
if( paramExist(paramEditItem.paramID) )
{
MenuCtrl_PushParamEdit( paramEditItem.paramID );
lastmenuitem = paramID;
}
}
 
menuitems++;
}
 
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
if( MenuCtrl_GetKey() == KEY_ESC ) break; // Menue beenden
 
paramID = MenuCtrl_GetItemId(); // welcher Menu-Punkt (= paramID)
 
find_paramEditItem( paramID ); // Edit-Definitionen heraussuchen (initialisiert: paramEditItem)
 
paramEditItem.editfunc( paramID, MKPARAM_EDIT ); // zugeordnete Edit-Funktion aufrufen
}
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void MK_Parameters_MenuMain( uint8_t setting, char *settingname )
{
uint8_t itemid;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
 
//---------------
// Einstellungen
//---------------
MenuCtrl_SetTitle( settingname );
MenuCtrl_ShowLevel( false );
//MenuCtrl_SetShowBatt( true );
//MenuCtrl_SetCycle( false );
//MenuCtrl_SetBeep( true );
 
//---------------
// Menuitems
//---------------
//MenuCtrl_PushML2_P( ID_MENU_TEST , MENU_ITEM, &TEST, ID_MENU_TEST_de , ID_MENU_TEST_en );
 
MenuCtrl_PushML2_P( ID_MENU_FAVORITEN , MENU_ITEM, NOFUNC, ID_MENU_FAVORITEN_de , ID_MENU_FAVORITEN_en ); // Favoriten: noch nicht implementiert...
 
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
 
MenuCtrl_PushML2_P( ID_MENU_KANAELE , MENU_ITEM, NOFUNC, ID_MENU_KANAELE_de , ID_MENU_KANAELE_en );
MenuCtrl_PushML2_P( ID_MENU_KONFIGURATION, MENU_ITEM, NOFUNC, ID_MENU_KONFIGURATION_de, ID_MENU_KONFIGURATION_en );
MenuCtrl_PushML2_P( ID_MENU_STICK , MENU_ITEM, NOFUNC, ID_MENU_STICK_de , ID_MENU_STICK_en );
MenuCtrl_PushML2_P( ID_MENU_LOOPING , MENU_ITEM, NOFUNC, ID_MENU_LOOPING_de , ID_MENU_LOOPING_en );
MenuCtrl_PushML2_P( ID_MENU_HOEHE , MENU_ITEM, NOFUNC, ID_MENU_HOEHE_de , ID_MENU_HOEHE_en );
MenuCtrl_PushML2_P( ID_MENU_KAMERA , MENU_ITEM, NOFUNC, ID_MENU_KAMERA_de , ID_MENU_KAMERA_en );
MenuCtrl_PushML2_P( ID_MENU_NAVICTRL , MENU_ITEM, NOFUNC, ID_MENU_NAVICTRL_de , ID_MENU_NAVICTRL_en );
MenuCtrl_PushML2_P( ID_MENU_AUSGAENGE , MENU_ITEM, NOFUNC, ID_MENU_AUSGAENGE_de , ID_MENU_AUSGAENGE_en );
MenuCtrl_PushML2_P( ID_MENU_VERSCHIEDENES, MENU_ITEM, NOFUNC, ID_MENU_VERSCHIEDENES_de, ID_MENU_VERSCHIEDENES_en );
MenuCtrl_PushML2_P( ID_MENU_GYRO , MENU_ITEM, NOFUNC, ID_MENU_GYRO_de , ID_MENU_GYRO_en );
MenuCtrl_PushML2_P( ID_MENU_BENUTZER , MENU_ITEM, NOFUNC, ID_MENU_BENUTZER_de , ID_MENU_BENUTZER_en );
MenuCtrl_PushML2_P( ID_MENU_ACHSKOPPLUNG , MENU_ITEM, NOFUNC, ID_MENU_ACHSKOPPLUNG_de , ID_MENU_ACHSKOPPLUNG_en );
//MenuCtrl_PushML2_P( ID_MENU_MIXERSETUP , MENU_ITEM, NOFUNC, ID_MENU_MIXERSETUP_de , ID_MENU_MIXERSETUP_en ); // nicht mehr unterstuetzt!
MenuCtrl_PushML2_P( ID_MENU_EASYSETUP , MENU_ITEM, NOFUNC, ID_MENU_EASYSETUP_de , ID_MENU_EASYSETUP_en );
 
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
if( MenuCtrl_GetKey() == KEY_ESC ) break;
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
switch( itemid )
{
case ID_MENU_FAVORITEN: Menu_Favoriten(); break;
 
case ID_MENU_KANAELE: Menu_EditCategory( ID_MENU_KANAELE_Items ); break;
case ID_MENU_KONFIGURATION: Menu_EditCategory( ID_MENU_KONFIGURATION_Items ); break;
case ID_MENU_STICK: Menu_EditCategory( ID_MENU_STICK_Items ); break;
case ID_MENU_LOOPING: Menu_EditCategory( ID_MENU_LOOPING_Items ); break;
case ID_MENU_HOEHE: Menu_EditCategory( ID_MENU_HOEHE_Items ); break;
case ID_MENU_KAMERA: Menu_EditCategory( ID_MENU_KAMERA_Items ); break;
case ID_MENU_NAVICTRL: Menu_EditCategory( ID_MENU_NAVICTRL_Items ); break;
case ID_MENU_AUSGAENGE: Menu_EditCategory( ID_MENU_AUSGAENGE_Items ); break;
case ID_MENU_VERSCHIEDENES: Menu_EditCategory( ID_MENU_VERSCHIEDENES_Items ); break;
case ID_MENU_GYRO: Menu_EditCategory( ID_MENU_GYRO_Items ); break;
case ID_MENU_BENUTZER: Menu_EditCategory( ID_MENU_BENUTZER_Items ); break;
case ID_MENU_ACHSKOPPLUNG: Menu_EditCategory( ID_MENU_ACHSKOPPLUNG_Items ); break;
case ID_MENU_EASYSETUP: Menu_EditCategory( ID_MENU_EASYSETUP_Items ); break;
 
default: //PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( PSTR("nicht verfügbar"), false, 200, true, true ); // Anzeige "nicht verfügbar" (max. 2 Sekunden anzeigen)
break;
}
}
 
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
 
 
 
//#############################################################################################
//# MK_Parameters() - Main-Function
//#############################################################################################
 
//--------------------------------------------------------------
// changed = MK_Parameters( setting, settingname )
//--------------------------------------------------------------
uint8_t MK_Parameters( uint8_t setting, char *settingname )
{
int changed;
unsigned char *org_parameters;
uint8_t size = paramsetSize();
 
//-----------------------------------------------------------------
// Erkennung ob Aenderungen durch den Benutzer vorgenommen wurde
// -> das aktuelle Paramset wird gespeichert um es spaeter mit
// der bearbeiteten Version via memcmp zu vergleichen
//-----------------------------------------------------------------
org_parameters = malloc( size+1 ); // +1 fuer das erste settings-byte
 
if( !org_parameters )
{
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( PSTR("NO RAM!"), true, 800, true, true ); // FEHLER! (NO RAM)
return false;
}
memcpy( org_parameters, (unsigned char *)(pRxData), size+1 ); // memcpy( dst, src, size))
 
 
//-----------------------------------------------------------------
// MK-Parameter bearbeiten
//-----------------------------------------------------------------
MK_Parameters_MenuMain( setting, settingname );
 
 
//-----------------------------------------------------------------
// Vergleich: Orginal-Daten <-> ggf. geaenderte Daten
//-----------------------------------------------------------------
changed = memcmp( org_parameters, (unsigned char *)(pRxData), size+1 );
 
free( org_parameters );
 
return( changed!=0 );
}
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mksettings/mkparameters.h
0,0 → 1,95
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2012 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2012 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY mkparameters.h
//#
//# 27.03.2014 OG
//# etliche neue Funktionen / Strukturen
//#
//# 23.02.2014 OG
//# - chg: MK_Parameters_Menu() umbenannt zu MK_Parameters()
//#
//# 12.02.2014 OG - NEU
//############################################################################
 
#ifndef _MKPARAMETERS_H
#define _MKPARAMETERS_H
 
 
// fuer cmd-Parameter der Edit-Funktionen
#define MKPARAM_EDIT 1 // Wert bearbeiten
#define MKPARAM_SHORTVALUE 2 // erzeugt einen 3-Zeichen String der den Wert darstellt (z.B. "Dis"); Ergebnis in strValueBuffer
#define MKPARAM_LONGVALUE 3 // erzeugt einen String der den Wert in langer Form darstellt (z.B. "Disabled"); Ergebnis in strValueBuffer
 
 
#define MKPARAM_STRBUFFER_LEN 20
 
 
//--------------------------------------------
// paramEditItem_t
// deklariert die Edit-Daten einer paramID
//--------------------------------------------
typedef struct
{
unsigned char paramID; // paramID aus paramset.h
void (*editfunc)(unsigned char paramID, uint8_t cmd); // Edit-Funktion (z.B. editGeneric()); cmd = CMD_EDIT oder CMD_SHORTVALUE
const char *format; // Parameter: String (PROGMEM) (vorallem fuer editGeneric() )
unsigned char min; // Parameter: min (P1)
unsigned char max; // Parameter: max (P2)
const char *title_de; // Text in PROGMEM - Menuetext und Beschreibung im Edit-Screen
const char *title_en; // Text in PROGMEM
} paramEditItem_t;
 
 
 
extern paramEditItem_t paramEditItem; // RAM Buffer: fuer ein Element von paramEditDef
extern char paramEditFormat[MKPARAM_STRBUFFER_LEN]; // RAM Buffer: fuer 'str' von paramEdit (Format; editGeneric)
extern char mkparam_strValueBuffer[MKPARAM_STRBUFFER_LEN]; // Anzeige eines Values als Klartext; Kurz (fuer das Menue) oder Lang (in der Edit-Funktion)
 
 
//---------------------------
// exportierte Funktionen
//---------------------------
unsigned char find_paramEditItem( unsigned char paramID );
void editGeneric( unsigned char paramID, uint8_t cmd );
void editBitmask( unsigned char paramID, uint8_t cmd );
void editDisableDeclCalc( unsigned char paramID, uint8_t cmd );
void editCompassOffset( unsigned char paramID, uint8_t cmd );
void editACCZLandingPulse( unsigned char paramID, uint8_t cmd );
void editNA( unsigned char paramID, uint8_t cmd );
 
uint8_t MK_Parameters( uint8_t setting, char *settingname );
 
 
#endif // _MKPARAMETERS_H
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mksettings/mkparameters_messages.h
0,0 → 1,618
/*****************************************************************************
*****************************************************************************/
 
//############################################################################
//# HISTORY mkparameters_messages.h
//#
//# 16.07.2015 Cebra
//# - add: Texte für neue Parameter in FC 2.11a inkl. der ID's
//# const char param_singleWpControlChannel_de
//# const char param_MenuKeyChannel_de
//#
//# 09.04.2015 Cebra
//# - add: Texte für neue Parameter in FC 2.09j
//# const char param_ServoNickFails_de[],const char param_ServoRollFails_de[], const char param_Servo3Fails_de[],
//# const char param_Servo4Fails_de[], const char param_Servo5Fails_de[]
//#
//# 26.09.2014 Cebra
//# - add: Text Höhe Tilt Compensation (FC207f)
//#
//# 04.06.2014 OG
//# - chg: Text von ID_MENU_FAVORITEN etwas gekuerzt
//#
//# 07.05.2014 OG
//# - chg: ID_MENU_FAVORITEN_en
//#
//# 18.04.2014 OG
//# - chg: Textanpassung: param_NaviGpsMinSat_de, param_NaviStickThreshold_de
//#
//# 17.04.2014 OG
//# - add: param_Servo3OnValue, param_Servo3OffValue, param_Servo4OnValue
//# param_Servo4OffValue
//# - add: param_NaviMaxFlyingRange, param_NaviDescendRange
//# - chg: Textanpassung: param_WARN_J16_Bitmask_de, param_WARN_J17_Bitmask_de
//# - chg: Textanpassung: param_J16Bitmask, param_J16Timing
//# - chg: Textanpassung: param_J17Bitmask, param_J17Timing
//# - chg: Textanpassung: param_SingleWpSpeed_de
//# - chg: Textanpassung: param_ServoNickRefresh_de, param_ServoManualControlSpeed_de
//# - chg: Textanpassung: param_ServoRollControl_de
//#
//# 07.04.2014 OG
//# - chg: kleine Aenderungen an englischen Texten
//#
//# 06.04.2014 CB
//# - add: englische Menütexte ergänzt
//#
//# 30.03.2014 OG
//# - chg: Sprache Hollaendisch vollstaendig entfernt
//#
//# 28.03.2014 OG
//# - add: paramID-Texte fuer Rev. 100
//# (param_AutoPhotoDistance, param_AutoPhotoAtitudes, param_SingleWpSpeed)
//#
//# 16.03.2014 OG
//# erste groesstenteils fertige Version
//#
//# 23.02.2014 OG - NEU
//############################################################################
 
#ifndef _MKPARAMETERS_MESSAGES_H
#define _MKPARAMETERS_MESSAGES_H
 
 
//#############################################################################################
//# Texte: Menues von mkparameters
//#############################################################################################
 
static const char ID_MENU_TEST_de[] PROGMEM = "TEST/DEBUG";
#define ID_MENU_TEST_en ID_MENU_TEST_de
 
static const char ID_MENU_FAVORITEN_de[] PROGMEM = "Favoriten";
static const char ID_MENU_FAVORITEN_en[] PROGMEM = "Favorites";
 
static const char ID_MENU_KANAELE_de[] PROGMEM = "Kanäle";
static const char ID_MENU_KANAELE_en[] PROGMEM = "Channel";
 
static const char ID_MENU_KONFIGURATION_de[] PROGMEM = "Konfiguration";
static const char ID_MENU_KONFIGURATION_en[] PROGMEM = "Configuration";
 
static const char ID_MENU_STICK_de[] PROGMEM = "Stick";
#define ID_MENU_STICK_en ID_MENU_STICK_de
 
static const char ID_MENU_LOOPING_de[] PROGMEM = "Looping";
#define ID_MENU_LOOPING_en ID_MENU_LOOPING_de
 
static const char ID_MENU_HOEHE_de[] PROGMEM = "Höhe";
static const char ID_MENU_HOEHE_en[] PROGMEM = "Altitude";
 
static const char ID_MENU_KAMERA_de[] PROGMEM = "Kamera";
static const char ID_MENU_KAMERA_en[] PROGMEM = "Camera";
 
static const char ID_MENU_NAVICTRL_de[] PROGMEM = "Navi-Ctrl";
#define ID_MENU_NAVICTRL_en ID_MENU_NAVICTRL_de
 
static const char ID_MENU_AUSGAENGE_de[] PROGMEM = "Ausgänge";
static const char ID_MENU_AUSGAENGE_en[] PROGMEM = "Outputs";
 
static const char ID_MENU_VERSCHIEDENES_de[] PROGMEM = "Verschiedenes";
static const char ID_MENU_VERSCHIEDENES_en[] PROGMEM = "Miscellaneous";
 
static const char ID_MENU_GYRO_de[] PROGMEM = "Gyro";
#define ID_MENU_GYRO_en ID_MENU_GYRO_de
 
static const char ID_MENU_BENUTZER_de[] PROGMEM = "Benutzer";
static const char ID_MENU_BENUTZER_en[] PROGMEM = "User";
 
static const char ID_MENU_ACHSKOPPLUNG_de[] PROGMEM = "Achskopplung";
static const char ID_MENU_ACHSKOPPLUNG_en[] PROGMEM = "Coupl Axes";
 
/*
static const char ID_MENU_MIXERSETUP_de[] PROGMEM = "Mixer-Setup";
static const char ID_MENU_MIXERSETUP_en[] PROGMEM = "Config Mix";
*/
 
static const char ID_MENU_EASYSETUP_de[] PROGMEM = "Easy Setup";
#define ID_MENU_EASYSETUP_en ID_MENU_EASYSETUP_de
 
 
 
//#############################################################################################
//# Bezeichnungen der paramID's
//#############################################################################################
 
// Hier ist erstmal alles deklariert was auch in paramset.h vorhanden ist.
// Wenn der Compiler richtig eingestellt ist, dann wird alles nicht benoetigte wegoptimiert!
 
static const char param_Hoehe_MinGas_de[] PROGMEM = "Min. Gas";
static const char param_Hoehe_MinGas_en[] PROGMEM = "min. throttle";
 
static const char param_Luftdruck_D_de[] PROGMEM = "Luftdruck D";
static const char param_Luftdruck_D_en[] PROGMEM = "barometric D";
 
static const char param_HoeheChannel_de[] PROGMEM = "Höhe Sollwert";
static const char param_HoeheChannel_en[] PROGMEM = "hight setpoint";
 
static const char param_Hoehe_P_de[] PROGMEM = "Höhe P";
static const char param_Hoehe_P_en[] PROGMEM = "altitude P";
 
static const char param_Hoehe_Verstaerkung_de[] PROGMEM = "Verstärk./Rate";
static const char param_Hoehe_Verstaerkung_en[] PROGMEM = "gain rate";
 
static const char param_Hoehe_ACC_Wirkung_de[] PROGMEM = "Z-ACC";
#define param_Hoehe_ACC_Wirkung_en param_Hoehe_ACC_Wirkung_de
 
static const char param_Hoehe_HoverBand_de[] PROGMEM = "Schwebe-Gas";
static const char param_Hoehe_HoverBand_en[] PROGMEM = "hoover throttle";
 
static const char param_Hoehe_GPS_Z_de[] PROGMEM = "GPS Z";
#define param_Hoehe_GPS_Z_en param_Hoehe_GPS_Z_de
 
static const char param_Hoehe_Tilt_Comp_de[] PROGMEM = "Tilt Compensation";
#define param_Hoehe_Tilt_Comp_en param_Hoehe_Tilt_Comp_de
 
static const char param_Hoehe_StickNeutralPoint_de[] PROGMEM = "Stick Neutr.Punkt";
static const char param_Hoehe_StickNeutralPoint_en[] PROGMEM = "stick neutr.point";
 
static const char param_Stick_P_de[] PROGMEM = "Nick/Roll P";
static const char param_Stick_D_de[] PROGMEM = "Nick/Roll D";
static const char param_StickGier_P_de[] PROGMEM = "Gier P";
#define param_Stick_P_en param_Stick_P_de
#define param_Stick_D_en param_Stick_D_de
#define param_StickGier_P_en param_StickGier_P_de
 
 
static const char param_Gas_Min_de[] PROGMEM = "Min. Gas";
static const char param_Gas_Min_en[] PROGMEM = "min. throttle";
 
static const char param_Gas_Max_de[] PROGMEM = "Max. Gas";
static const char param_Gas_Max_en[] PROGMEM = "max. throttle";
 
static const char param_GyroAccFaktor_de[] PROGMEM = "ACC/Gyro Faktor";
#define param_GyroAccFaktor_en param_GyroAccFaktor_de
 
static const char param_KompassWirkung_de[] PROGMEM = "Kompasswirkung";
static const char param_KompassWirkung_en[] PROGMEM = "compass effect";
 
static const char param_Gyro_P_de[] PROGMEM = "Gyro P";
static const char param_Gyro_I_de[] PROGMEM = "Gyro I";
static const char param_Gyro_D_de[] PROGMEM = "Gyro D";
static const char param_Gyro_Gier_P_de[] PROGMEM = "Gier P";
static const char param_Gyro_Gier_I_de[] PROGMEM = "Gier I";
static const char param_Gyro_Stability_de[] PROGMEM = "Gyro stab.";
#define param_Gyro_P_en param_Gyro_P_de
#define param_Gyro_I_en param_Gyro_I_de
#define param_Gyro_D_en param_Gyro_D_de
#define param_Gyro_Gier_P_en param_Gyro_Gier_P_de
#define param_Gyro_Gier_I_en param_Gyro_Gier_I_de
#define param_Gyro_Stability_en param_Gyro_Stability_de
 
static const char param_UnterspannungsWarnung_de[] PROGMEM = "Unterspannung [0.1V]";
static const char param_UnterspannungsWarnung_en[] PROGMEM = "undervoltage [0.1V]";
 
static const char param_NotGas_de[] PROGMEM = "NOT-Gas";
static const char param_NotGas_en[] PROGMEM = "Emerg.Throttle";
 
static const char param_NotGasZeit_de[] PROGMEM = "NOT-Gas Zeit [0.1s]";
static const char param_NotGasZeit_en[] PROGMEM = "Emerg.Thro.Time[0.1s]";
 
static const char param_Receiver_de[] PROGMEM = "Receiver";
#define param_Receiver_en param_Receiver_de
 
static const char param_I_Faktor_de[] PROGMEM = "Hauptregler I";
static const char param_I_Faktor_en[] PROGMEM = "main I";
 
static const char param_UserParam1_de[] PROGMEM = "Parameter 1";
static const char param_UserParam2_de[] PROGMEM = "Parameter 2";
static const char param_UserParam3_de[] PROGMEM = "Parameter 3";
static const char param_UserParam4_de[] PROGMEM = "Parameter 4";
#define param_UserParam1_en param_UserParam1_de
#define param_UserParam2_en param_UserParam2_de
#define param_UserParam3_en param_UserParam3_de
#define param_UserParam4_en param_UserParam4_de
 
static const char param_ServoNickControl_de[] PROGMEM = "Nick Ansteuerung";
static const char param_ServoNickControl_en[] PROGMEM = "nick servo ctrl";
 
static const char param_ServoNickComp_de[] PROGMEM = "Nick Kompensation";
static const char param_ServoNickComp_en[] PROGMEM = "nick servo comp.";
 
static const char param_ServoNickFails_de[] PROGMEM = "Nick Failsave Wert";
static const char param_ServoNickFails_en[] PROGMEM = "nick failsave value";
 
 
static const char param_ServoNickMin_de[] PROGMEM = "Nick Servo Minimum";
static const char param_ServoNickMax_de[] PROGMEM = "Nick Servo Maximum";
#define param_ServoNickMin_en param_ServoNickMin_de
#define param_ServoNickMax_en param_ServoNickMax_de
 
static const char param_ServoRollControl_de[] PROGMEM = "Roll Ansteuerung";
static const char param_ServoRollControl_en[] PROGMEM = "roll servo ctrl.";
 
static const char param_ServoRollComp_de[] PROGMEM = "Roll Kompensation";
static const char param_ServoRollComp_en[] PROGMEM = "roll compensation";
 
static const char param_ServoRollFails_de[] PROGMEM = "Roll Failsave Wert";
static const char param_ServoRollFails_en[] PROGMEM = "roll failsave value";
 
static const char param_ServoRollMin_de[] PROGMEM = "Roll Minimum";
static const char param_ServoRollMax_de[] PROGMEM = "Roll Maximum";
#define param_ServoRollMin_en param_ServoRollMin_de
#define param_ServoRollMax_en param_ServoRollMax_de
 
//static const char param_ServoNickRefresh_de[] PROGMEM = "Anst. Geschw."; // ALT
static const char param_ServoNickRefresh_de[] PROGMEM = "Anst. Geschwindigkeit";
static const char param_ServoNickRefresh_en[] PROGMEM = "servo refresh";
 
static const char param_ServoManualControlSpeed_de[] PROGMEM = "Manu. Geschwindigkeit.";
static const char param_ServoManualControlSpeed_en[] PROGMEM = "manuell Speed";
 
static const char param_CamOrientation_de[] PROGMEM = "Cam Richtung";
static const char param_CamOrientation_en[] PROGMEM = "cam orientation";
 
static const char param_Servo3_de[] PROGMEM = "Servo 3";
#define param_Servo3_en param_Servo3_de
 
static const char param_Servo3Fails_de[] PROGMEM = "Servo 3 Failsave Wert";
static const char param_Servo3Fails_en[] PROGMEM = "Servo 3 failsave value";
 
static const char param_Servo4_de[] PROGMEM = "Servo 4";
#define param_Servo4_en param_Servo4_de
 
static const char param_Servo4Fails_de[] PROGMEM = "Servo 4 Failsave Wert";
static const char param_Servo4Fails_en[] PROGMEM = "Servo 4 failsave value";
 
static const char param_Servo5_de[] PROGMEM = "Servo 5";
#define param_Servo5_en param_Servo5_de
 
static const char param_Servo5Fails_de[] PROGMEM = "Servo 5 Failsave Wert";
static const char param_Servo5Fails_en[] PROGMEM = "Servo 5 failsave value";
 
 
static const char param_Servo3OnValue_de[] PROGMEM = "Servo 3 On Out1/2";
static const char param_Servo3OffValue_de[] PROGMEM = "Servo 3 Off Out1/2";
static const char param_Servo4OnValue_de[] PROGMEM = "Servo 4 On Out1/2";
static const char param_Servo4OffValue_de[] PROGMEM = "Servo 4 Off Out1/2";
#define param_Servo3OnValue_en param_Servo3OnValue_de
#define param_Servo3OffValue_en param_Servo3OffValue_de
#define param_Servo4OnValue_en param_Servo4OnValue_de
#define param_Servo4OffValue_en param_Servo4OffValue_de
 
 
static const char param_LoopGasLimit_de[] PROGMEM = "Looping Gas Limit";
static const char param_LoopGasLimit_en[] PROGMEM = "loop throttle limit";
 
static const char param_LoopThreshold_de[] PROGMEM = "Ansprechschwelle";
static const char param_LoopThreshold_en[] PROGMEM = "response threshold";
 
static const char param_LoopHysterese_de[] PROGMEM = "Hysterese";
static const char param_LoopHysterese_en[] PROGMEM = "hysteresis";
 
static const char param_AchsKopplung1_de[] PROGMEM = "Gier pos. Kopplung";
static const char param_AchsKopplung1_en[] PROGMEM = "gier pos. coupling";
 
static const char param_AchsKopplung2_de[] PROGMEM = "Nick/Roll Kopplung";
static const char param_AchsKopplung2_en[] PROGMEM = "nick/roll coupling";
 
static const char param_CouplingYawCorrection_de[] PROGMEM = "Gier Korrektur";
static const char param_CouplingYawCorrection_en[] PROGMEM = "gier correction";
 
static const char param_WinkelUmschlagNick_de[] PROGMEM = "Nick Umkehrpunkt";
static const char param_WinkelUmschlagNick_en[] PROGMEM = "nick turnover";
 
static const char param_WinkelUmschlagRoll_de[] PROGMEM = "Roll Umkehrpunkt";
static const char param_WinkelUmschlagRoll_en[] PROGMEM = "roll turnover";
 
static const char param_GyroAccAbgleich_de[] PROGMEM = "ACC/Gyro Komp. [1/x]";
static const char param_GyroAccAbgleich_en[] PROGMEM = "ACC/Gyro Comp. [1/x]";
 
static const char param_Driftkomp_de[] PROGMEM = "Drift-Kompensation";
static const char param_Driftkomp_en[] PROGMEM = "drift compensation";
 
static const char param_DynamicStability_de[] PROGMEM = "Dynamische Stabilität";
static const char param_DynamicStability_en[] PROGMEM = "dynamic stabiliy";
 
static const char param_UserParam5_de[] PROGMEM = "Parameter 5";
static const char param_UserParam6_de[] PROGMEM = "Parameter 6";
static const char param_UserParam7_de[] PROGMEM = "Parameter 7";
static const char param_UserParam8_de[] PROGMEM = "Parameter 8";
#define param_UserParam5_en param_UserParam5_de
#define param_UserParam6_en param_UserParam6_de
#define param_UserParam7_en param_UserParam7_de
#define param_UserParam8_en param_UserParam8_de
 
 
static const char param_J16Bitmask_de[] PROGMEM = "Out1: Bitmaske";
static const char param_J16Bitmask_en[] PROGMEM = "Out1: bitmask";
 
static const char param_J16Timing_de[] PROGMEM = "Out1: Timing [10ms]";
#define param_J16Timing_en param_J16Timing_de
 
static const char param_J17Bitmask_de[] PROGMEM = "Out2: Bitmaske";
static const char param_J17Bitmask_en[] PROGMEM = "Out2: bitmask";
 
static const char param_J17Timing_de[] PROGMEM = "Out2: Timing [10ms]";
#define param_J17Timing_en param_J17Timing_de
 
static const char param_WARN_J16_Bitmask_de[] PROGMEM = "Out1 Warn UBat";
static const char param_WARN_J16_Bitmask_en[] PROGMEM = "Out1 undervolt warn";
 
static const char param_WARN_J17_Bitmask_de[] PROGMEM = "Out2 Warn UBat";
static const char param_WARN_J17_Bitmask_en[] PROGMEM = "Out2 undervolt warn";
 
static const char param_AutoPhotoDistance_de[] PROGMEM = "Auto Trigger Dist.[m]"; // ab Rev. 100 (z.B. FC 2.05e)
#define param_AutoPhotoDistance_en param_AutoPhotoDistance_de // ab Rev. 100 (z.B. FC 2.05e)
 
static const char param_AutoPhotoAtitudes_de[] PROGMEM = "Auto Trigger Alt. [m]"; // ab Rev. 100 (z.B. FC 2.05e)
#define param_AutoPhotoAtitudes_en param_AutoPhotoAtitudes_de // ab Rev. 100 (z.B. FC 2.05e)
 
#define param_NaviOut1Parameter_de param_AutoPhotoDistance_de // bis Rev. 98
#define param_NaviOut1Parameter_en param_AutoPhotoDistance_de // bis Rev. 98
 
static const char param_SingleWpSpeed_de[] PROGMEM = "SingleWP Speed 0.1m/s"; // ab Rev. 100 (z.B. FC 2.05e)
#define param_SingleWpSpeed_en param_SingleWpSpeed_de // ab Rev. 100 (z.B. FC 2.05e)
 
static const char param_LandingPulse_de[] PROGMEM = "ACC Z Landing Pulse"; // ab Rev. 104 (FC 2.09d)
#define param_LandingPulse_en param_LandingPulse_de // ab Rev. 104 (FC 2.09d)
 
static const char param_NaviGpsModeChannel_de[] PROGMEM = "GPS Modus Steuerung";
static const char param_NaviGpsModeChannel_en[] PROGMEM = "GPS mode control";
 
static const char param_NaviGpsGain_de[] PROGMEM = "GPS Verstärkung [%]";
static const char param_NaviGpsGain_en[] PROGMEM = "GPS gain [%]";
 
static const char param_NaviGpsP_de[] PROGMEM = "GPS-P";
static const char param_NaviGpsI_de[] PROGMEM = "GPS-I";
static const char param_NaviGpsD_de[] PROGMEM = "GPS-D";
static const char param_NaviGpsPLimit_de[] PROGMEM = "GPS-P Limit";
static const char param_NaviGpsILimit_de[] PROGMEM = "GPS-I Limit";
static const char param_NaviGpsDLimit_de[] PROGMEM = "GPS-D Limit";
static const char param_NaviGpsA_de[] PROGMEM = "GPS Acc";
#define param_NaviGpsP_en param_NaviGpsP_de
#define param_NaviGpsI_en param_NaviGpsI_de
#define param_NaviGpsD_en param_NaviGpsD_de
#define param_NaviGpsPLimit_en param_NaviGpsPLimit_de
#define param_NaviGpsILimit_en param_NaviGpsILimit_de
#define param_NaviGpsDLimit_en param_NaviGpsDLimit_de
#define param_NaviGpsA_en param_NaviGpsA_de
 
static const char param_NaviGpsMinSat_de[] PROGMEM = "Min. Satelliten";
static const char param_NaviGpsMinSat_en[] PROGMEM = "minimum satelite";
 
static const char param_NaviStickThreshold_de[] PROGMEM = "GPS Stick-Schwelle";
static const char param_NaviStickThreshold_en[] PROGMEM = "GPS stick threshold";
 
static const char param_NaviWindCorrection_de[] PROGMEM = "GPS Windkorrektur [%]";
static const char param_NaviWindCorrection_en[] PROGMEM = "GPS wind correct. [%]";
 
static const char param_NaviAccCompensation_de[] PROGMEM = "ACC Kompensation";
static const char param_NaviAccCompensation_en[] PROGMEM = "ACC compensation";
 
static const char param_NaviOperatingRadius_de[] PROGMEM = "max. Radius";
static const char param_NaviOperatingRadius_en[] PROGMEM = "max. radius";
 
static const char param_NaviAngleLimitation_de[] PROGMEM = "Winkel Limit";
static const char param_NaviAngleLimitation_en[] PROGMEM = "angle limit";
 
static const char param_NaviPH_LoginTime_de[] PROGMEM = "PH Login Zeit [s]";
static const char param_NaviPH_LoginTime_en[] PROGMEM = "PH login time [s]";
 
static const char param_ExternalControl_de[] PROGMEM = "Ext. Kontrolle";
static const char param_ExternalControl_en[] PROGMEM = "ext. control";
 
static const char param_OrientationAngle_de[] PROGMEM = "OrientationAngle";
#define param_OrientationAngle_en param_OrientationAngle_de
 
static const char param_CareFreeChannel_de[] PROGMEM = "CareFree Steuerung";
static const char param_CareFreeChannel_en[] PROGMEM = "careFree control";
 
static const char param_MotorSafetySwitch_de[] PROGMEM = "Motor Sicherh.Schalt.";
static const char param_MotorSafetySwitch_en[] PROGMEM = "motor safety switch";
 
static const char param_MotorSmooth_de[] PROGMEM = "Motor Glättung";
static const char param_MotorSmooth_en[] PROGMEM = "motor smooth";
 
static const char param_ComingHomeAltitude_de[] PROGMEM = "Com.Home Höhe [m]";
static const char param_ComingHomeAltitude_en[] PROGMEM = "coming home alti. [m]";
 
static const char param_FailSafeTime_de[] PROGMEM = "Fails. CH Zeit [s]";
static const char param_FailSafeTime_en[] PROGMEM = "fails. CH time [s]";
 
static const char param_MaxAltitude_de[] PROGMEM = "Max. Höhe [m]";
static const char param_MaxAltitude_en[] PROGMEM = "max. altitude [m]";
 
static const char param_FailsafeChannel_de[] PROGMEM = "Fails. Channel 0=Aus";
static const char param_FailsafeChannel_en[] PROGMEM = "fails. channel 0=off";
 
static const char param_ServoFilterNick_de[] PROGMEM = "Nick Filter";
static const char param_ServoFilterNick_en[] PROGMEM = "nick filter";
 
static const char param_ServoFilterRoll_de[] PROGMEM = "Roll Filter";
static const char param_ServoFilterRoll_en[] PROGMEM = "roll filter";
 
static const char param_StartLandChannel_de[] PROGMEM = "Auto StartLand Kanal";
static const char param_StartLandChannel_en[] PROGMEM = "auto start/land chan.";
 
static const char param_LandingSpeed_de[] PROGMEM = "Landing Speed 0.1m/s";
#define param_LandingSpeed_en param_LandingSpeed_de
 
static const char param_CompassOffset_de[] PROGMEM = "Compass Offset [\x0B]";
#define param_CompassOffset_en param_CompassOffset_de
 
static const char param_AutoLandingVoltage_de[] PROGMEM = "Autoland. Volt [0.1V]";
#define param_AutoLandingVoltage_en param_AutoLandingVoltage_de
 
static const char param_ComingHomeVoltage_de[] PROGMEM = "Coming H. Volt [0.1V]";
#define param_ComingHomeVoltage_en param_ComingHomeVoltage_de
 
static const char param_BitConfig_de[] PROGMEM = "BitConfig";
static const char param_ServoCompInvert_de[] PROGMEM = "ServoCompInvert";
static const char param_ExtraConfig_de[] PROGMEM = "ExtraConfig";
static const char param_GlobalConfig3_de[] PROGMEM = "GlobalConfig3";
static const char param_Name_de[] PROGMEM = "Setting Name";
#define param_BitConfig_en param_BitConfig_de
#define param_ServoCompInvert_en param_ServoCompInvert_de
#define param_ExtraConfig_en param_ExtraConfig_de
#define param_GlobalConfig3_en param_GlobalConfig3_de
#define param_Name_en param_Name_de
 
 
static const char param_ComingHomeOrientation_de[] PROGMEM = "CH Ausrichtung";
static const char param_ComingHomeOrientation_en[] PROGMEM = "CH orientation";
 
static const char param_SingleWpControlChannel_de[] PROGMEM = "Single WP Ctrl Chan.";
#define param_SingleWpControlChannel_en param_SingleWpControlChannel_de
 
static const char param_MenuKeyChannel_de[] PROGMEM = "Next WP Channel";
#define param_MenuKeyChannel_en param_MenuKeyChannel_de
 
// subitems (Bit / Byte-Felder)
static const char param_ServoCompInvert_SVNick_de[] PROGMEM = "Nick Umkehren";
static const char param_ServoCompInvert_SVNick_en[] PROGMEM = "nick inv. direction";
 
static const char param_ServoCompInvert_SVRoll_de[] PROGMEM = "Roll Umkehren";
static const char param_ServoCompInvert_SVRoll_en[] PROGMEM = "Roll inv. direction";
 
static const char param_ServoCompInvert_SVRelMov_de[] PROGMEM = "Nick Relativ";
static const char param_ServoCompInvert_SVRelMov_en[] PROGMEM = "nick relativ";
 
static const char param_ExtraConfig_HeightLimit_de[] PROGMEM = "Höhenbegrenzung";
static const char param_ExtraConfig_HeightLimit_en[] PROGMEM = "heigth limitation";
 
static const char param_ExtraConfig_HeightVario_de[] PROGMEM = "Vario-Höhe"; // negiert param_ExtraConfig_HeightLimit
static const char param_ExtraConfig_HeightVario_en[] PROGMEM = "vario heigth"; // negiert param_ExtraConfig_HeightLimit
 
static const char param_ExtraConfig_VarioBeep_de[] PROGMEM = "akust. Vario";
#define param_ExtraConfig_VarioBeep_en param_ExtraConfig_VarioBeep_de
 
static const char param_ExtraConfig_SensitiveRc_de[] PROGMEM = "Erw. Empf.Sig.Prüfung";
static const char param_ExtraConfig_SensitiveRc_en[] PROGMEM = "enh. rec. sign. check";
 
static const char param_ExtraConfig_33vReference_de[] PROGMEM = "33vReference";
#define param_ExtraConfig_33vReference_en param_ExtraConfig_33vReference_de
 
static const char param_ExtraConfig_NoRcOffBeeping_de[] PROGMEM = "k.Summer o.Sender";
static const char param_ExtraConfig_NoRcOffBeeping_en[] PROGMEM = "no beep without TX";
 
static const char param_ExtraConfig_GpsAid_de[] PROGMEM = "Dynamic PH";
#define param_ExtraConfig_GpsAid_en param_ExtraConfig_GpsAid_de
 
static const char param_ExtraConfig_LearnableCarefree_de[] PROGMEM = "Teachable CF";
#define param_ExtraConfig_LearnableCarefree_en param_ExtraConfig_LearnableCarefree_de
 
static const char param_ExtraConfig_IgnoreMagErrAtStartup_de[] PROGMEM = "Kompass Fehler ignor.";
static const char param_ExtraConfig_IgnoreMagErrAtStartup_en[] PROGMEM = "ignore compass error";
 
static const char param_BitConfig_LoopOben_de[] PROGMEM = "Looping Oben";
static const char param_BitConfig_LoopOben_en[] PROGMEM = "looping up";
 
static const char param_BitConfig_LoopUnten_de[] PROGMEM = "Looping Unten";
static const char param_BitConfig_LoopUnten_en[] PROGMEM = "looping down";
 
static const char param_BitConfig_LoopLinks_de[] PROGMEM = "Looping Links";
static const char param_BitConfig_LoopLinks_en[] PROGMEM = "looping left";
 
static const char param_BitConfig_LoopRechts_de[] PROGMEM = "Looping Rechts";
static const char param_BitConfig_LoopRechts_en[] PROGMEM = "looping right";
 
static const char param_BitConfig_MotorBlink1_de[] PROGMEM = "nur wenn Motor An";
static const char param_BitConfig_MotorBlink1_en[] PROGMEM = "only with motor on";
 
static const char param_BitConfig_MotorOffLed1_de[] PROGMEM = " \x19 sofort an";
static const char param_BitConfig_MotorOffLed1_en[] PROGMEM = " \x19 immediately on";
 
#define param_BitConfig_MotorOffLed2_de param_BitConfig_MotorOffLed1_de
#define param_BitConfig_MotorBlink2_de param_BitConfig_MotorBlink1_de
 
#define param_BitConfig_MotorOffLed2_en param_BitConfig_MotorOffLed1_en
#define param_BitConfig_MotorBlink2_en param_BitConfig_MotorBlink1_en
 
 
static const char param_GlobalConfig3_NoSdCardNoStart_de[] PROGMEM = "k.Start o.SD-Karte";
static const char param_GlobalConfig3_NoSdCardNoStart_en[] PROGMEM = "no start w/o SD-card";
 
static const char param_GlobalConfig3_DphMaxRadius_de[] PROGMEM = "Max.Radius dPH";
#define param_GlobalConfig3_DphMaxRadius_en param_GlobalConfig3_DphMaxRadius_de
 
static const char param_GlobalConfig3_VarioFailsafe_de[] PROGMEM = "NOT-Gas Vario Höhe";
static const char param_GlobalConfig3_VarioFailsafe_en[] PROGMEM = "Emerg.thr.vario h.";
 
static const char param_GlobalConfig3_MotorSwitchMode_de[] PROGMEM = "Motor Swi.Mode";
#define param_GlobalConfig3_MotorSwitchMode_en param_GlobalConfig3_MotorSwitchMode_de
 
static const char param_GlobalConfig3_NoGpsFixNoStart_de[] PROGMEM = "k.Start o.GPS Fix";
static const char param_GlobalConfig3_NoGpsFixNoStart_en[] PROGMEM = "no start w/o GPS Fix";
 
static const char param_GlobalConfig3_UseNcForOut1_de[] PROGMEM = "mit WP-Event verkn.";
static const char param_GlobalConfig3_UseNcForOut1_en[] PROGMEM = "combine with WP-Event";
 
static const char param_GlobalConfig3_SpeakAll_de[] PROGMEM = "Alles Ansagen";
static const char param_GlobalConfig3_SpeakAll_en[] PROGMEM = "speak all";
 
static const char param_GlobalConfig3_ServoNickCompOff_de[] PROGMEM = "Nick Komp. Aus";
static const char param_GlobalConfig3_ServoNickCompOff_en[] PROGMEM = "nick compensation off";
 
static const char param_GlobalConfig_HoehenRegelung_de[] PROGMEM = "Höhenregelung";
static const char param_GlobalConfig_HoehenRegelung_en[] PROGMEM = "height control";
 
static const char param_GlobalConfig_HoehenSchalter_de[] PROGMEM = "Schalter Höhe";
static const char param_GlobalConfig_HoehenSchalter_en[] PROGMEM = "height switch";
 
static const char param_GlobalConfig_HeadingHold_de[] PROGMEM = "Heading Hold";
#define param_GlobalConfig_HeadingHold_en param_GlobalConfig_HeadingHold_de
 
static const char param_GlobalConfig_KompassAktiv_de[] PROGMEM = "Kompass Aktiv";
static const char param_GlobalConfig_KompassAktiv_en[] PROGMEM = "compass aktiv";
 
static const char param_GlobalConfig_KompassFix_de[] PROGMEM = "Kompass Fix";
static const char param_GlobalConfig_KompassFix_en[] PROGMEM = "compass fix";
 
static const char param_GlobalConfig_GpsAktiv_de[] PROGMEM = "GPS Aktiv";
#define param_GlobalConfig_GpsAktiv_en param_GlobalConfig_GpsAktiv_de
 
static const char param_GlobalConfig_AchsenkopplungAktiv_de[] PROGMEM = "Achs(ent)kopplung";
static const char param_GlobalConfig_AchsenkopplungAktiv_en[] PROGMEM = "(De)Coupl Axes";
 
static const char param_GlobalConfig_DrehratenBegrenzer_de[] PROGMEM = "Drehratenbegrenzung";
static const char param_GlobalConfig_DrehratenBegrenzer_en[] PROGMEM = "rotary rate limit.";
 
static const char param_Kanalbelegung_Nick_de[] PROGMEM = "Nick";
static const char param_Kanalbelegung_Roll_de[] PROGMEM = "Roll";
#define param_Kanalbelegung_Nick_en param_Kanalbelegung_Nick_de
#define param_Kanalbelegung_Roll_en param_Kanalbelegung_Roll_de
 
static const char param_Kanalbelegung_Gas_de[] PROGMEM = "Gas";
static const char param_Kanalbelegung_Gas_en[] PROGMEM = "throttle";
 
static const char param_Kanalbelegung_Gear_de[] PROGMEM = "Gear";
#define param_Kanalbelegung_Gear_en param_Kanalbelegung_Gear_de
 
static const char param_Kanalbelegung_Poti1_de[] PROGMEM = "Poti 1";
static const char param_Kanalbelegung_Poti2_de[] PROGMEM = "Poti 2";
static const char param_Kanalbelegung_Poti3_de[] PROGMEM = "Poti 3";
static const char param_Kanalbelegung_Poti4_de[] PROGMEM = "Poti 4";
static const char param_Kanalbelegung_Poti5_de[] PROGMEM = "Poti 5";
static const char param_Kanalbelegung_Poti6_de[] PROGMEM = "Poti 6";
static const char param_Kanalbelegung_Poti7_de[] PROGMEM = "Poti 7";
static const char param_Kanalbelegung_Poti8_de[] PROGMEM = "Poti 8";
#define param_Kanalbelegung_Poti1_en param_Kanalbelegung_Poti1_de
#define param_Kanalbelegung_Poti2_en param_Kanalbelegung_Poti2_de
#define param_Kanalbelegung_Poti3_en param_Kanalbelegung_Poti3_de
#define param_Kanalbelegung_Poti4_en param_Kanalbelegung_Poti4_de
#define param_Kanalbelegung_Poti5_en param_Kanalbelegung_Poti5_de
#define param_Kanalbelegung_Poti6_en param_Kanalbelegung_Poti6_de
#define param_Kanalbelegung_Poti7_en param_Kanalbelegung_Poti7_de
#define param_Kanalbelegung_Poti8_en param_Kanalbelegung_Poti8_de
 
static const char param_CompassOffset_DisableDeclCalc_de[] PROGMEM = "Disable Decl. Calc";
#define param_CompassOffset_DisableDeclCalc_en param_CompassOffset_DisableDeclCalc_de
 
 
static const char param_NaviMaxFlyingRange_de[] PROGMEM = "Max. Flugradius [10m]";
static const char param_NaviMaxFlyingRange_en[] PROGMEM = "Max. Flightrad. [10m]";
 
static const char param_NaviDescendRange_de[] PROGMEM = "Fail SinkRadius [10m]";
#define param_NaviDescendRange_en param_NaviDescendRange_de
 
 
 
#endif // _MKPARAMETERS_H
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mksettings/mksettings.c
0,0 → 1,707
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY mksettings.c
//#
//# 14.05.2014 OG
//# - chg: include "mkbase.h" geaendert auf "../mk/mkbase.h"
//#
//# 11.05.2014 OG
//# - chg: MKSettings_Menu() umgestellt auf MenuCtrl_SetTitleFromParentItem()
//# -> die Menues 'erben' damit ihren Titel vom aufrufenden Menuepunkt
//#
//# 29.03.2014 OG
//# - chg: versch. Funktionen: del: MenuCtrl_SetShowBatt() wegen Aenderung
//# des Defaults auf true
//#
//# 26.03.2014 OG
//# - add: etliche Aenderungen in allen Bereichen fuer das erste Release
//# der neuen MK-Settings
//#
//# 27.02.2014 OG
//# - chg: MKSettings_AskAction() Unterstuetzung von param_DUMMY
//#
//# 26.02.2014 OG
//# - chg: MKSettings_Copy() auf KEYLINE2 geaendert
//#
//# 23.02.2014 OG
//# - chg: MKSettings_Menu() Aufruf von MK_Parameters() geaendert
//#
//# 18.02.2014 OG - NEU
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <avr/wdt.h>
#include <util/delay.h>
#include <avr/eeprom.h>
#include <util/delay.h>
#include <string.h>
#include <util/atomic.h>
 
//#include "../lipo/lipo.h"
#include "../main.h"
#include "../lipo/lipo.h"
#include "../lcd/lcd.h"
#include "../uart/usart.h"
#include "../utils/menuctrl.h"
#include "../utils/xutils.h"
 
#include "../uart/uart1.h"
#include "../mk-data-structs.h"
//#include "../menu.h"
#include "../timer/timer.h"
#include "../eeprom/eeprom.h"
#include "../messages.h"
#include "../pkt/pkt.h"
#include "../mk/mkbase.h"
#include "paramset.h"
#include "mkparameters.h"
#include "mksettings.h"
 
//---------------------------------------------------------------------------------------------
 
#define F_EXIT 0
#define F_REFRESH 1
 
char mksettings_menu_names[6][18]; // befuellt von: MKSettings_read_Names()
 
 
//-------------------------------------
//-------------------------------------
typedef struct
{
unsigned char paramsetRevision; // Revision FC-Parameterset fuer die das Temp-Setting gueltig ist
unsigned char *paramset; // malloc: Pointer auf kopierte Parameter-Daten
} MKSetting_TMP_t;
 
 
MKSetting_TMP_t MKSetting_TMP;
 
 
#define ID_SETTING_COPY 10 // fuer MKSettings_Menu()
#define ID_EDIT 20 // fuer MKSettings_AskAction()
#define ID_ACTIVATE 21 // fuer MKSettings_AskAction()
#define ID_COPY 22 // fuer MKSettings_AskAction()
 
#define ID_SAVE 30 // fuer MKSettings_AskSaveSetting()
#define ID_DISCARD 31 // fuer MKSettings_AskSaveSetting()
 
 
//#############################################################################################
//#
//#############################################################################################
 
 
//--------------------------------------------------------------
// MKSettings_TMP_Init0()
//
// nur fuer main.c
//--------------------------------------------------------------
void MKSettings_TMP_Init0( void )
{
memset( &MKSetting_TMP, 0, sizeof(MKSetting_TMP_t) );
strcpy( mksettings_menu_names[5], "PKT: --empty--");
}
 
 
 
//--------------------------------------------------------------
// MKSettings_TMP_Init()
//
// loeschen / initialisieren vom PKT Temp-Setting
//--------------------------------------------------------------
void MKSettings_TMP_Init( void )
{
if( MKSetting_TMP.paramset != NULL )
{
free( MKSetting_TMP.paramset );
}
MKSettings_TMP_Init0();
}
 
 
 
//--------------------------------------------------------------
// from_setting = 6 : von TMP zu einem MK-Setting
// from_setting <= 5: von MK-Setting zu TMP
//--------------------------------------------------------------
uint8_t MKSettings_TMP_copy( uint8_t to_setting, uint8_t timeout )
{
uint8_t written;
uint8_t size = paramsetSize();
 
if( MKSetting_TMP.paramset == NULL )
{
MKSetting_TMP.paramset = malloc( size+1 ); // +1 fuer das erste settings-byte
}
 
if( !MKSetting_TMP.paramset )
{
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( PSTR("NO RAM!"), true, 800, true, true ); // FEHLER! (NO RAM)
return 0; // -> EXIT
}
 
// von MK-Setting 1..5 zu TMP
if( to_setting == 6 )
{
MKSetting_TMP.paramsetRevision = MKVersion.paramsetRevision;
memcpy( MKSetting_TMP.paramset, (unsigned char *)(pRxData), size+1 ); // memcpy( dst, src, size))
return 6;
}
 
// von TMP zu MK-Setting 1..5
memcpy( (unsigned char *)(pRxData), MKSetting_TMP.paramset , size+1 ); // memcpy( dst, src, size))
written = MK_Setting_write( to_setting, timeout);
return written;
}
 
 
 
//#############################################################################################
//#
//#############################################################################################
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t MKSettings_read_Names( void )
{
uint8_t setting;
 
// die 5 Settings vom Kopter laden um die
// Setting-Namen zu speichern
for( setting=1; setting <= 5; setting++ )
{
if( !MK_Setting_load( setting, 20 ) )
return(0); // Fehler - setting konnte nicht geladen werden (timeout = 20)
xsnprintf( mksettings_menu_names[setting-1], 16, "%1d: %s", setting, paramGet_p(param_Name) );
}
 
// TMP-Setting
if( MKSetting_TMP.paramset != NULL )
{
if( MKSetting_TMP.paramsetRevision != MKVersion.paramsetRevision )
{
// wenn die FC-Revision vom TMP-Setting abweicht vom zuletzt geladenen
// dann wurde ggf. der Kopter gewechselt -> TMP-Setting verwerfen
MKSettings_TMP_Init();
}
else
{
// den Namen aus dem TMP-Setting holen
paramsetInit( MKSetting_TMP.paramset );
xsnprintf( mksettings_menu_names[5], 16, "PKT: %s", paramGet_p(param_Name) );
}
}
 
setting = MK_Setting_load( 0xff, 20); // aktuelles MK Setting ermitteln
 
return setting;
}
 
 
 
//--------------------------------------------------------------
// wahl = MKSettings_AskAction( setting)
//
// Rueckgabe:
// 0 (==Ende), ID_EDIT, ID_ACTIVATE, ID_COPY
//--------------------------------------------------------------
uint8_t MKSettings_AskAction( uint8_t setting )
{
uint8_t wahl = 0;
 
//-----------------
// Menue erstellen
//-----------------
MenuCtrl_Create();
MenuCtrl_SetTitle( mksettings_menu_names[setting-1] ); // Menuetitel ist der Settingname
MenuCtrl_ShowLevel(false);
MenuCtrl_SetTopSpace(1); // oben beim Menue eine Leerzeile einfuegen
 
//-----------------
// Menueeintraege
//-----------------
if( !paramExist(param_DUMMY) ) // param_DUMMY -> das Parameterset wird nicht zum bearbeiten unterstuetzt
MenuCtrl_Push_P( ID_EDIT , MENU_ITEM, NOFUNC, strGet(EDIT_SETTING) ); // "Setting ändern"
 
if( setting != 6)
MenuCtrl_Push_P( ID_ACTIVATE, MENU_ITEM, NOFUNC, strGet(PARA_AKTIVI) ); // "aktivieren"
 
MenuCtrl_Push_P( ID_COPY , MENU_ITEM, NOFUNC, strGet(STR_COPY) ); // "kopieren"
 
//-----------------
// Menue Control
//-----------------
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() != KEY_ESC )
wahl = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID_CHANGE, ID_ACTIVATE)
 
MenuCtrl_Destroy();
MenuCtrl_ShowLevel(true);
 
return wahl; // 0=Ende; ID_EDIT; ID_ACTIVATE, ID_COPY
}
 
 
 
//--------------------------------------------------------------
// wahl = MKSettings_AskSaveSetting( setting)
//
// Rueckgabe:
// 0 (==Ende), ID_SAVE, ID_DISCARD
//--------------------------------------------------------------
uint8_t MKSettings_AskSaveSetting( uint8_t setting )
{
uint8_t wahl = 0;
 
//-----------------
// Menue erstellen
//-----------------
MenuCtrl_Create();
MenuCtrl_SetTitle( mksettings_menu_names[setting-1] ); // Menuetitel ist der Settingname
MenuCtrl_ShowLevel(false);
MenuCtrl_SetTopSpace(1); // oben beim Menue eine Leerzeile einfuegen
 
//-----------------
// Menueeintraege
//-----------------
MenuCtrl_Push_P( ID_SAVE , MENU_ITEM, NOFUNC, strGet(STR_SAVE) ); // "speichern"
MenuCtrl_Push_P( ID_DISCARD , MENU_ITEM, NOFUNC, strGet(STR_DISCARD) ); // "verwerfen"
 
 
//-----------------
// Menue Control
//-----------------
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() != KEY_ESC )
wahl = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID_CHANGE, ID_ACTIVATE)
 
MenuCtrl_Destroy();
MenuCtrl_ShowLevel(true);
 
return wahl; // 0=Ende; ID_EDIT; ID_ACTIVATE, ID_COPY
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t MKSettings_Copy( uint8_t from_setting )
{
const char *mask = PSTR("%15s");
uint8_t redraw = true;
uint8_t loaded = 0;
uint8_t to_setting;
uint8_t written;
uint8_t key;
int8_t yoffs;
 
 
lcd_cls();
 
to_setting = from_setting;
 
while( true )
{
//------------------------
// anzeigen
//------------------------
if( redraw )
{
lcd_frect( 0, 0, 127, 7, 1); // Titel: Invers
lcd_printp_at( 1, 0, strGet(PARA_COPY), MINVERS);
 
yoffs = -1;
lcdx_printp_at( 0, 2, strGet(STR_VON), MNORMAL, 0,yoffs); // "von"
lcdx_printf_at_P( 5, 2, MNORMAL, 3,yoffs, mask, mksettings_menu_names[from_setting-1] );
 
yoffs = -7;
lcd_frect( 5*6, 4*8+yoffs, 15*6, 7, 0);
lcdx_printp_at( 0, 4, strGet(STR_NACH), MNORMAL, 0,yoffs); // "nach"
lcdx_printf_at_P( 5, 4, MNORMAL, 3,yoffs, mask, mksettings_menu_names[to_setting-1] );
 
lcd_printp_at(0, 7, strGet(KEYLINE2), MNORMAL); // Keyline: <- -> Ende OK
 
redraw = false;
}
 
//------------------------
// Tasten abfragen
//------------------------
if( get_key_press(1 << KEY_ESC) )
{
return 99; // nur "ENDE"
}
 
if( get_key_press(1 << KEY_PLUS) )
{
if( to_setting == 6 ) to_setting = 1;
else to_setting++;
redraw = true;
}
 
if( get_key_press(1 << KEY_MINUS) )
{
if( to_setting == 1 ) to_setting = 6;
else to_setting--;
redraw = true;
}
 
//-------------------------------
// Taste: OK = Setting kopieren?
//-------------------------------
if( get_key_press(1 << KEY_ENTER) )
{
lcdx_printp_center( 5, strGet(PARA_COPYQ), MNORMAL, 0,1); // "Wirklich kopieren?" (zentriert)
lcd_rect_round( 0, 5*8-3, 127, 7+7, 1, R2); // Rahmen um die Frage
 
lcd_frect( 0, 7*8, 127, 7, 0); // Keyline loeschen
lcd_printp_at(12, 7, strGet(NOYES), MNORMAL); // neue Keyline: "Nein Ja"
 
set_beep( 25, 0xffff, BeepNormal ); // kurzer Beep
 
key = 0;
while( !key ) // Abfrage: Ja / Nein
{
key = get_key_press(1 << KEY_ENTER) ? KEY_ENTER : key; // => "Ja" (=Setting kopieren)
key = get_key_press(1 << KEY_ESC) ? KEY_ESC : key; // => "Nein"
PKT_CtrlHook();
}
 
//---------------------------
// "Ja" -> Setting kopieren!
//---------------------------
if( key == KEY_ENTER ) // => "Ja" -> Setting kopieren!
{
if( from_setting != 6 ) // kein PKT TMP-Setting
{
loaded = MK_Setting_load( from_setting, 20 ); // timeout = 20
 
if( loaded != from_setting ) // Fehler beim laden - Datenverlust?
{
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( strGet(ERROR_NODATA), true, 800, true, true ); // "Datenverlust!" (max. 8 Sekunden anzeigen)
return 0; // 0 = Ende/Abbruch
}
}
 
if( to_setting == 6 ) // von Setting 1..5 nach TMP speichern
{
MKSettings_TMP_copy( 6, 10 );
return loaded;
}
 
// Anzeige "speichern..."
lcd_frect( 0, (8*4), 128, (8*4), 0); // Anzeigebereich löschen
lcdx_printp_center( 4, strGet(STR_SAVING), MNORMAL, 0,9); // Text zentriert; String in PROGMEM
lcd_rect_round( 0, 37, 127, 14, 1, R2); // Rahmen
 
 
if( from_setting == 6 ) // von TMP nach Setting 1..5
{
written = MKSettings_TMP_copy( to_setting, 30 );
return written;
}
 
 
if( to_setting <= 5 ) // 'echtes' MK Setting speichern
{
written = MK_Setting_write( to_setting, 30 ); // Timeout = 40
return written;
}
}
 
if( key == KEY_ESC ) // => "Nein" -> nicht kopieren
{
lcd_cls();
redraw = true;
}
 
} //end: if( get_key_press(1 << KEY_ENTER) )
 
 
//------------------------------------------
// Pruefe PKT-Update oder andere PKT-Aktion
//------------------------------------------
if( PKT_CtrlHook() ) // Update vom Updatetool angefordert?
{
lcd_cls();
redraw = true;
}
 
} // end: while( true )
 
return 0;
}
 
 
 
//--------------------------------------------------------------
// ret = MKSettings_Menu()
//
// Rueckgabe:
// 0 = Ende/Fehler/Abbruch
// 1 = Refresh
//--------------------------------------------------------------
uint8_t MKSettings_Menu( void )
{
uint8_t i;
uint8_t active_setting;
uint8_t setting;
uint8_t wahl;
uint8_t wahl2;
uint8_t changed;
 
 
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( strGet(MSG_LOADSETTINGS), false, 0, true, true ); // "lade Settings..."
 
 
active_setting = MKSettings_read_Names();
 
if( !active_setting ) // Fehler: settings konnten nicht geladen werden...
{
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( strGet(ERROR_NODATA), true, 800, true, true ); // "Datenverlust!" (max. 8 Sekunden anzeigen)
return F_EXIT; // F_EXIT = Ende/Abbruch
}
 
 
//---------------
// Create
//---------------
MenuCtrl_Create();
 
//---------------
// Einstellungen
//---------------
MenuCtrl_SetTitleFromParentItem(); // "MK Settings"
//MenuCtrl_SetTitle_P( PSTR("MK Settings") );
//MenuCtrl_SetCycle( false );
//MenuCtrl_SetShowBatt( true );
 
 
//---------------
// Menue-Punkte
//---------------
for( i=0; i< ( MKSetting_TMP.paramset!=NULL ? 6 : 5); i++ )
{
MenuCtrl_Push( i+1, MENU_SUB, NOFUNC, mksettings_menu_names[i] ); // Setting 1..5
}
 
MenuCtrl_ItemSelect( active_setting ); // Menucursor auf aktives Setting setzen
MenuCtrl_ItemMark( active_setting, true); // aktives Setting markieren
 
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) // Ende?
{
break; // Ende
}
 
setting = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
if( setting >=1 && setting <= 6 )
{
wahl = MKSettings_AskAction( setting );
 
//--------------
// bearbeiten
//--------------
if( wahl == ID_EDIT )
{
// TODO: Fehler abfangen!
MK_Setting_load( setting, 25 ); // timeout = 25
changed = MK_Parameters( setting, mksettings_menu_names[setting-1] );
 
if( changed && (setting!=6) )
{
wahl2 = MKSettings_AskSaveSetting( setting );
if( wahl2 == ID_SAVE )
{
lcd_frect( 0, (8*7), 128, 7, 0); // Keyline löschen
lcdx_printp_center( 4, strGet(STR_SAVING), MNORMAL, 0,9); // Text zentriert; String in PROGMEM
lcd_rect_round( 0, 37, 127, 14, 1, R2); // Rahmen
 
setting = MK_Setting_write( setting, 50);
 
if( !setting )
{
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( strGet(ERROR_NODATA), true, 800, true, true ); // FEHLER! nodata (max. 8 Sekunden anzeigen)
//MenuCtrl_Destroy();
//return F_EXIT; // F_EXIT = Ende/Abbruch
}
}
}
}
 
 
//--------------
// aktivieren
//--------------
if( wahl == ID_ACTIVATE )
{
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( strGet(MSG_ACTIVATESETTING), false, 0, true, true ); // "aktiviere Setting..."
 
active_setting = MK_Setting_change( setting );
 
if( !active_setting )
{
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( strGet(ERROR_NODATA), true, 800, true, true ); // FEHLER! nodata (max. 8 Sekunden anzeigen)
//MenuCtrl_Destroy();
//return F_EXIT; // F_EXIT = Ende/Abbruch
}
else
{
// neues Setting markieren
for( i=1; i<=5; i++ ) MenuCtrl_ItemMark( i, false); // Markierungen loeschen
MenuCtrl_ItemMark( active_setting, true); // aktives Setting markieren
}
 
} // end: if( wahl == ID_ACTIVATE )
 
 
//--------------
// kopieren
//--------------
if( wahl == ID_COPY )
{
active_setting = MKSettings_Copy( setting );
 
if( !active_setting )
{
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( strGet(ERROR_NODATA), true, 800, true, true ); // FEHLER! nodata (max. 8 Sekunden anzeigen)
//MenuCtrl_Destroy();
//return F_EXIT; // F_EXIT = Ende/Abbruch
}
 
if( active_setting != 99 ) // =99 bedeutet: User hat die Funktion abgebrochen...
{
MenuCtrl_Destroy(); // ok, kein Abbruch durch den User -> Menue neu aufbauen
return F_REFRESH; // da sich ggf. Settings-Namen geaendert haben
}
} // end: if( wahl == ID_COPY )
 
}
 
} // end: while( true )
 
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
 
return F_EXIT;
}
 
 
 
//#############################################################################################
//#
//#############################################################################################
 
 
//--------------------------------------------------------------
// das muss ueberarbeitet werden....
//--------------------------------------------------------------
static uint8_t check_motorOff(void)
{
NaviData_t *naviData;
 
if( hardware == NC ) // Prüfung funktioniert nur mit NC
{
SwitchToNC();
SendOutData( 'o', ADDRESS_NC, 1, 10, 1);
mode = 'O';
rxd_buffer_locked = FALSE;
timer = 200;
 
while( !rxd_buffer_locked && timer>0 );
 
if( rxd_buffer_locked ) // naviData Ok?
{
// timer = MK_TIMEOUT;
Decode64();
naviData = (NaviData_t *) pRxData;
 
if( naviData->FCStatusFlags & FC_STATUS_MOTOR_RUN )
return false;
else
return true;
}
 
return false;
}
 
return true; // hmm, wenn man nur eine FC hat dann wird hier immer gemeldet "Motoren sind aus" ?
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void MK_Settings( void )
{
//MKSettings_TMP_Init();
 
//if( true )
if( !check_motorOff() )
{
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( strGet(STR_SWITCHMOTOROFF), false, 400, true, true ); // "Motoren ausschalten!"
return;
}
 
while( MKSettings_Menu() == F_REFRESH );
}
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mksettings/mksettings.h
0,0 → 1,55
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2012 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2012 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY mksettings.h
//#
//# 19.02.2014 OG - NEU
//# - add: MKSettings_TMP_Init(), MKSettings_TMP_Init0()
//#
//# 18.02.2014 OG - NEU
//############################################################################
 
#ifndef _MKPARAMETERS_H
#define _MKPARAMETERS_H
 
 
//---------------------------
// exportierte Funktionen
//---------------------------
void MK_Settings( void );
 
void MKSettings_TMP_Init0( void );
void MKSettings_TMP_Init( void );
 
#endif // _MKPARAMETERS_H
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mksettings/paramset.c
0,0 → 1,2583
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY paramset.c
//#
//# 16.07.2015 Cebra (PKT385a)
//# - add: unsigned char SingleWpControlChannel; (FC2.11a)
//# unsigned char MenuKeyChannel; (FC2.11a)
//# - add: paramset_106 (FC2.11a)
//#
//# 09.04.2015 Cebra (PKT384a)
//# - add: unsigned char ServoFS_Pos[5] (FC 2.09i)
//# - add: paramset_105 (FC2.09j)
//#
//# 19.03.2015 Cebra (PKT383a)
//# - add: param_LandingPulse (FC 2.09d)
//#
//# 26.01.2015 Cebra
//# - add: Function transform_ComingHomeOrientation
//# Ändert die Bits 4+5 für ServoCompInvert
//# in Konfigurationstabelle der paramSubID: param_ComingHomeOrientation neu
//#
//# 26.09.2014 Cebra
//# - add: Parameterset Rev. 103 (FC 2.07f)
//# - chg: param_Hoehe_GPS_Z zu param_Hoehe_Verstaerkung im Paramset 103
//#
//# 14.05.2014 OG
//# - chg: include "mkbase.h" geaendert auf "../mk/mkbase.h"
//#
//# 10.05.2014 OG
//# - add: transform_CompassOffset_DisableDeclCalc() - transformiert true/false
//# in das Byte von param_CompassOffset
//#
//# 09.05.2014 OG
//# - chg: paramSet() - angepasst auf Transform-Funktionen
//# - chg: paramGet() - angepasst auf Transform-Funktionen
//# - add: eine neue Transformations-Zwischenschicht implementiert - abgebildet
//# ueber die neue Tabelle paramTransform.
//# Hier koennen Transform-Funktionen hinterlegt werden die einen
//# ubyte8 Wert veraendern.
//# Die Transformation wird von paramSet()/paramGet() aufgerufen.
//#
//# 17.04.2014 OG
//# - FIX: _paramset_getsubitemid(): Pruefung von_Revision/bis_Revision
//# korrigiert - fuehrte vorher ggf. zu falschen Anzeigen von SubItems!
//# - chg: param_BitConfig_MotorOffLed1 auf bis_Revision 101 begrenzt
//# - chg: param_BitConfig_MotorOffLed2 auf bis_Revision 101 begrenzt
//#
//# 09.04.2014 OG
//# - chg: Rev. 101 auf param_DUMMY umgestellt um Platz zu sparen
//#
//# 08.04.2014 OG
//# - add: Parameterset Rev. 102 (FC 2.05g)
//# - fix: _paramset_getsubitemid() - Vergleich bzgl. von/bis_Revision umgedreht
//# und equal zugefuegt
//#
//# 06.04.2014 OG
//# - add: Parameterset Rev. 101 (FC 2.05f)
//# -> param_Servo3OnValue, param_Servo3OffValue
//# -> param_Servo4OnValue, param_Servo4OffValue
//#
//# 28.03.2014 OG
//# - add: Parameterset Rev. 100 (FC 2.05e)
//# (param_AutoPhotoDistance, param_AutoPhotoAtitudes, param_SingleWpSpeed)
//#
//# 26.03.2014 OG
//# - add: param_CompassOffset_DisableDeclCalc (Sub-Item)
//#
//# 24.03.2014 OG
//# - chg: _paramset_getsubitemid() erweitert Unterstuetzung von/bis FC-Revisionen
//# - add: paramSubItem_t mit Unterstuetzung fuer von/bis FC-Revisionen
//#
//# 27.02.2014 OG
//# - chg: die Revisions-Tabellen 90 bis 94 mittels param_DUMMY gekuerzt
//# -> keine Parameter-Bearbeitung bei denen moeglich
//# - add: vollstaendige Unterstuetzung von paramSubID's via paramGet(), paramSet()
//#
//# 26.02.2014 OG
//# - add: paramSubItem[] - Zugriffstabelle auf Bit- und Bytefelder innerhalb
//# einer paramID
//# - chg: bei den paramset_nnn[] Tabellen 'const' ergaenzt
//# - chg: paramsetTest() umbenannt zu paramsetDEBUG()
//#
//# 19.02.2014 OG
//# - fix: paramsetInit() Parameter pData wurde nicht konsequent verwendet
//#
//# 14.02.2014 OG
//# - add: diverse Zugriffsfunktionen fuer paramID's und paramSet's
//# - add: Rev-Tabellen von FC v0.88e bis FC v2.03d
//#
//# 05.02.2014 OG - NEU
//############################################################################
 
 
//############################################################################
//# INHALT
//#
//# 1a. Konfigurationtabellen fuer verschiedene FC-Revisionen
//# 1b. Zuweisungstabelle: Revision -> paramset_xxx
//# 2. Konfigurationstabelle der paramSubID's (Bit- und Bytefelder)
//# 3a. interne Zugriffsfunktionen
//# 3b. oeffentliche Zugriffsfunktionen fuer paramID / paramSubID Elemente
//# 3c. oeffentliche Zugriffsfunktionen fuer das gesamte Paramset (Int usw.)
//# x. TEST / DEBUG
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <avr/wdt.h>
#include <util/delay.h>
#include <avr/eeprom.h>
#include <util/delay.h>
#include <string.h>
#include <util/atomic.h>
 
#include "../main.h"
#include "../lipo/lipo.h"
#include "../lcd/lcd.h"
#include "../uart/usart.h"
 
#include "../uart/uart1.h"
#include "../mk-data-structs.h"
#include "../timer/timer.h"
#include "../eeprom/eeprom.h"
#include "../messages.h"
#include "../utils/scrollbox.h"
#include "../pkt/pkt.h"
#include "../mk/mkbase.h"
#include "paramset.h"
 
 
 
//---------------------------
// fuer transform_...
//---------------------------
#define GETVALUE 1 // Wert setzen
#define SETVALUE 2 // Wert lesen
 
 
 
paramRevItem_t *paramsetRevTable; // Zeiger auf aktive Revision-Table oder 0 wenn nicht gesetzt -> wird gesetzt druch paramsetInit() / paramset.c
unsigned char *mkparamset; // nur temp. gueltig solange der PKT-RX-Buffer (pRxData) noch nicht wieder ueberschrieben -> wird gesetzt druch paramsetInit() / paramset.c
 
 
 
//#############################################################################################
//# 1a. Konfigurationtabellen fuer verschiedene FC-Revisionen
//#############################################################################################
 
 
//---------------------------------------------------------------------------------------
// die nachfolgenden Tabellen entsprechen der Struktur von paramRevItem_t aus paramset.h
//---------------------------------------------------------------------------------------
 
 
//-----------------------------------------------
// FC-Parameter Revision: 90
//
// ab FC-Version: ab ??? bis ???
// gefunden in : 0.88e
//
// Tabelle ist definiert in der
// nachfolgenden paramset_091
//
// STRUKTUR-DIFF zu 0:
//
// DEFINE-DIFF zu 0:
//-----------------------------------------------
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 91
//
// ab FC-Version: ab ??? bis ???
// gefunden in : 0.88m, 0.88n
//
// STRUKTUR-DIFF zu 090:
// - keine Aenderung der internen Datenstruktur erkennbar!
//
// DEFINE-DIFF zu 090:
// - add: #define PID_SPEAK_HOTT_CFG
// - add: #define CFG3_MOTOR_SWITCH_MODE
// - add: #define CFG3_NO_GPSFIX_NO_START
//-----------------------------------------------
//
//
// + paramID (paramRevItem_t -> paramID)
// |
// | + size in Bytes (paramRevItem_t -> size)
// | |
// | |
// | |
paramRevItem_t const paramset_091[] PROGMEM =
{
{ param_DUMMY , 111 }, // n-Bytes Fueller... keine Unterstuetzung fuer paramEdit
{ param_Name , 12 }, // char Name[12];
{ param_DUMMY , 1 }, // n-Bytes Fueller... keine Unterstuetzung fuer paramEdit
 
{ param_EOF , 0 } // END OF PARAM-LIST - MUST BE THE LAST!!
 
}; // end: paramset_091[]
 
 
 
//############################################################################################################################################################
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 92
//
// ab FC-Version: ab ??? bis ???
// gefunden in : 0.90d
//
// Tabelle ist definiert in der
// nachfolgenden paramset_093
//
// STRUKTUR-DIFF zu 091:
// -add: param_NaviOut1Parameter
//#
// DEFINE-DIFF zu 091:
// -add: #define CFG3_USE_NC_FOR_OUT1 0x20
// -add: #define CFG3_SPEAK_ALL
// -add: #define SERVO_NICK_INV 0x01
// -add: #define SERVO_ROLL_INV 0x02
// -add: #define SERVO_RELATIVE 0x04
//-----------------------------------------------
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 93
//
// ab FC-Version: ab ??? bis ???
// gefunden in : 0.90e, 0.90g, 0.90j
//
// STRUKTUR-DIFF zu 092:
// - keine Aenderung der internen Datenstruktur erkennbar!
//
// DEFINE-DIFF zu 092:
// - keine Aenderung erkennbar!
//-----------------------------------------------
paramRevItem_t const paramset_093[] PROGMEM =
{
{ param_DUMMY , 112 }, // n-Bytes Fueller... keine Unterstuetzung fuer paramEdit
{ param_Name , 12 }, // char Name[12];
{ param_DUMMY , 1 }, // n-Bytes Fueller... keine Unterstuetzung fuer paramEdit
 
{ param_EOF , 0 } // END OF PARAM-LIST - MUST BE THE LAST!!
 
}; // end: paramset_093[]
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 94
//
// ab FC-Version: ab ??? bis ???
// gefunden in : 0.91a
//
// STRUKTUR-DIFF zu 093:
// - add: param_StartLandChannel
// - add: param_LandingSpeed
//
// DEFINE-DIFF zu 093:
// etwas undurchsichtig...
// - add: #define EE_DUMMY
// - add: #define PID_HARDWARE_VERSION
//-----------------------------------------------
paramRevItem_t const paramset_094[] PROGMEM =
{
{ param_DUMMY , 114 }, // n-Bytes Fueller... keine Unterstuetzung fuer paramEdit
{ param_Name , 12 }, // char Name[12];
{ param_DUMMY , 1 }, // n-Bytes Fueller... keine Unterstuetzung fuer paramEdit
 
{ param_EOF , 0 } // END OF PARAM-LIST - MUST BE THE LAST!!
 
}; // end: paramset_094[]
 
 
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 95
//
// ab FC-Version: ab ??? bis ???
// gefunden in : 0.90L, 2.00a, , 2.00e
//
// STRUKTUR-DIFF zu 094:
// - rename: param_MaxHoehe -> param_HoeheChannel
// - rename: param_NaviGpsModeControl -> param_NaviGpsModeChannel
// - rename: param_NaviGpsACC -> param_NaviGpsA
// - rename: param_CareFreeModeControl -> param_CareFreeChannel
//
// DEFINE-DIFF zu 094:
// - keine Aenderung
//-----------------------------------------------
paramRevItem_t const paramset_095[] PROGMEM =
{
{ param_Revision , 1 }, // unsigned char Revision;
{ param_Kanalbelegung , 12 }, // unsigned char Kanalbelegung[12]; // GAS[0], GIER[1],NICK[2], ROLL[3], POTI1, POTI2, POTI3
{ param_GlobalConfig , 1 }, // unsigned char GlobalConfig; // 0x01=Höhenregler aktiv,0x02=Kompass aktiv, 0x04=GPS aktiv, 0x08=Heading Hold aktiv
{ param_Hoehe_MinGas , 1 }, // unsigned char Hoehe_MinGas; // Wert : 0-100
{ param_Luftdruck_D , 1 }, // unsigned char Luftdruck_D; // Wert : 0-250
{ param_HoeheChannel , 1 }, // unsigned char HoeheChannel; // Wert : 0-32
{ param_Hoehe_P , 1 }, // unsigned char Hoehe_P; // Wert : 0-32
{ param_Hoehe_Verstaerkung , 1 }, // unsigned char Hoehe_Verstaerkung; // Wert : 0-50
{ param_Hoehe_ACC_Wirkung , 1 }, // unsigned char Hoehe_ACC_Wirkung; // Wert : 0-250
{ param_Hoehe_HoverBand , 1 }, // unsigned char Hoehe_HoverBand; // Wert : 0-250
{ param_Hoehe_GPS_Z , 1 }, // unsigned char Hoehe_GPS_Z; // Wert : 0-250
{ param_Hoehe_StickNeutralPoint , 1 }, // unsigned char Hoehe_StickNeutralPoint;// Wert : 0-250
{ param_Stick_P , 1 }, // unsigned char Stick_P; // Wert : 1-6
{ param_Stick_D , 1 }, // unsigned char Stick_D; // Wert : 0-64
{ param_StickGier_P , 1 }, // unsigned char StickGier_P; // Wert : 1-20
{ param_Gas_Min , 1 }, // unsigned char Gas_Min; // Wert : 0-32
{ param_Gas_Max , 1 }, // unsigned char Gas_Max; // Wert : 33-250
{ param_GyroAccFaktor , 1 }, // unsigned char GyroAccFaktor; // Wert : 1-64
{ param_KompassWirkung , 1 }, // unsigned char KompassWirkung; // Wert : 0-32
{ param_Gyro_P , 1 }, // unsigned char Gyro_P; // Wert : 10-250
{ param_Gyro_I , 1 }, // unsigned char Gyro_I; // Wert : 0-250
{ param_Gyro_D , 1 }, // unsigned char Gyro_D; // Wert : 0-250
{ param_Gyro_Gier_P , 1 }, // unsigned char Gyro_Gier_P; // Wert : 10-250
{ param_Gyro_Gier_I , 1 }, // unsigned char Gyro_Gier_I; // Wert : 0-250
{ param_Gyro_Stability , 1 }, // unsigned char Gyro_Stability; // Wert : 0-16
{ param_UnterspannungsWarnung , 1 }, // unsigned char UnterspannungsWarnung; // Wert : 0-250
{ param_NotGas , 1 }, // unsigned char NotGas; // Wert : 0-250 //Gaswert bei Empängsverlust
{ param_NotGasZeit , 1 }, // unsigned char NotGasZeit; // Wert : 0-250 // Zeitbis auf NotGas geschaltet wird, wg. Rx-Problemen
{ param_Receiver , 1 }, // unsigned char Receiver; // 0= Summensignal, 1= Spektrum, 2 =Jeti, 3=ACT DSL, 4=ACT S3D
{ param_I_Faktor , 1 }, // unsigned char I_Faktor; // Wert : 0-250
{ param_UserParam1 , 1 }, // unsigned char UserParam1; // Wert : 0-250
{ param_UserParam2 , 1 }, // unsigned char UserParam2; // Wert : 0-250
{ param_UserParam3 , 1 }, // unsigned char UserParam3; // Wert : 0-250
{ param_UserParam4 , 1 }, // unsigned char UserParam4; // Wert : 0-250
{ param_ServoNickControl , 1 }, // unsigned char ServoNickControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoNickComp , 1 }, // unsigned char ServoNickComp; // Wert : 0-250 // Einfluss Gyro/Servo
{ param_ServoNickMin , 1 }, // unsigned char ServoNickMin; // Wert : 0-250 // Anschlag
{ param_ServoNickMax , 1 }, // unsigned char ServoNickMax; // Wert : 0-250 // Anschlag
{ param_ServoRollControl , 1 }, // unsigned char ServoRollControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoRollComp , 1 }, // unsigned char ServoRollComp; // Wert : 0-250
{ param_ServoRollMin , 1 }, // unsigned char ServoRollMin; // Wert : 0-250
{ param_ServoRollMax , 1 }, // unsigned char ServoRollMax; // Wert : 0-250
{ param_ServoNickRefresh , 1 }, // unsigned char ServoNickRefresh; // Speed of the Servo
{ param_ServoManualControlSpeed , 1 }, // unsigned char ServoManualControlSpeed;//
{ param_CamOrientation , 1 }, // unsigned char CamOrientation; //
{ param_Servo3 , 1 }, // unsigned char Servo3; // Value or mapping of the Servo Output
{ param_Servo4 , 1 }, // unsigned char Servo4; // Value or mapping of the Servo Output
{ param_Servo5 , 1 }, // unsigned char Servo5; // Value or mapping of the Servo Output
{ param_LoopGasLimit , 1 }, // unsigned char LoopGasLimit; // Wert: 0-250 max. Gas während Looping
{ param_LoopThreshold , 1 }, // unsigned char LoopThreshold; // Wert: 0-250 Schwelle für Stickausschlag
{ param_LoopHysterese , 1 }, // unsigned char LoopHysterese; // Wert: 0-250 Hysterese für Stickausschlag
{ param_AchsKopplung1 , 1 }, // unsigned char AchsKopplung1; // Wert: 0-250 Faktor, mit dem Gier die Achsen Roll und Nick koppelt (NickRollMitkopplung)
{ param_AchsKopplung2 , 1 }, // unsigned char AchsKopplung2; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_CouplingYawCorrection , 1 }, // unsigned char CouplingYawCorrection; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_WinkelUmschlagNick , 1 }, // unsigned char WinkelUmschlagNick; // Wert: 0-250 180°-Punkt
{ param_WinkelUmschlagRoll , 1 }, // unsigned char WinkelUmschlagRoll; // Wert: 0-250 180°-Punkt
{ param_GyroAccAbgleich , 1 }, // unsigned char GyroAccAbgleich; // 1/k (Koppel_ACC_Wirkung)
{ param_Driftkomp , 1 }, // unsigned char Driftkomp;
{ param_DynamicStability , 1 }, // unsigned char DynamicStability;
{ param_UserParam5 , 1 }, // unsigned char UserParam5; // Wert : 0-250
{ param_UserParam6 , 1 }, // unsigned char UserParam6; // Wert : 0-250
{ param_UserParam7 , 1 }, // unsigned char UserParam7; // Wert : 0-250
{ param_UserParam8 , 1 }, // unsigned char UserParam8; // Wert : 0-250
{ param_J16Bitmask , 1 }, // unsigned char J16Bitmask; // for the J16 Output
{ param_J16Timing , 1 }, // unsigned char J16Timing; // for the J16 Output
{ param_J17Bitmask , 1 }, // unsigned char J17Bitmask; // for the J17 Output
{ param_J17Timing , 1 }, // unsigned char J17Timing; // for the J17 Output
{ param_WARN_J16_Bitmask , 1 }, // unsigned char WARN_J16_Bitmask; // for the J16 Output
{ param_WARN_J17_Bitmask , 1 }, // unsigned char WARN_J17_Bitmask; // for the J17 Output
{ param_NaviOut1Parameter , 1 }, // unsigned char NaviOut1Parameter; // for the J16 Output
{ param_NaviGpsModeChannel , 1 }, // unsigned char NaviGpsModeChannel; // Parameters for the Naviboard
{ param_NaviGpsGain , 1 }, // unsigned char NaviGpsGain;
{ param_NaviGpsP , 1 }, // unsigned char NaviGpsP;
{ param_NaviGpsI , 1 }, // unsigned char NaviGpsI;
{ param_NaviGpsD , 1 }, // unsigned char NaviGpsD;
{ param_NaviGpsPLimit , 1 }, // unsigned char NaviGpsPLimit;
{ param_NaviGpsILimit , 1 }, // unsigned char NaviGpsILimit;
{ param_NaviGpsDLimit , 1 }, // unsigned char NaviGpsDLimit;
{ param_NaviGpsA , 1 }, // unsigned char NaviGpsA;
{ param_NaviGpsMinSat , 1 }, // unsigned char NaviGpsMinSat;
{ param_NaviStickThreshold , 1 }, // unsigned char NaviStickThreshold;
{ param_NaviWindCorrection , 1 }, // unsigned char NaviWindCorrection;
{ param_NaviAccCompensation , 1 }, // unsigned char NaviAccCompensation; // New since 0.86 -> was: SpeedCompensation
{ param_NaviOperatingRadius , 1 }, // unsigned char NaviOperatingRadius;
{ param_NaviAngleLimitation , 1 }, // unsigned char NaviAngleLimitation;
{ param_NaviPH_LoginTime , 1 }, // unsigned char NaviPH_LoginTime;
{ param_ExternalControl , 1 }, // unsigned char ExternalControl; // for serial Control
{ param_OrientationAngle , 1 }, // unsigned char OrientationAngle; // Where is the front-direction?
{ param_CareFreeChannel , 1 }, // unsigned char CareFreeChannel; // switch for CareFree
{ param_MotorSafetySwitch , 1 }, // unsigned char MotorSafetySwitch;
{ param_MotorSmooth , 1 }, // unsigned char MotorSmooth;
{ param_ComingHomeAltitude , 1 }, // unsigned char ComingHomeAltitude;
{ param_FailSafeTime , 1 }, // unsigned char FailSafeTime;
{ param_MaxAltitude , 1 }, // unsigned char MaxAltitude;
{ param_FailsafeChannel , 1 }, // unsigned char FailsafeChannel; // if the value of this channel is > 100, the MK reports "RC-Lost"
{ param_ServoFilterNick , 1 }, // unsigned char ServoFilterNick;
{ param_ServoFilterRoll , 1 }, // unsigned char ServoFilterRoll;
{ param_StartLandChannel , 1 }, // unsigned char StartLandChannel;
{ param_LandingSpeed , 1 }, // unsigned char LandingSpeed;
{ param_BitConfig , 1 }, // unsigned char BitConfig; // (war Loop-Cfg) Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
{ param_ServoCompInvert , 1 }, // unsigned char ServoCompInvert; // 0x01 = Nick, 0x02 = Roll, 0x04 = relative moving // WICHTIG!!! am Ende lassen
{ param_ExtraConfig , 1 }, // unsigned char ExtraConfig; // bitcodiert
{ param_GlobalConfig3 , 1 }, // unsigned char GlobalConfig3; // bitcodiert
{ param_Name , 12 }, // char Name[12];
{ param_crc , 1 }, // unsigned char crc; // must be the last byte!
 
{ param_EOF , 0 } // END OF PARAM-LIST - MUST BE THE LAST!!
 
}; // end: paramset_095[]
 
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 96
//
// ab FC-Version: ab ??? bis ???
// gefunden in: ???
//
// STRUKTUR-DIFF zu 095:
// - KEINE AENDERUNG der INTERNEN DATEN-STRUKTUR!
//
// DEFINE-DIFF zu 095:
// GlobalConfig3
// - add: #define CFG3_SERVO_NICK_COMP_OFF 0x80
//-----------------------------------------------
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 97
//
// ab FC-Version: ab ??? bis ???
// gefunden in: 2.02b
//
// STRUKTUR-DIFF zu 096:
// - add: param_CompassOffset
// - add: param_AutoLandingVoltage
//
// DEFINE-DIFF zu 096:
// - keine Aenderung
//-----------------------------------------------
paramRevItem_t const paramset_097[] PROGMEM =
{
{ param_Revision , 1 }, // unsigned char Revision;
{ param_Kanalbelegung , 12 }, // unsigned char Kanalbelegung[12]; // GAS[0], GIER[1],NICK[2], ROLL[3], POTI1, POTI2, POTI3
{ param_GlobalConfig , 1 }, // unsigned char GlobalConfig; // 0x01=Höhenregler aktiv,0x02=Kompass aktiv, 0x04=GPS aktiv, 0x08=Heading Hold aktiv
{ param_Hoehe_MinGas , 1 }, // unsigned char Hoehe_MinGas; // Wert : 0-100
{ param_Luftdruck_D , 1 }, // unsigned char Luftdruck_D; // Wert : 0-250
{ param_HoeheChannel , 1 }, // unsigned char HoeheChannel; // Wert : 0-32
{ param_Hoehe_P , 1 }, // unsigned char Hoehe_P; // Wert : 0-32
{ param_Hoehe_Verstaerkung , 1 }, // unsigned char Hoehe_Verstaerkung; // Wert : 0-50
{ param_Hoehe_ACC_Wirkung , 1 }, // unsigned char Hoehe_ACC_Wirkung; // Wert : 0-250
{ param_Hoehe_HoverBand , 1 }, // unsigned char Hoehe_HoverBand; // Wert : 0-250
{ param_Hoehe_GPS_Z , 1 }, // unsigned char Hoehe_GPS_Z; // Wert : 0-250
{ param_Hoehe_StickNeutralPoint , 1 }, // unsigned char Hoehe_StickNeutralPoint;// Wert : 0-250
{ param_Stick_P , 1 }, // unsigned char Stick_P; // Wert : 1-6
{ param_Stick_D , 1 }, // unsigned char Stick_D; // Wert : 0-64
{ param_StickGier_P , 1 }, // unsigned char StickGier_P; // Wert : 1-20
{ param_Gas_Min , 1 }, // unsigned char Gas_Min; // Wert : 0-32
{ param_Gas_Max , 1 }, // unsigned char Gas_Max; // Wert : 33-250
{ param_GyroAccFaktor , 1 }, // unsigned char GyroAccFaktor; // Wert : 1-64
{ param_KompassWirkung , 1 }, // unsigned char KompassWirkung; // Wert : 0-32
{ param_Gyro_P , 1 }, // unsigned char Gyro_P; // Wert : 10-250
{ param_Gyro_I , 1 }, // unsigned char Gyro_I; // Wert : 0-250
{ param_Gyro_D , 1 }, // unsigned char Gyro_D; // Wert : 0-250
{ param_Gyro_Gier_P , 1 }, // unsigned char Gyro_Gier_P; // Wert : 10-250
{ param_Gyro_Gier_I , 1 }, // unsigned char Gyro_Gier_I; // Wert : 0-250
{ param_Gyro_Stability , 1 }, // unsigned char Gyro_Stability; // Wert : 0-16
{ param_UnterspannungsWarnung , 1 }, // unsigned char UnterspannungsWarnung; // Wert : 0-250
{ param_NotGas , 1 }, // unsigned char NotGas; // Wert : 0-250 //Gaswert bei Empängsverlust
{ param_NotGasZeit , 1 }, // unsigned char NotGasZeit; // Wert : 0-250 // Zeitbis auf NotGas geschaltet wird, wg. Rx-Problemen
{ param_Receiver , 1 }, // unsigned char Receiver; // 0= Summensignal, 1= Spektrum, 2 =Jeti, 3=ACT DSL, 4=ACT S3D
{ param_I_Faktor , 1 }, // unsigned char I_Faktor; // Wert : 0-250
{ param_UserParam1 , 1 }, // unsigned char UserParam1; // Wert : 0-250
{ param_UserParam2 , 1 }, // unsigned char UserParam2; // Wert : 0-250
{ param_UserParam3 , 1 }, // unsigned char UserParam3; // Wert : 0-250
{ param_UserParam4 , 1 }, // unsigned char UserParam4; // Wert : 0-250
{ param_ServoNickControl , 1 }, // unsigned char ServoNickControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoNickComp , 1 }, // unsigned char ServoNickComp; // Wert : 0-250 // Einfluss Gyro/Servo
{ param_ServoNickMin , 1 }, // unsigned char ServoNickMin; // Wert : 0-250 // Anschlag
{ param_ServoNickMax , 1 }, // unsigned char ServoNickMax; // Wert : 0-250 // Anschlag
{ param_ServoRollControl , 1 }, // unsigned char ServoRollControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoRollComp , 1 }, // unsigned char ServoRollComp; // Wert : 0-250
{ param_ServoRollMin , 1 }, // unsigned char ServoRollMin; // Wert : 0-250
{ param_ServoRollMax , 1 }, // unsigned char ServoRollMax; // Wert : 0-250
{ param_ServoNickRefresh , 1 }, // unsigned char ServoNickRefresh; // Speed of the Servo
{ param_ServoManualControlSpeed , 1 }, // unsigned char ServoManualControlSpeed;//
{ param_CamOrientation , 1 }, // unsigned char CamOrientation; //
{ param_Servo3 , 1 }, // unsigned char Servo3; // Value or mapping of the Servo Output
{ param_Servo4 , 1 }, // unsigned char Servo4; // Value or mapping of the Servo Output
{ param_Servo5 , 1 }, // unsigned char Servo5; // Value or mapping of the Servo Output
{ param_LoopGasLimit , 1 }, // unsigned char LoopGasLimit; // Wert: 0-250 max. Gas während Looping
{ param_LoopThreshold , 1 }, // unsigned char LoopThreshold; // Wert: 0-250 Schwelle für Stickausschlag
{ param_LoopHysterese , 1 }, // unsigned char LoopHysterese; // Wert: 0-250 Hysterese für Stickausschlag
{ param_AchsKopplung1 , 1 }, // unsigned char AchsKopplung1; // Wert: 0-250 Faktor, mit dem Gier die Achsen Roll und Nick koppelt (NickRollMitkopplung)
{ param_AchsKopplung2 , 1 }, // unsigned char AchsKopplung2; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_CouplingYawCorrection , 1 }, // unsigned char CouplingYawCorrection; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_WinkelUmschlagNick , 1 }, // unsigned char WinkelUmschlagNick; // Wert: 0-250 180°-Punkt
{ param_WinkelUmschlagRoll , 1 }, // unsigned char WinkelUmschlagRoll; // Wert: 0-250 180°-Punkt
{ param_GyroAccAbgleich , 1 }, // unsigned char GyroAccAbgleich; // 1/k (Koppel_ACC_Wirkung)
{ param_Driftkomp , 1 }, // unsigned char Driftkomp;
{ param_DynamicStability , 1 }, // unsigned char DynamicStability;
{ param_UserParam5 , 1 }, // unsigned char UserParam5; // Wert : 0-250
{ param_UserParam6 , 1 }, // unsigned char UserParam6; // Wert : 0-250
{ param_UserParam7 , 1 }, // unsigned char UserParam7; // Wert : 0-250
{ param_UserParam8 , 1 }, // unsigned char UserParam8; // Wert : 0-250
{ param_J16Bitmask , 1 }, // unsigned char J16Bitmask; // for the J16 Output
{ param_J16Timing , 1 }, // unsigned char J16Timing; // for the J16 Output
{ param_J17Bitmask , 1 }, // unsigned char J17Bitmask; // for the J17 Output
{ param_J17Timing , 1 }, // unsigned char J17Timing; // for the J17 Output
{ param_WARN_J16_Bitmask , 1 }, // unsigned char WARN_J16_Bitmask; // for the J16 Output
{ param_WARN_J17_Bitmask , 1 }, // unsigned char WARN_J17_Bitmask; // for the J17 Output
{ param_NaviOut1Parameter , 1 }, // unsigned char NaviOut1Parameter; // for the J16 Output
{ param_NaviGpsModeChannel , 1 }, // unsigned char NaviGpsModeChannel; // Parameters for the Naviboard
{ param_NaviGpsGain , 1 }, // unsigned char NaviGpsGain;
{ param_NaviGpsP , 1 }, // unsigned char NaviGpsP;
{ param_NaviGpsI , 1 }, // unsigned char NaviGpsI;
{ param_NaviGpsD , 1 }, // unsigned char NaviGpsD;
{ param_NaviGpsPLimit , 1 }, // unsigned char NaviGpsPLimit;
{ param_NaviGpsILimit , 1 }, // unsigned char NaviGpsILimit;
{ param_NaviGpsDLimit , 1 }, // unsigned char NaviGpsDLimit;
{ param_NaviGpsA , 1 }, // unsigned char NaviGpsA;
{ param_NaviGpsMinSat , 1 }, // unsigned char NaviGpsMinSat;
{ param_NaviStickThreshold , 1 }, // unsigned char NaviStickThreshold;
{ param_NaviWindCorrection , 1 }, // unsigned char NaviWindCorrection;
{ param_NaviAccCompensation , 1 }, // unsigned char NaviAccCompensation; // New since 0.86 -> was: SpeedCompensation
{ param_NaviOperatingRadius , 1 }, // unsigned char NaviOperatingRadius;
{ param_NaviAngleLimitation , 1 }, // unsigned char NaviAngleLimitation;
{ param_NaviPH_LoginTime , 1 }, // unsigned char NaviPH_LoginTime;
{ param_ExternalControl , 1 }, // unsigned char ExternalControl; // for serial Control
{ param_OrientationAngle , 1 }, // unsigned char OrientationAngle; // Where is the front-direction?
{ param_CareFreeChannel , 1 }, // unsigned char CareFreeChannel; // switch for CareFree
{ param_MotorSafetySwitch , 1 }, // unsigned char MotorSafetySwitch;
{ param_MotorSmooth , 1 }, // unsigned char MotorSmooth;
{ param_ComingHomeAltitude , 1 }, // unsigned char ComingHomeAltitude;
{ param_FailSafeTime , 1 }, // unsigned char FailSafeTime;
{ param_MaxAltitude , 1 }, // unsigned char MaxAltitude;
{ param_FailsafeChannel , 1 }, // unsigned char FailsafeChannel; // if the value of this channel is > 100, the MK reports "RC-Lost"
{ param_ServoFilterNick , 1 }, // unsigned char ServoFilterNick;
{ param_ServoFilterRoll , 1 }, // unsigned char ServoFilterRoll;
{ param_StartLandChannel , 1 }, // unsigned char StartLandChannel;
{ param_LandingSpeed , 1 }, // unsigned char LandingSpeed;
{ param_CompassOffset , 1 }, // unsigned char CompassOffset;
{ param_AutoLandingVoltage , 1 }, // unsigned char AutoLandingVoltage; // in 0,1V 0 -> disabled
{ param_BitConfig , 1 }, // unsigned char BitConfig; // (war Loop-Cfg) Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
{ param_ServoCompInvert , 1 }, // unsigned char ServoCompInvert; // 0x01 = Nick, 0x02 = Roll, 0x04 = relative moving // WICHTIG!!! am Ende lassen
{ param_ExtraConfig , 1 }, // unsigned char ExtraConfig; // bitcodiert
{ param_GlobalConfig3 , 1 }, // unsigned char GlobalConfig3; // bitcodiert
{ param_Name , 12 }, // char Name[12];
{ param_crc , 1 }, // unsigned char crc; // must be the last byte!
 
{ param_EOF , 0 } // END OF PARAM-LIST - MUST BE THE LAST!!
 
}; // end: paramset_097[]
 
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 98
//
// ab FC-Version: ab ??? bis ???
// gefunden in: 2.03d
//
// STRUKTUR-DIFF zu 097:
// - add: param_ComingHomeVoltage
//
// DEFINE-DIFF zu 097:
// - keine Aenderung
//-----------------------------------------------
paramRevItem_t const paramset_098[] PROGMEM =
{
{ param_Revision , 1 }, // unsigned char Revision;
{ param_Kanalbelegung , 12 }, // unsigned char Kanalbelegung[12]; // GAS[0], GIER[1],NICK[2], ROLL[3], POTI1, POTI2, POTI3
{ param_GlobalConfig , 1 }, // unsigned char GlobalConfig; // 0x01=Höhenregler aktiv,0x02=Kompass aktiv, 0x04=GPS aktiv, 0x08=Heading Hold aktiv
{ param_Hoehe_MinGas , 1 }, // unsigned char Hoehe_MinGas; // Wert : 0-100
{ param_Luftdruck_D , 1 }, // unsigned char Luftdruck_D; // Wert : 0-250
{ param_HoeheChannel , 1 }, // unsigned char HoeheChannel; // Wert : 0-32
{ param_Hoehe_P , 1 }, // unsigned char Hoehe_P; // Wert : 0-32
{ param_Hoehe_Verstaerkung , 1 }, // unsigned char Hoehe_Verstaerkung; // Wert : 0-50
{ param_Hoehe_ACC_Wirkung , 1 }, // unsigned char Hoehe_ACC_Wirkung; // Wert : 0-250
{ param_Hoehe_HoverBand , 1 }, // unsigned char Hoehe_HoverBand; // Wert : 0-250
{ param_Hoehe_GPS_Z , 1 }, // unsigned char Hoehe_GPS_Z; // Wert : 0-250
{ param_Hoehe_StickNeutralPoint , 1 }, // unsigned char Hoehe_StickNeutralPoint;// Wert : 0-250
{ param_Stick_P , 1 }, // unsigned char Stick_P; // Wert : 1-6
{ param_Stick_D , 1 }, // unsigned char Stick_D; // Wert : 0-64
{ param_StickGier_P , 1 }, // unsigned char StickGier_P; // Wert : 1-20
{ param_Gas_Min , 1 }, // unsigned char Gas_Min; // Wert : 0-32
{ param_Gas_Max , 1 }, // unsigned char Gas_Max; // Wert : 33-250
{ param_GyroAccFaktor , 1 }, // unsigned char GyroAccFaktor; // Wert : 1-64
{ param_KompassWirkung , 1 }, // unsigned char KompassWirkung; // Wert : 0-32
{ param_Gyro_P , 1 }, // unsigned char Gyro_P; // Wert : 10-250
{ param_Gyro_I , 1 }, // unsigned char Gyro_I; // Wert : 0-250
{ param_Gyro_D , 1 }, // unsigned char Gyro_D; // Wert : 0-250
{ param_Gyro_Gier_P , 1 }, // unsigned char Gyro_Gier_P; // Wert : 10-250
{ param_Gyro_Gier_I , 1 }, // unsigned char Gyro_Gier_I; // Wert : 0-250
{ param_Gyro_Stability , 1 }, // unsigned char Gyro_Stability; // Wert : 0-16
{ param_UnterspannungsWarnung , 1 }, // unsigned char UnterspannungsWarnung; // Wert : 0-250
{ param_NotGas , 1 }, // unsigned char NotGas; // Wert : 0-250 //Gaswert bei Empängsverlust
{ param_NotGasZeit , 1 }, // unsigned char NotGasZeit; // Wert : 0-250 // Zeitbis auf NotGas geschaltet wird, wg. Rx-Problemen
{ param_Receiver , 1 }, // unsigned char Receiver; // 0= Summensignal, 1= Spektrum, 2 =Jeti, 3=ACT DSL, 4=ACT S3D
{ param_I_Faktor , 1 }, // unsigned char I_Faktor; // Wert : 0-250
{ param_UserParam1 , 1 }, // unsigned char UserParam1; // Wert : 0-250
{ param_UserParam2 , 1 }, // unsigned char UserParam2; // Wert : 0-250
{ param_UserParam3 , 1 }, // unsigned char UserParam3; // Wert : 0-250
{ param_UserParam4 , 1 }, // unsigned char UserParam4; // Wert : 0-250
{ param_ServoNickControl , 1 }, // unsigned char ServoNickControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoNickComp , 1 }, // unsigned char ServoNickComp; // Wert : 0-250 // Einfluss Gyro/Servo
{ param_ServoNickMin , 1 }, // unsigned char ServoNickMin; // Wert : 0-250 // Anschlag
{ param_ServoNickMax , 1 }, // unsigned char ServoNickMax; // Wert : 0-250 // Anschlag
{ param_ServoRollControl , 1 }, // unsigned char ServoRollControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoRollComp , 1 }, // unsigned char ServoRollComp; // Wert : 0-250
{ param_ServoRollMin , 1 }, // unsigned char ServoRollMin; // Wert : 0-250
{ param_ServoRollMax , 1 }, // unsigned char ServoRollMax; // Wert : 0-250
{ param_ServoNickRefresh , 1 }, // unsigned char ServoNickRefresh; // Speed of the Servo
{ param_ServoManualControlSpeed , 1 }, // unsigned char ServoManualControlSpeed;//
{ param_CamOrientation , 1 }, // unsigned char CamOrientation; //
{ param_Servo3 , 1 }, // unsigned char Servo3; // Value or mapping of the Servo Output
{ param_Servo4 , 1 }, // unsigned char Servo4; // Value or mapping of the Servo Output
{ param_Servo5 , 1 }, // unsigned char Servo5; // Value or mapping of the Servo Output
{ param_LoopGasLimit , 1 }, // unsigned char LoopGasLimit; // Wert: 0-250 max. Gas während Looping
{ param_LoopThreshold , 1 }, // unsigned char LoopThreshold; // Wert: 0-250 Schwelle für Stickausschlag
{ param_LoopHysterese , 1 }, // unsigned char LoopHysterese; // Wert: 0-250 Hysterese für Stickausschlag
{ param_AchsKopplung1 , 1 }, // unsigned char AchsKopplung1; // Wert: 0-250 Faktor, mit dem Gier die Achsen Roll und Nick koppelt (NickRollMitkopplung)
{ param_AchsKopplung2 , 1 }, // unsigned char AchsKopplung2; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_CouplingYawCorrection , 1 }, // unsigned char CouplingYawCorrection; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_WinkelUmschlagNick , 1 }, // unsigned char WinkelUmschlagNick; // Wert: 0-250 180°-Punkt
{ param_WinkelUmschlagRoll , 1 }, // unsigned char WinkelUmschlagRoll; // Wert: 0-250 180°-Punkt
{ param_GyroAccAbgleich , 1 }, // unsigned char GyroAccAbgleich; // 1/k (Koppel_ACC_Wirkung)
{ param_Driftkomp , 1 }, // unsigned char Driftkomp;
{ param_DynamicStability , 1 }, // unsigned char DynamicStability;
{ param_UserParam5 , 1 }, // unsigned char UserParam5; // Wert : 0-250
{ param_UserParam6 , 1 }, // unsigned char UserParam6; // Wert : 0-250
{ param_UserParam7 , 1 }, // unsigned char UserParam7; // Wert : 0-250
{ param_UserParam8 , 1 }, // unsigned char UserParam8; // Wert : 0-250
{ param_J16Bitmask , 1 }, // unsigned char J16Bitmask; // for the J16 Output
{ param_J16Timing , 1 }, // unsigned char J16Timing; // for the J16 Output
{ param_J17Bitmask , 1 }, // unsigned char J17Bitmask; // for the J17 Output
{ param_J17Timing , 1 }, // unsigned char J17Timing; // for the J17 Output
{ param_WARN_J16_Bitmask , 1 }, // unsigned char WARN_J16_Bitmask; // for the J16 Output
{ param_WARN_J17_Bitmask , 1 }, // unsigned char WARN_J17_Bitmask; // for the J17 Output
{ param_NaviOut1Parameter , 1 }, // unsigned char NaviOut1Parameter; // for the J16 Output
{ param_NaviGpsModeChannel , 1 }, // unsigned char NaviGpsModeChannel; // Parameters for the Naviboard
{ param_NaviGpsGain , 1 }, // unsigned char NaviGpsGain;
{ param_NaviGpsP , 1 }, // unsigned char NaviGpsP;
{ param_NaviGpsI , 1 }, // unsigned char NaviGpsI;
{ param_NaviGpsD , 1 }, // unsigned char NaviGpsD;
{ param_NaviGpsPLimit , 1 }, // unsigned char NaviGpsPLimit;
{ param_NaviGpsILimit , 1 }, // unsigned char NaviGpsILimit;
{ param_NaviGpsDLimit , 1 }, // unsigned char NaviGpsDLimit;
{ param_NaviGpsA , 1 }, // unsigned char NaviGpsA;
{ param_NaviGpsMinSat , 1 }, // unsigned char NaviGpsMinSat;
{ param_NaviStickThreshold , 1 }, // unsigned char NaviStickThreshold;
{ param_NaviWindCorrection , 1 }, // unsigned char NaviWindCorrection;
{ param_NaviAccCompensation , 1 }, // unsigned char NaviAccCompensation; // New since 0.86 -> was: SpeedCompensation
{ param_NaviOperatingRadius , 1 }, // unsigned char NaviOperatingRadius;
{ param_NaviAngleLimitation , 1 }, // unsigned char NaviAngleLimitation;
{ param_NaviPH_LoginTime , 1 }, // unsigned char NaviPH_LoginTime;
{ param_ExternalControl , 1 }, // unsigned char ExternalControl; // for serial Control
{ param_OrientationAngle , 1 }, // unsigned char OrientationAngle; // Where is the front-direction?
{ param_CareFreeChannel , 1 }, // unsigned char CareFreeChannel; // switch for CareFree
{ param_MotorSafetySwitch , 1 }, // unsigned char MotorSafetySwitch;
{ param_MotorSmooth , 1 }, // unsigned char MotorSmooth;
{ param_ComingHomeAltitude , 1 }, // unsigned char ComingHomeAltitude;
{ param_FailSafeTime , 1 }, // unsigned char FailSafeTime;
{ param_MaxAltitude , 1 }, // unsigned char MaxAltitude;
{ param_FailsafeChannel , 1 }, // unsigned char FailsafeChannel; // if the value of this channel is > 100, the MK reports "RC-Lost"
{ param_ServoFilterNick , 1 }, // unsigned char ServoFilterNick;
{ param_ServoFilterRoll , 1 }, // unsigned char ServoFilterRoll;
{ param_StartLandChannel , 1 }, // unsigned char StartLandChannel;
{ param_LandingSpeed , 1 }, // unsigned char LandingSpeed;
{ param_CompassOffset , 1 }, // unsigned char CompassOffset;
{ param_AutoLandingVoltage , 1 }, // unsigned char AutoLandingVoltage; // in 0,1V 0 -> disabled
{ param_ComingHomeVoltage , 1 }, // unsigned char ComingHomeVoltage; // in 0,1V 0 -> disabled
{ param_BitConfig , 1 }, // unsigned char BitConfig; // (war Loop-Cfg) Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
{ param_ServoCompInvert , 1 }, // unsigned char ServoCompInvert; // 0x01 = Nick, 0x02 = Roll, 0x04 = relative moving // WICHTIG!!! am Ende lassen
{ param_ExtraConfig , 1 }, // unsigned char ExtraConfig; // bitcodiert
{ param_GlobalConfig3 , 1 }, // unsigned char GlobalConfig3; // bitcodiert
{ param_Name , 12 }, // char Name[12];
{ param_crc , 1 }, // unsigned char crc; // must be the last byte!
 
{ param_EOF , 0 } // END OF PARAM-LIST - MUST BE THE LAST!!
 
}; // end: paramset_098[]
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 99
// keine Inormationen zu Rev. 99 vorhanden.
//
// Kommentar dazu von Holger Buss:
// "Die Revision 0.99 kannst Du ignorieren."
//-----------------------------------------------
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 100
//
// ab FC-Version: ab ??? bis 2.05e
// gefunden in: 2.05e
//
// STRUKTUR-DIFF zu 098:
// - del: NaviOut1Parameter
// - add: AutoPhotoDistance (ersetzt NaviOut1Parameter)
// - add: AutoPhotoAtitudes
// - add: SingleWpSpeed
//
// DEFINE-DIFF zu 098:
// - keine Aenderung
//
// ANMERKUNG OG 06.04.2014:
// Die Tabelle kann ggf. demnaechst geloescht werden
// da sie nur fuer eine kurze Zeit in Betaversionen
// vorhanden war!
//-----------------------------------------------
paramRevItem_t const paramset_100[] PROGMEM =
{
{ param_Revision , 1 }, // unsigned char Revision;
{ param_Kanalbelegung , 12 }, // unsigned char char Kanalbelegung[12]; // GAS[0], GIER[1],NICK[2], ROLL[3], POTI1, POTI2, POTI3
{ param_GlobalConfig , 1 }, // unsigned char char GlobalConfig; // 0x01=Höhenregler aktiv,0x02=Kompass aktiv, 0x04=GPS aktiv, 0x08=Heading Hold aktiv
{ param_Hoehe_MinGas , 1 }, // unsigned char char Hoehe_MinGas; // Wert : 0-100
{ param_Luftdruck_D , 1 }, // unsigned char char Luftdruck_D; // Wert : 0-250
{ param_HoeheChannel , 1 }, // unsigned char char HoeheChannel; // Wert : 0-32
{ param_Hoehe_P , 1 }, // unsigned char char Hoehe_P; // Wert : 0-32
{ param_Hoehe_Verstaerkung , 1 }, // unsigned char char Hoehe_Verstaerkung; // Wert : 0-50
{ param_Hoehe_ACC_Wirkung , 1 }, // unsigned char char Hoehe_ACC_Wirkung; // Wert : 0-250
{ param_Hoehe_HoverBand , 1 }, // unsigned char char Hoehe_HoverBand; // Wert : 0-250
{ param_Hoehe_GPS_Z , 1 }, // unsigned char char Hoehe_GPS_Z; // Wert : 0-250
{ param_Hoehe_StickNeutralPoint , 1 }, // unsigned char char Hoehe_StickNeutralPoint; // Wert : 0-250
{ param_Stick_P , 1 }, // unsigned char char Stick_P; // Wert : 1-6
{ param_Stick_D , 1 }, // unsigned char char Stick_D; // Wert : 0-64
{ param_StickGier_P , 1 }, // unsigned char char StickGier_P; // Wert : 1-20
{ param_Gas_Min , 1 }, // unsigned char char Gas_Min; // Wert : 0-32
{ param_Gas_Max , 1 }, // unsigned char char Gas_Max; // Wert : 33-250
{ param_GyroAccFaktor , 1 }, // unsigned char char GyroAccFaktor; // Wert : 1-64
{ param_KompassWirkung , 1 }, // unsigned char char KompassWirkung; // Wert : 0-32
{ param_Gyro_P , 1 }, // unsigned char char Gyro_P; // Wert : 10-250
{ param_Gyro_I , 1 }, // unsigned char char Gyro_I; // Wert : 0-250
{ param_Gyro_D , 1 }, // unsigned char char Gyro_D; // Wert : 0-250
{ param_Gyro_Gier_P , 1 }, // unsigned char char Gyro_Gier_P; // Wert : 10-250
{ param_Gyro_Gier_I , 1 }, // unsigned char char Gyro_Gier_I; // Wert : 0-250
{ param_Gyro_Stability , 1 }, // unsigned char char Gyro_Stability; // Wert : 0-16
{ param_UnterspannungsWarnung , 1 }, // unsigned char char UnterspannungsWarnung; // Wert : 0-250
{ param_NotGas , 1 }, // unsigned char char NotGas; // Wert : 0-250 //Gaswert bei Empängsverlust
{ param_NotGasZeit , 1 }, // unsigned char char NotGasZeit; // Wert : 0-250 // Zeitbis auf NotGas geschaltet wird, wg. Rx-Problemen
{ param_Receiver , 1 }, // unsigned char char Receiver; // 0= Summensignal, 1= Spektrum, 2 =Jeti, 3=ACT DSL, 4=ACT S3D
{ param_I_Faktor , 1 }, // unsigned char char I_Faktor; // Wert : 0-250
{ param_UserParam1 , 1 }, // unsigned char char UserParam1; // Wert : 0-250
{ param_UserParam2 , 1 }, // unsigned char char UserParam2; // Wert : 0-250
{ param_UserParam3 , 1 }, // unsigned char char UserParam3; // Wert : 0-250
{ param_UserParam4 , 1 }, // unsigned char char UserParam4; // Wert : 0-250
{ param_ServoNickControl , 1 }, // unsigned char char ServoNickControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoNickComp , 1 }, // unsigned char char ServoNickComp; // Wert : 0-250 // Einfluss Gyro/Servo
{ param_ServoNickMin , 1 }, // unsigned char char ServoNickMin; // Wert : 0-250 // Anschlag
{ param_ServoNickMax , 1 }, // unsigned char char ServoNickMax; // Wert : 0-250 // Anschlag
{ param_ServoRollControl , 1 }, // unsigned char char ServoRollControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoRollComp , 1 }, // unsigned char char ServoRollComp; // Wert : 0-250
{ param_ServoRollMin , 1 }, // unsigned char char ServoRollMin; // Wert : 0-250
{ param_ServoRollMax , 1 }, // unsigned char char ServoRollMax; // Wert : 0-250
{ param_ServoNickRefresh , 1 }, // unsigned char char ServoNickRefresh; // Speed of the Servo
{ param_ServoManualControlSpeed , 1 }, // unsigned char char ServoManualControlSpeed; //
{ param_CamOrientation , 1 }, // unsigned char char CamOrientation; //
{ param_Servo3 , 1 }, // unsigned char char Servo3; // Value or mapping of the Servo Output
{ param_Servo4 , 1 }, // unsigned char char Servo4; // Value or mapping of the Servo Output
{ param_Servo5 , 1 }, // unsigned char char Servo5; // Value or mapping of the Servo Output
{ param_LoopGasLimit , 1 }, // unsigned char char LoopGasLimit; // Wert: 0-250 max. Gas während Looping
{ param_LoopThreshold , 1 }, // unsigned char char LoopThreshold; // Wert: 0-250 Schwelle für Stickausschlag
{ param_LoopHysterese , 1 }, // unsigned char char LoopHysterese; // Wert: 0-250 Hysterese für Stickausschlag
{ param_AchsKopplung1 , 1 }, // unsigned char char AchsKopplung1; // Wert: 0-250 Faktor, mit dem Gier die Achsen Roll und Nick koppelt (NickRollMitkopplung)
{ param_AchsKopplung2 , 1 }, // unsigned char char AchsKopplung2; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_CouplingYawCorrection , 1 }, // unsigned char char CouplingYawCorrection; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_WinkelUmschlagNick , 1 }, // unsigned char char WinkelUmschlagNick; // Wert: 0-250 180°-Punkt
{ param_WinkelUmschlagRoll , 1 }, // unsigned char char WinkelUmschlagRoll; // Wert: 0-250 180°-Punkt
{ param_GyroAccAbgleich , 1 }, // unsigned char char GyroAccAbgleich; // 1/k (Koppel_ACC_Wirkung)
{ param_Driftkomp , 1 }, // unsigned char char Driftkomp;
{ param_DynamicStability , 1 }, // unsigned char char DynamicStability;
{ param_UserParam5 , 1 }, // unsigned char char UserParam5; // Wert : 0-250
{ param_UserParam6 , 1 }, // unsigned char char UserParam6; // Wert : 0-250
{ param_UserParam7 , 1 }, // unsigned char char UserParam7; // Wert : 0-250
{ param_UserParam8 , 1 }, // unsigned char char UserParam8; // Wert : 0-250
{ param_J16Bitmask , 1 }, // unsigned char char J16Bitmask; // for the J16 Output
{ param_J16Timing , 1 }, // unsigned char char J16Timing; // for the J16 Output
{ param_J17Bitmask , 1 }, // unsigned char char J17Bitmask; // for the J17 Output
{ param_J17Timing , 1 }, // unsigned char char J17Timing; // for the J17 Output
{ param_WARN_J16_Bitmask , 1 }, // unsigned char char WARN_J16_Bitmask; // for the J16 Output
{ param_WARN_J17_Bitmask , 1 }, // unsigned char char WARN_J17_Bitmask; // for the J17 Output
{ param_AutoPhotoDistance , 1 }, // unsigned char char AutoPhotoDistance; // Auto Photo // ab Rev. 100 (ehemals NaviOut1Parameter)
{ param_NaviGpsModeChannel , 1 }, // unsigned char char NaviGpsModeChannel; // Parameters for the Naviboard
{ param_NaviGpsGain , 1 }, // unsigned char char NaviGpsGain;
{ param_NaviGpsP , 1 }, // unsigned char char NaviGpsP;
{ param_NaviGpsI , 1 }, // unsigned char char NaviGpsI;
{ param_NaviGpsD , 1 }, // unsigned char char NaviGpsD;
{ param_NaviGpsPLimit , 1 }, // unsigned char char NaviGpsPLimit;
{ param_NaviGpsILimit , 1 }, // unsigned char char NaviGpsILimit;
{ param_NaviGpsDLimit , 1 }, // unsigned char char NaviGpsDLimit;
{ param_NaviGpsA , 1 }, // unsigned char char NaviGpsA;
{ param_NaviGpsMinSat , 1 }, // unsigned char char NaviGpsMinSat;
{ param_NaviStickThreshold , 1 }, // unsigned char char NaviStickThreshold;
{ param_NaviWindCorrection , 1 }, // unsigned char char NaviWindCorrection;
{ param_NaviAccCompensation , 1 }, // unsigned char char NaviAccCompensation; // New since 0.86 -> was: SpeedCompensation
{ param_NaviOperatingRadius , 1 }, // unsigned char char NaviOperatingRadius;
{ param_NaviAngleLimitation , 1 }, // unsigned char char NaviAngleLimitation;
{ param_NaviPH_LoginTime , 1 }, // unsigned char char NaviPH_LoginTime;
{ param_ExternalControl , 1 }, // unsigned char char ExternalControl; // for serial Control
{ param_OrientationAngle , 1 }, // unsigned char char OrientationAngle; // Where is the front-direction?
{ param_CareFreeChannel , 1 }, // unsigned char char CareFreeChannel; // switch for CareFree
{ param_MotorSafetySwitch , 1 }, // unsigned char char MotorSafetySwitch;
{ param_MotorSmooth , 1 }, // unsigned char char MotorSmooth;
{ param_ComingHomeAltitude , 1 }, // unsigned char char ComingHomeAltitude;
{ param_FailSafeTime , 1 }, // unsigned char char FailSafeTime;
{ param_MaxAltitude , 1 }, // unsigned char char MaxAltitude;
{ param_FailsafeChannel , 1 }, // unsigned char char FailsafeChannel; // if the value of this channel is > 100, the MK reports "RC-Lost"
{ param_ServoFilterNick , 1 }, // unsigned char char ServoFilterNick;
{ param_ServoFilterRoll , 1 }, // unsigned char char ServoFilterRoll;
{ param_StartLandChannel , 1 }, // unsigned char char StartLandChannel;
{ param_LandingSpeed , 1 }, // unsigned char char LandingSpeed;
{ param_CompassOffset , 1 }, // unsigned char char CompassOffset;
{ param_AutoLandingVoltage , 1 }, // unsigned char char AutoLandingVoltage; // in 0,1V 0 -> disabled
{ param_ComingHomeVoltage , 1 }, // unsigned char char ComingHomeVoltage; // in 0,1V 0 -> disabled
{ param_AutoPhotoAtitudes , 1 }, // unsigned char char AutoPhotoAtitudes; // ab Rev. 100
{ param_SingleWpSpeed , 1 }, // unsigned char char SingleWpSpeed; // ab Rev. 100
{ param_BitConfig , 1 }, // unsigned char char BitConfig; // (war Loop-Cfg) Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
{ param_ServoCompInvert , 1 }, // unsigned char char ServoCompInvert; // 0x01 = Nick, 0x02 = Roll, 0x04 = relative moving // WICHTIG!!! am Ende lassen
{ param_ExtraConfig , 1 }, // unsigned char char ExtraConfig; // bitcodiert
{ param_GlobalConfig3 , 1 }, // unsigned char char GlobalConfig3; // bitcodiert
{ param_Name , 12 }, // char Name[12];
{ param_crc , 1 }, // unsigned char char crc; // must be the last byte!
 
{ param_EOF , 0 } // END OF PARAM-LIST - MUST BE THE LAST!!
 
}; // end: paramset_100[]
 
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 101
//
// ab FC-Version: ab 2.05f bis 2.05f
// gefunden in: 2.05f
//
// STRUKTUR-DIFF zu 100:
// - add: Servo3OnValue
// - add: Servo3OffValue
// - add: Servo4OnValue
// - add: Servo4OffValue
//
// DEFINE-DIFF zu 100:
// - keine Aenderung
//
// ANMERKUNG OG 06.04.2014:
// Die Tabelle kann ggf. demnaechst geloescht werden
// da sie nur fuer eine einzige Betaversion
// vorhanden war!
//-----------------------------------------------
paramRevItem_t const paramset_101[] PROGMEM =
{
{ param_DUMMY , 123 }, // n-Bytes Fueller... keine Unterstuetzung fuer paramEdit
{ param_Name , 12 }, // char Name[12];
{ param_DUMMY , 1 }, // n-Bytes Fueller... keine Unterstuetzung fuer paramEdit
 
{ param_EOF , 0 } // END OF PARAM-LIST - MUST BE THE LAST!!
 
}; // end: paramset_101[]
 
 
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 102
//
// ab FC-Version: ab 2.05g bis ??? (min. 2.06b)
// gefunden in: 2.05g, 2.06a
//
// STRUKTUR-DIFF zu 101:
// - add: NaviMaxFlyingRange (ersetzt NaviOperatingRadius)
// - add: NaviDescendRange
// - del: NaviOperatingRadius
//
// DEFINE-DIFF zu 101:
// - del: CFG3_DPH_MAX_RADIUS
//-----------------------------------------------
paramRevItem_t const paramset_102[] PROGMEM =
{
{ param_Revision , 1 }, // unsigned char Revision;
{ param_Kanalbelegung , 12 }, // unsigned char char Kanalbelegung[12]; // GAS[0], GIER[1],NICK[2], ROLL[3], POTI1, POTI2, POTI3
{ param_GlobalConfig , 1 }, // unsigned char char GlobalConfig; // 0x01=Höhenregler aktiv,0x02=Kompass aktiv, 0x04=GPS aktiv, 0x08=Heading Hold aktiv
{ param_Hoehe_MinGas , 1 }, // unsigned char char Hoehe_MinGas; // Wert : 0-100
{ param_Luftdruck_D , 1 }, // unsigned char char Luftdruck_D; // Wert : 0-250
{ param_HoeheChannel , 1 }, // unsigned char char HoeheChannel; // Wert : 0-32
{ param_Hoehe_P , 1 }, // unsigned char char Hoehe_P; // Wert : 0-32
{ param_Hoehe_Verstaerkung , 1 }, // unsigned char char Hoehe_Verstaerkung; // Wert : 0-50
{ param_Hoehe_ACC_Wirkung , 1 }, // unsigned char char Hoehe_ACC_Wirkung; // Wert : 0-250
{ param_Hoehe_HoverBand , 1 }, // unsigned char char Hoehe_HoverBand; // Wert : 0-250
{ param_Hoehe_GPS_Z , 1 }, // unsigned char char Hoehe_GPS_Z; // Wert : 0-250
{ param_Hoehe_StickNeutralPoint , 1 }, // unsigned char char Hoehe_StickNeutralPoint; // Wert : 0-250
{ param_Stick_P , 1 }, // unsigned char char Stick_P; // Wert : 1-6
{ param_Stick_D , 1 }, // unsigned char char Stick_D; // Wert : 0-64
{ param_StickGier_P , 1 }, // unsigned char char StickGier_P; // Wert : 1-20
{ param_Gas_Min , 1 }, // unsigned char char Gas_Min; // Wert : 0-32
{ param_Gas_Max , 1 }, // unsigned char char Gas_Max; // Wert : 33-250
{ param_GyroAccFaktor , 1 }, // unsigned char char GyroAccFaktor; // Wert : 1-64
{ param_KompassWirkung , 1 }, // unsigned char char KompassWirkung; // Wert : 0-32
{ param_Gyro_P , 1 }, // unsigned char char Gyro_P; // Wert : 10-250
{ param_Gyro_I , 1 }, // unsigned char char Gyro_I; // Wert : 0-250
{ param_Gyro_D , 1 }, // unsigned char char Gyro_D; // Wert : 0-250
{ param_Gyro_Gier_P , 1 }, // unsigned char char Gyro_Gier_P; // Wert : 10-250
{ param_Gyro_Gier_I , 1 }, // unsigned char char Gyro_Gier_I; // Wert : 0-250
{ param_Gyro_Stability , 1 }, // unsigned char char Gyro_Stability; // Wert : 0-16
{ param_UnterspannungsWarnung , 1 }, // unsigned char char UnterspannungsWarnung; // Wert : 0-250
{ param_NotGas , 1 }, // unsigned char char NotGas; // Wert : 0-250 //Gaswert bei Empängsverlust
{ param_NotGasZeit , 1 }, // unsigned char char NotGasZeit; // Wert : 0-250 // Zeitbis auf NotGas geschaltet wird, wg. Rx-Problemen
{ param_Receiver , 1 }, // unsigned char char Receiver; // 0= Summensignal, 1= Spektrum, 2 =Jeti, 3=ACT DSL, 4=ACT S3D
{ param_I_Faktor , 1 }, // unsigned char char I_Faktor; // Wert : 0-250
{ param_UserParam1 , 1 }, // unsigned char char UserParam1; // Wert : 0-250
{ param_UserParam2 , 1 }, // unsigned char char UserParam2; // Wert : 0-250
{ param_UserParam3 , 1 }, // unsigned char char UserParam3; // Wert : 0-250
{ param_UserParam4 , 1 }, // unsigned char char UserParam4; // Wert : 0-250
{ param_ServoNickControl , 1 }, // unsigned char char ServoNickControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoNickComp , 1 }, // unsigned char char ServoNickComp; // Wert : 0-250 // Einfluss Gyro/Servo
{ param_ServoNickMin , 1 }, // unsigned char char ServoNickMin; // Wert : 0-250 // Anschlag
{ param_ServoNickMax , 1 }, // unsigned char char ServoNickMax; // Wert : 0-250 // Anschlag
{ param_ServoRollControl , 1 }, // unsigned char char ServoRollControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoRollComp , 1 }, // unsigned char char ServoRollComp; // Wert : 0-250
{ param_ServoRollMin , 1 }, // unsigned char char ServoRollMin; // Wert : 0-250
{ param_ServoRollMax , 1 }, // unsigned char char ServoRollMax; // Wert : 0-250
{ param_ServoNickRefresh , 1 }, // unsigned char char ServoNickRefresh; // Speed of the Servo
{ param_ServoManualControlSpeed , 1 }, // unsigned char char ServoManualControlSpeed; //
{ param_CamOrientation , 1 }, // unsigned char char CamOrientation; //
{ param_Servo3 , 1 }, // unsigned char char Servo3; // Value or mapping of the Servo Output
{ param_Servo4 , 1 }, // unsigned char char Servo4; // Value or mapping of the Servo Output
{ param_Servo5 , 1 }, // unsigned char char Servo5; // Value or mapping of the Servo Output
{ param_LoopGasLimit , 1 }, // unsigned char char LoopGasLimit; // Wert: 0-250 max. Gas während Looping
{ param_LoopThreshold , 1 }, // unsigned char char LoopThreshold; // Wert: 0-250 Schwelle für Stickausschlag
{ param_LoopHysterese , 1 }, // unsigned char char LoopHysterese; // Wert: 0-250 Hysterese für Stickausschlag
{ param_AchsKopplung1 , 1 }, // unsigned char char AchsKopplung1; // Wert: 0-250 Faktor, mit dem Gier die Achsen Roll und Nick koppelt (NickRollMitkopplung)
{ param_AchsKopplung2 , 1 }, // unsigned char char AchsKopplung2; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_CouplingYawCorrection , 1 }, // unsigned char char CouplingYawCorrection; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_WinkelUmschlagNick , 1 }, // unsigned char char WinkelUmschlagNick; // Wert: 0-250 180°-Punkt
{ param_WinkelUmschlagRoll , 1 }, // unsigned char char WinkelUmschlagRoll; // Wert: 0-250 180°-Punkt
{ param_GyroAccAbgleich , 1 }, // unsigned char char GyroAccAbgleich; // 1/k (Koppel_ACC_Wirkung)
{ param_Driftkomp , 1 }, // unsigned char char Driftkomp;
{ param_DynamicStability , 1 }, // unsigned char char DynamicStability;
{ param_UserParam5 , 1 }, // unsigned char char UserParam5; // Wert : 0-250
{ param_UserParam6 , 1 }, // unsigned char char UserParam6; // Wert : 0-250
{ param_UserParam7 , 1 }, // unsigned char char UserParam7; // Wert : 0-250
{ param_UserParam8 , 1 }, // unsigned char char UserParam8; // Wert : 0-250
{ param_J16Bitmask , 1 }, // unsigned char char J16Bitmask; // for the J16 Output
{ param_J16Timing , 1 }, // unsigned char char J16Timing; // for the J16 Output
{ param_J17Bitmask , 1 }, // unsigned char char J17Bitmask; // for the J17 Output
{ param_J17Timing , 1 }, // unsigned char char J17Timing; // for the J17 Output
{ param_WARN_J16_Bitmask , 1 }, // unsigned char char WARN_J16_Bitmask; // for the J16 Output
{ param_WARN_J17_Bitmask , 1 }, // unsigned char char WARN_J17_Bitmask; // for the J17 Output
{ param_AutoPhotoDistance , 1 }, // unsigned char char AutoPhotoDistance; // Auto Photo // ab Rev. 100 (ehemals NaviOut1Parameter)
{ param_NaviGpsModeChannel , 1 }, // unsigned char char NaviGpsModeChannel; // Parameters for the Naviboard
{ param_NaviGpsGain , 1 }, // unsigned char char NaviGpsGain;
{ param_NaviGpsP , 1 }, // unsigned char char NaviGpsP;
{ param_NaviGpsI , 1 }, // unsigned char char NaviGpsI;
{ param_NaviGpsD , 1 }, // unsigned char char NaviGpsD;
{ param_NaviGpsPLimit , 1 }, // unsigned char char NaviGpsPLimit;
{ param_NaviGpsILimit , 1 }, // unsigned char char NaviGpsILimit;
{ param_NaviGpsDLimit , 1 }, // unsigned char char NaviGpsDLimit;
{ param_NaviGpsA , 1 }, // unsigned char char NaviGpsA;
{ param_NaviGpsMinSat , 1 }, // unsigned char char NaviGpsMinSat;
{ param_NaviStickThreshold , 1 }, // unsigned char char NaviStickThreshold;
{ param_NaviWindCorrection , 1 }, // unsigned char char NaviWindCorrection;
{ param_NaviAccCompensation , 1 }, // unsigned char char NaviAccCompensation; // New since 0.86 -> was: SpeedCompensation
{ param_NaviMaxFlyingRange , 1 }, // unsigned char char NaviMaxFlyingRange; // in 10m
{ param_NaviAngleLimitation , 1 }, // unsigned char char NaviAngleLimitation;
{ param_NaviPH_LoginTime , 1 }, // unsigned char char NaviPH_LoginTime;
{ param_NaviDescendRange , 1 }, // unsigned char char NaviDescendRange;
{ param_ExternalControl , 1 }, // unsigned char char ExternalControl; // for serial Control
{ param_OrientationAngle , 1 }, // unsigned char char OrientationAngle; // Where is the front-direction?
{ param_CareFreeChannel , 1 }, // unsigned char char CareFreeChannel; // switch for CareFree
{ param_MotorSafetySwitch , 1 }, // unsigned char char MotorSafetySwitch;
{ param_MotorSmooth , 1 }, // unsigned char char MotorSmooth;
{ param_ComingHomeAltitude , 1 }, // unsigned char char ComingHomeAltitude;
{ param_FailSafeTime , 1 }, // unsigned char char FailSafeTime;
{ param_MaxAltitude , 1 }, // unsigned char char MaxAltitude;
{ param_FailsafeChannel , 1 }, // unsigned char char FailsafeChannel; // if the value of this channel is > 100, the MK reports "RC-Lost"
{ param_ServoFilterNick , 1 }, // unsigned char char ServoFilterNick;
{ param_ServoFilterRoll , 1 }, // unsigned char char ServoFilterRoll;
{ param_Servo3OnValue , 1 }, // unsigned char char Servo3OnValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo3OffValue , 1 }, // unsigned char char Servo3OffValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo4OnValue , 1 }, // unsigned char char Servo4OnValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo4OffValue , 1 }, // unsigned char char Servo4OffValue; // ab Rev. 101 (FC 2.05f)
{ param_StartLandChannel , 1 }, // unsigned char char StartLandChannel;
{ param_LandingSpeed , 1 }, // unsigned char char LandingSpeed;
{ param_CompassOffset , 1 }, // unsigned char char CompassOffset;
{ param_AutoLandingVoltage , 1 }, // unsigned char char AutoLandingVoltage; // in 0,1V 0 -> disabled
{ param_ComingHomeVoltage , 1 }, // unsigned char char ComingHomeVoltage; // in 0,1V 0 -> disabled
{ param_AutoPhotoAtitudes , 1 }, // unsigned char char AutoPhotoAtitudes; // ab Rev. 100
{ param_SingleWpSpeed , 1 }, // unsigned char char SingleWpSpeed; // ab Rev. 100
{ param_BitConfig , 1 }, // unsigned char char BitConfig; // (war Loop-Cfg) Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
{ param_ServoCompInvert , 1 }, // unsigned char char ServoCompInvert; // 0x01 = Nick, 0x02 = Roll, 0x04 = relative moving // WICHTIG!!! am Ende lassen
{ param_ExtraConfig , 1 }, // unsigned char char ExtraConfig; // bitcodiert
{ param_GlobalConfig3 , 1 }, // unsigned char char GlobalConfig3; // bitcodiert
{ param_Name , 12 }, // char Name[12];
{ param_crc , 1 }, // unsigned char char crc; // must be the last byte!
 
{ param_EOF , 0 } // END OF PARAM-LIST - MUST BE THE LAST!!
 
}; // end: paramset_102[]
 
 
 
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 103
//
// ab FC-Version: ab 2.07f bis ???
// gefunden in: 2.07f
//
// STRUKTUR-DIFF zu 102:
// keine
//
// DEFINE-DIFF zu 102:
// - chg: Hoehe_GPS_Z zu Hoehe_TiltCompensation
//-----------------------------------------------
paramRevItem_t const paramset_103[] PROGMEM =
{
{ param_Revision , 1 }, // unsigned char Revision;
{ param_Kanalbelegung , 12 }, // unsigned char char Kanalbelegung[12]; // GAS[0], GIER[1],NICK[2], ROLL[3], POTI1, POTI2, POTI3
{ param_GlobalConfig , 1 }, // unsigned char char GlobalConfig; // 0x01=Höhenregler aktiv,0x02=Kompass aktiv, 0x04=GPS aktiv, 0x08=Heading Hold aktiv
{ param_Hoehe_MinGas , 1 }, // unsigned char char Hoehe_MinGas; // Wert : 0-100
{ param_Luftdruck_D , 1 }, // unsigned char char Luftdruck_D; // Wert : 0-250
{ param_HoeheChannel , 1 }, // unsigned char char HoeheChannel; // Wert : 0-32
{ param_Hoehe_P , 1 }, // unsigned char char Hoehe_P; // Wert : 0-32
{ param_Hoehe_Verstaerkung , 1 }, // unsigned char char Hoehe_Verstaerkung; // Wert : 0-50
{ param_Hoehe_ACC_Wirkung , 1 }, // unsigned char char Hoehe_ACC_Wirkung; // Wert : 0-250
{ param_Hoehe_HoverBand , 1 }, // unsigned char char Hoehe_HoverBand; // Wert : 0-250
{ param_Hoehe_TiltCompensation , 1 }, // unsigned char char Hoehe_TiltCompensation; // Wert : 0-250
{ param_Hoehe_StickNeutralPoint , 1 }, // unsigned char char Hoehe_StickNeutralPoint; // Wert : 0-250
{ param_Stick_P , 1 }, // unsigned char char Stick_P; // Wert : 1-6
{ param_Stick_D , 1 }, // unsigned char char Stick_D; // Wert : 0-64
{ param_StickGier_P , 1 }, // unsigned char char StickGier_P; // Wert : 1-20
{ param_Gas_Min , 1 }, // unsigned char char Gas_Min; // Wert : 0-32
{ param_Gas_Max , 1 }, // unsigned char char Gas_Max; // Wert : 33-250
{ param_GyroAccFaktor , 1 }, // unsigned char char GyroAccFaktor; // Wert : 1-64
{ param_KompassWirkung , 1 }, // unsigned char char KompassWirkung; // Wert : 0-32
{ param_Gyro_P , 1 }, // unsigned char char Gyro_P; // Wert : 10-250
{ param_Gyro_I , 1 }, // unsigned char char Gyro_I; // Wert : 0-250
{ param_Gyro_D , 1 }, // unsigned char char Gyro_D; // Wert : 0-250
{ param_Gyro_Gier_P , 1 }, // unsigned char char Gyro_Gier_P; // Wert : 10-250
{ param_Gyro_Gier_I , 1 }, // unsigned char char Gyro_Gier_I; // Wert : 0-250
{ param_Gyro_Stability , 1 }, // unsigned char char Gyro_Stability; // Wert : 0-16
{ param_UnterspannungsWarnung , 1 }, // unsigned char char UnterspannungsWarnung; // Wert : 0-250
{ param_NotGas , 1 }, // unsigned char char NotGas; // Wert : 0-250 //Gaswert bei Empängsverlust
{ param_NotGasZeit , 1 }, // unsigned char char NotGasZeit; // Wert : 0-250 // Zeitbis auf NotGas geschaltet wird, wg. Rx-Problemen
{ param_Receiver , 1 }, // unsigned char char Receiver; // 0= Summensignal, 1= Spektrum, 2 =Jeti, 3=ACT DSL, 4=ACT S3D
{ param_I_Faktor , 1 }, // unsigned char char I_Faktor; // Wert : 0-250
{ param_UserParam1 , 1 }, // unsigned char char UserParam1; // Wert : 0-250
{ param_UserParam2 , 1 }, // unsigned char char UserParam2; // Wert : 0-250
{ param_UserParam3 , 1 }, // unsigned char char UserParam3; // Wert : 0-250
{ param_UserParam4 , 1 }, // unsigned char char UserParam4; // Wert : 0-250
{ param_ServoNickControl , 1 }, // unsigned char char ServoNickControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoNickComp , 1 }, // unsigned char char ServoNickComp; // Wert : 0-250 // Einfluss Gyro/Servo
{ param_ServoNickMin , 1 }, // unsigned char char ServoNickMin; // Wert : 0-250 // Anschlag
{ param_ServoNickMax , 1 }, // unsigned char char ServoNickMax; // Wert : 0-250 // Anschlag
{ param_ServoRollControl , 1 }, // unsigned char char ServoRollControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoRollComp , 1 }, // unsigned char char ServoRollComp; // Wert : 0-250
{ param_ServoRollMin , 1 }, // unsigned char char ServoRollMin; // Wert : 0-250
{ param_ServoRollMax , 1 }, // unsigned char char ServoRollMax; // Wert : 0-250
{ param_ServoNickRefresh , 1 }, // unsigned char char ServoNickRefresh; // Speed of the Servo
{ param_ServoManualControlSpeed , 1 }, // unsigned char char ServoManualControlSpeed; //
{ param_CamOrientation , 1 }, // unsigned char char CamOrientation; //
{ param_Servo3 , 1 }, // unsigned char char Servo3; // Value or mapping of the Servo Output
{ param_Servo4 , 1 }, // unsigned char char Servo4; // Value or mapping of the Servo Output
{ param_Servo5 , 1 }, // unsigned char char Servo5; // Value or mapping of the Servo Output
{ param_LoopGasLimit , 1 }, // unsigned char char LoopGasLimit; // Wert: 0-250 max. Gas während Looping
{ param_LoopThreshold , 1 }, // unsigned char char LoopThreshold; // Wert: 0-250 Schwelle für Stickausschlag
{ param_LoopHysterese , 1 }, // unsigned char char LoopHysterese; // Wert: 0-250 Hysterese für Stickausschlag
{ param_AchsKopplung1 , 1 }, // unsigned char char AchsKopplung1; // Wert: 0-250 Faktor, mit dem Gier die Achsen Roll und Nick koppelt (NickRollMitkopplung)
{ param_AchsKopplung2 , 1 }, // unsigned char char AchsKopplung2; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_CouplingYawCorrection , 1 }, // unsigned char char CouplingYawCorrection; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_WinkelUmschlagNick , 1 }, // unsigned char char WinkelUmschlagNick; // Wert: 0-250 180°-Punkt
{ param_WinkelUmschlagRoll , 1 }, // unsigned char char WinkelUmschlagRoll; // Wert: 0-250 180°-Punkt
{ param_GyroAccAbgleich , 1 }, // unsigned char char GyroAccAbgleich; // 1/k (Koppel_ACC_Wirkung)
{ param_Driftkomp , 1 }, // unsigned char char Driftkomp;
{ param_DynamicStability , 1 }, // unsigned char char DynamicStability;
{ param_UserParam5 , 1 }, // unsigned char char UserParam5; // Wert : 0-250
{ param_UserParam6 , 1 }, // unsigned char char UserParam6; // Wert : 0-250
{ param_UserParam7 , 1 }, // unsigned char char UserParam7; // Wert : 0-250
{ param_UserParam8 , 1 }, // unsigned char char UserParam8; // Wert : 0-250
{ param_J16Bitmask , 1 }, // unsigned char char J16Bitmask; // for the J16 Output
{ param_J16Timing , 1 }, // unsigned char char J16Timing; // for the J16 Output
{ param_J17Bitmask , 1 }, // unsigned char char J17Bitmask; // for the J17 Output
{ param_J17Timing , 1 }, // unsigned char char J17Timing; // for the J17 Output
{ param_WARN_J16_Bitmask , 1 }, // unsigned char char WARN_J16_Bitmask; // for the J16 Output
{ param_WARN_J17_Bitmask , 1 }, // unsigned char char WARN_J17_Bitmask; // for the J17 Output
{ param_AutoPhotoDistance , 1 }, // unsigned char char AutoPhotoDistance; // Auto Photo // ab Rev. 100 (ehemals NaviOut1Parameter)
{ param_NaviGpsModeChannel , 1 }, // unsigned char char NaviGpsModeChannel; // Parameters for the Naviboard
{ param_NaviGpsGain , 1 }, // unsigned char char NaviGpsGain;
{ param_NaviGpsP , 1 }, // unsigned char char NaviGpsP;
{ param_NaviGpsI , 1 }, // unsigned char char NaviGpsI;
{ param_NaviGpsD , 1 }, // unsigned char char NaviGpsD;
{ param_NaviGpsPLimit , 1 }, // unsigned char char NaviGpsPLimit;
{ param_NaviGpsILimit , 1 }, // unsigned char char NaviGpsILimit;
{ param_NaviGpsDLimit , 1 }, // unsigned char char NaviGpsDLimit;
{ param_NaviGpsA , 1 }, // unsigned char char NaviGpsA;
{ param_NaviGpsMinSat , 1 }, // unsigned char char NaviGpsMinSat;
{ param_NaviStickThreshold , 1 }, // unsigned char char NaviStickThreshold;
{ param_NaviWindCorrection , 1 }, // unsigned char char NaviWindCorrection;
{ param_NaviAccCompensation , 1 }, // unsigned char char NaviAccCompensation; // New since 0.86 -> was: SpeedCompensation
{ param_NaviMaxFlyingRange , 1 }, // unsigned char char NaviMaxFlyingRange; // in 10m
{ param_NaviAngleLimitation , 1 }, // unsigned char char NaviAngleLimitation;
{ param_NaviPH_LoginTime , 1 }, // unsigned char char NaviPH_LoginTime;
{ param_NaviDescendRange , 1 }, // unsigned char char NaviDescendRange;
{ param_ExternalControl , 1 }, // unsigned char char ExternalControl; // for serial Control
{ param_OrientationAngle , 1 }, // unsigned char char OrientationAngle; // Where is the front-direction?
{ param_CareFreeChannel , 1 }, // unsigned char char CareFreeChannel; // switch for CareFree
{ param_MotorSafetySwitch , 1 }, // unsigned char char MotorSafetySwitch;
{ param_MotorSmooth , 1 }, // unsigned char char MotorSmooth;
{ param_ComingHomeAltitude , 1 }, // unsigned char char ComingHomeAltitude;
{ param_FailSafeTime , 1 }, // unsigned char char FailSafeTime;
{ param_MaxAltitude , 1 }, // unsigned char char MaxAltitude;
{ param_FailsafeChannel , 1 }, // unsigned char char FailsafeChannel; // if the value of this channel is > 100, the MK reports "RC-Lost"
{ param_ServoFilterNick , 1 }, // unsigned char char ServoFilterNick;
{ param_ServoFilterRoll , 1 }, // unsigned char char ServoFilterRoll;
{ param_Servo3OnValue , 1 }, // unsigned char char Servo3OnValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo3OffValue , 1 }, // unsigned char char Servo3OffValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo4OnValue , 1 }, // unsigned char char Servo4OnValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo4OffValue , 1 }, // unsigned char char Servo4OffValue; // ab Rev. 101 (FC 2.05f)
{ param_StartLandChannel , 1 }, // unsigned char char StartLandChannel;
{ param_LandingSpeed , 1 }, // unsigned char char LandingSpeed;
{ param_CompassOffset , 1 }, // unsigned char char CompassOffset;
{ param_AutoLandingVoltage , 1 }, // unsigned char char AutoLandingVoltage; // in 0,1V 0 -> disabled
{ param_ComingHomeVoltage , 1 }, // unsigned char char ComingHomeVoltage; // in 0,1V 0 -> disabled
{ param_AutoPhotoAtitudes , 1 }, // unsigned char char AutoPhotoAtitudes; // ab Rev. 100
{ param_SingleWpSpeed , 1 }, // unsigned char char SingleWpSpeed; // ab Rev. 100
{ param_BitConfig , 1 }, // unsigned char char BitConfig; // (war Loop-Cfg) Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
{ param_ServoCompInvert , 1 }, // unsigned char char ServoCompInvert; // 0x01 = Nick, 0x02 = Roll, 0x04 = relative moving // WICHTIG!!! am Ende lassen
{ param_ExtraConfig , 1 }, // unsigned char char ExtraConfig; // bitcodiert
{ param_GlobalConfig3 , 1 }, // unsigned char char GlobalConfig3; // bitcodiert
{ param_Name , 12 }, // char Name[12];
{ param_crc , 1 }, // unsigned char char crc; // must be the last byte!
 
{ param_EOF , 0 } // END OF PARAM-LIST - MUST BE THE LAST!!
 
}; // end: paramset_103[]
 
 
 
//-----------------------------------------------
// FC-Parameter Revision: 104
//
// ab FC-Version: ab 2.09d bis ???
// gefunden in: 2.09d
//
// STRUKTUR-DIFF zu 103:
// add: LandingPulse
//
 
//-----------------------------------------------
paramRevItem_t const paramset_104[] PROGMEM =
{
{ param_Revision , 1 }, // unsigned char Revision;
{ param_Kanalbelegung , 12 }, // unsigned char char Kanalbelegung[12]; // GAS[0], GIER[1],NICK[2], ROLL[3], POTI1, POTI2, POTI3
{ param_GlobalConfig , 1 }, // unsigned char char GlobalConfig; // 0x01=Höhenregler aktiv,0x02=Kompass aktiv, 0x04=GPS aktiv, 0x08=Heading Hold aktiv
{ param_Hoehe_MinGas , 1 }, // unsigned char char Hoehe_MinGas; // Wert : 0-100
{ param_Luftdruck_D , 1 }, // unsigned char char Luftdruck_D; // Wert : 0-250
{ param_HoeheChannel , 1 }, // unsigned char char HoeheChannel; // Wert : 0-32
{ param_Hoehe_P , 1 }, // unsigned char char Hoehe_P; // Wert : 0-32
{ param_Hoehe_Verstaerkung , 1 }, // unsigned char char Hoehe_Verstaerkung; // Wert : 0-50
{ param_Hoehe_ACC_Wirkung , 1 }, // unsigned char char Hoehe_ACC_Wirkung; // Wert : 0-250
{ param_Hoehe_HoverBand , 1 }, // unsigned char char Hoehe_HoverBand; // Wert : 0-250
{ param_Hoehe_TiltCompensation , 1 }, // unsigned char char Hoehe_TiltCompensation; // Wert : 0-250
{ param_Hoehe_StickNeutralPoint , 1 }, // unsigned char char Hoehe_StickNeutralPoint; // Wert : 0-250
{ param_Stick_P , 1 }, // unsigned char char Stick_P; // Wert : 1-6
{ param_Stick_D , 1 }, // unsigned char char Stick_D; // Wert : 0-64
{ param_StickGier_P , 1 }, // unsigned char char StickGier_P; // Wert : 1-20
{ param_Gas_Min , 1 }, // unsigned char char Gas_Min; // Wert : 0-32
{ param_Gas_Max , 1 }, // unsigned char char Gas_Max; // Wert : 33-250
{ param_GyroAccFaktor , 1 }, // unsigned char char GyroAccFaktor; // Wert : 1-64
{ param_KompassWirkung , 1 }, // unsigned char char KompassWirkung; // Wert : 0-32
{ param_Gyro_P , 1 }, // unsigned char char Gyro_P; // Wert : 10-250
{ param_Gyro_I , 1 }, // unsigned char char Gyro_I; // Wert : 0-250
{ param_Gyro_D , 1 }, // unsigned char char Gyro_D; // Wert : 0-250
{ param_Gyro_Gier_P , 1 }, // unsigned char char Gyro_Gier_P; // Wert : 10-250
{ param_Gyro_Gier_I , 1 }, // unsigned char char Gyro_Gier_I; // Wert : 0-250
{ param_Gyro_Stability , 1 }, // unsigned char char Gyro_Stability; // Wert : 0-16
{ param_UnterspannungsWarnung , 1 }, // unsigned char char UnterspannungsWarnung; // Wert : 0-250
{ param_NotGas , 1 }, // unsigned char char NotGas; // Wert : 0-250 //Gaswert bei Empängsverlust
{ param_NotGasZeit , 1 }, // unsigned char char NotGasZeit; // Wert : 0-250 // Zeitbis auf NotGas geschaltet wird, wg. Rx-Problemen
{ param_Receiver , 1 }, // unsigned char char Receiver; // 0= Summensignal, 1= Spektrum, 2 =Jeti, 3=ACT DSL, 4=ACT S3D
{ param_I_Faktor , 1 }, // unsigned char char I_Faktor; // Wert : 0-250
{ param_UserParam1 , 1 }, // unsigned char char UserParam1; // Wert : 0-250
{ param_UserParam2 , 1 }, // unsigned char char UserParam2; // Wert : 0-250
{ param_UserParam3 , 1 }, // unsigned char char UserParam3; // Wert : 0-250
{ param_UserParam4 , 1 }, // unsigned char char UserParam4; // Wert : 0-250
{ param_ServoNickControl , 1 }, // unsigned char char ServoNickControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoNickComp , 1 }, // unsigned char char ServoNickComp; // Wert : 0-250 // Einfluss Gyro/Servo
{ param_ServoNickMin , 1 }, // unsigned char char ServoNickMin; // Wert : 0-250 // Anschlag
{ param_ServoNickMax , 1 }, // unsigned char char ServoNickMax; // Wert : 0-250 // Anschlag
{ param_ServoRollControl , 1 }, // unsigned char char ServoRollControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoRollComp , 1 }, // unsigned char char ServoRollComp; // Wert : 0-250
{ param_ServoRollMin , 1 }, // unsigned char char ServoRollMin; // Wert : 0-250
{ param_ServoRollMax , 1 }, // unsigned char char ServoRollMax; // Wert : 0-250
{ param_ServoNickRefresh , 1 }, // unsigned char char ServoNickRefresh; // Speed of the Servo
{ param_ServoManualControlSpeed , 1 }, // unsigned char char ServoManualControlSpeed; //
{ param_CamOrientation , 1 }, // unsigned char char CamOrientation; //
{ param_Servo3 , 1 }, // unsigned char char Servo3; // Value or mapping of the Servo Output
{ param_Servo4 , 1 }, // unsigned char char Servo4; // Value or mapping of the Servo Output
{ param_Servo5 , 1 }, // unsigned char char Servo5; // Value or mapping of the Servo Output
{ param_LoopGasLimit , 1 }, // unsigned char char LoopGasLimit; // Wert: 0-250 max. Gas während Looping
{ param_LoopThreshold , 1 }, // unsigned char char LoopThreshold; // Wert: 0-250 Schwelle für Stickausschlag
{ param_LoopHysterese , 1 }, // unsigned char char LoopHysterese; // Wert: 0-250 Hysterese für Stickausschlag
{ param_AchsKopplung1 , 1 }, // unsigned char char AchsKopplung1; // Wert: 0-250 Faktor, mit dem Gier die Achsen Roll und Nick koppelt (NickRollMitkopplung)
{ param_AchsKopplung2 , 1 }, // unsigned char char AchsKopplung2; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_CouplingYawCorrection , 1 }, // unsigned char char CouplingYawCorrection; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_WinkelUmschlagNick , 1 }, // unsigned char char WinkelUmschlagNick; // Wert: 0-250 180°-Punkt
{ param_WinkelUmschlagRoll , 1 }, // unsigned char char WinkelUmschlagRoll; // Wert: 0-250 180°-Punkt
{ param_GyroAccAbgleich , 1 }, // unsigned char char GyroAccAbgleich; // 1/k (Koppel_ACC_Wirkung)
{ param_Driftkomp , 1 }, // unsigned char char Driftkomp;
{ param_DynamicStability , 1 }, // unsigned char char DynamicStability;
{ param_UserParam5 , 1 }, // unsigned char char UserParam5; // Wert : 0-250
{ param_UserParam6 , 1 }, // unsigned char char UserParam6; // Wert : 0-250
{ param_UserParam7 , 1 }, // unsigned char char UserParam7; // Wert : 0-250
{ param_UserParam8 , 1 }, // unsigned char char UserParam8; // Wert : 0-250
{ param_J16Bitmask , 1 }, // unsigned char char J16Bitmask; // for the J16 Output
{ param_J16Timing , 1 }, // unsigned char char J16Timing; // for the J16 Output
{ param_J17Bitmask , 1 }, // unsigned char char J17Bitmask; // for the J17 Output
{ param_J17Timing , 1 }, // unsigned char char J17Timing; // for the J17 Output
{ param_WARN_J16_Bitmask , 1 }, // unsigned char char WARN_J16_Bitmask; // for the J16 Output
{ param_WARN_J17_Bitmask , 1 }, // unsigned char char WARN_J17_Bitmask; // for the J17 Output
{ param_AutoPhotoDistance , 1 }, // unsigned char char AutoPhotoDistance; // Auto Photo // ab Rev. 100 (ehemals NaviOut1Parameter)
{ param_NaviGpsModeChannel , 1 }, // unsigned char char NaviGpsModeChannel; // Parameters for the Naviboard
{ param_NaviGpsGain , 1 }, // unsigned char char NaviGpsGain;
{ param_NaviGpsP , 1 }, // unsigned char char NaviGpsP;
{ param_NaviGpsI , 1 }, // unsigned char char NaviGpsI;
{ param_NaviGpsD , 1 }, // unsigned char char NaviGpsD;
{ param_NaviGpsPLimit , 1 }, // unsigned char char NaviGpsPLimit;
{ param_NaviGpsILimit , 1 }, // unsigned char char NaviGpsILimit;
{ param_NaviGpsDLimit , 1 }, // unsigned char char NaviGpsDLimit;
{ param_NaviGpsA , 1 }, // unsigned char char NaviGpsA;
{ param_NaviGpsMinSat , 1 }, // unsigned char char NaviGpsMinSat;
{ param_NaviStickThreshold , 1 }, // unsigned char char NaviStickThreshold;
{ param_NaviWindCorrection , 1 }, // unsigned char char NaviWindCorrection;
{ param_NaviAccCompensation , 1 }, // unsigned char char NaviAccCompensation; // New since 0.86 -> was: SpeedCompensation
{ param_NaviMaxFlyingRange , 1 }, // unsigned char char NaviMaxFlyingRange; // in 10m
{ param_NaviAngleLimitation , 1 }, // unsigned char char NaviAngleLimitation;
{ param_NaviPH_LoginTime , 1 }, // unsigned char char NaviPH_LoginTime;
{ param_NaviDescendRange , 1 }, // unsigned char char NaviDescendRange;
{ param_ExternalControl , 1 }, // unsigned char char ExternalControl; // for serial Control
{ param_OrientationAngle , 1 }, // unsigned char char OrientationAngle; // Where is the front-direction?
{ param_CareFreeChannel , 1 }, // unsigned char char CareFreeChannel; // switch for CareFree
{ param_MotorSafetySwitch , 1 }, // unsigned char char MotorSafetySwitch;
{ param_MotorSmooth , 1 }, // unsigned char char MotorSmooth;
{ param_ComingHomeAltitude , 1 }, // unsigned char char ComingHomeAltitude;
{ param_FailSafeTime , 1 }, // unsigned char char FailSafeTime;
{ param_MaxAltitude , 1 }, // unsigned char char MaxAltitude;
{ param_FailsafeChannel , 1 }, // unsigned char char FailsafeChannel; // if the value of this channel is > 100, the MK reports "RC-Lost"
{ param_ServoFilterNick , 1 }, // unsigned char char ServoFilterNick;
{ param_ServoFilterRoll , 1 }, // unsigned char char ServoFilterRoll;
{ param_Servo3OnValue , 1 }, // unsigned char char Servo3OnValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo3OffValue , 1 }, // unsigned char char Servo3OffValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo4OnValue , 1 }, // unsigned char char Servo4OnValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo4OffValue , 1 }, // unsigned char char Servo4OffValue; // ab Rev. 101 (FC 2.05f)
{ param_StartLandChannel , 1 }, // unsigned char char StartLandChannel;
{ param_LandingSpeed , 1 }, // unsigned char char LandingSpeed;
{ param_CompassOffset , 1 }, // unsigned char char CompassOffset;
{ param_AutoLandingVoltage , 1 }, // unsigned char char AutoLandingVoltage; // in 0,1V 0 -> disabled
{ param_ComingHomeVoltage , 1 }, // unsigned char char ComingHomeVoltage; // in 0,1V 0 -> disabled
{ param_AutoPhotoAtitudes , 1 }, // unsigned char char AutoPhotoAtitudes; // ab Rev. 100
{ param_SingleWpSpeed , 1 }, // unsigned char char SingleWpSpeed; // ab Rev. 100
{ param_LandingPulse , 1 }, // unsigned char char LandingPulse; // ab Rev. 104 (FC 2.09d)
{ param_BitConfig , 1 }, // unsigned char char BitConfig; // (war Loop-Cfg) Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
{ param_ServoCompInvert , 1 }, // unsigned char char ServoCompInvert; // 0x01 = Nick, 0x02 = Roll, 0x04 = relative moving // WICHTIG!!! am Ende lassen
{ param_ExtraConfig , 1 }, // unsigned char char ExtraConfig; // bitcodiert
{ param_GlobalConfig3 , 1 }, // unsigned char char GlobalConfig3; // bitcodiert
{ param_Name , 12 }, // char Name[12];
{ param_crc , 1 }, // unsigned char char crc; // must be the last byte!
 
{ param_EOF , 0 } // END OF PARAM-LIST - MUST BE THE LAST!!
 
}; // end: paramset_104[]
 
//-----------------------------------------------
// FC-Parameter Revision: 105
//
// ab FC-Version: ab 2.09j bis ???
// gefunden in: 2.09j
//
// STRUKTUR-DIFF zu 104:
// add: unsigned char ServoFS_Pos[5];
//
 
//-----------------------------------------------
paramRevItem_t const paramset_105[] PROGMEM =
{
{ param_Revision , 1 }, // unsigned char Revision;
{ param_Kanalbelegung , 12 }, // unsigned char char Kanalbelegung[12]; // GAS[0], GIER[1],NICK[2], ROLL[3], POTI1, POTI2, POTI3
{ param_GlobalConfig , 1 }, // unsigned char char GlobalConfig; // 0x01=Höhenregler aktiv,0x02=Kompass aktiv, 0x04=GPS aktiv, 0x08=Heading Hold aktiv
{ param_Hoehe_MinGas , 1 }, // unsigned char char Hoehe_MinGas; // Wert : 0-100
{ param_Luftdruck_D , 1 }, // unsigned char char Luftdruck_D; // Wert : 0-250
{ param_HoeheChannel , 1 }, // unsigned char char HoeheChannel; // Wert : 0-32
{ param_Hoehe_P , 1 }, // unsigned char char Hoehe_P; // Wert : 0-32
{ param_Hoehe_Verstaerkung , 1 }, // unsigned char char Hoehe_Verstaerkung; // Wert : 0-50
{ param_Hoehe_ACC_Wirkung , 1 }, // unsigned char char Hoehe_ACC_Wirkung; // Wert : 0-250
{ param_Hoehe_HoverBand , 1 }, // unsigned char char Hoehe_HoverBand; // Wert : 0-250
{ param_Hoehe_TiltCompensation , 1 }, // unsigned char char Hoehe_TiltCompensation; // Wert : 0-250
{ param_Hoehe_StickNeutralPoint , 1 }, // unsigned char char Hoehe_StickNeutralPoint; // Wert : 0-250
{ param_Stick_P , 1 }, // unsigned char char Stick_P; // Wert : 1-6
{ param_Stick_D , 1 }, // unsigned char char Stick_D; // Wert : 0-64
{ param_StickGier_P , 1 }, // unsigned char char StickGier_P; // Wert : 1-20
{ param_Gas_Min , 1 }, // unsigned char char Gas_Min; // Wert : 0-32
{ param_Gas_Max , 1 }, // unsigned char char Gas_Max; // Wert : 33-250
{ param_GyroAccFaktor , 1 }, // unsigned char char GyroAccFaktor; // Wert : 1-64
{ param_KompassWirkung , 1 }, // unsigned char char KompassWirkung; // Wert : 0-32
{ param_Gyro_P , 1 }, // unsigned char char Gyro_P; // Wert : 10-250
{ param_Gyro_I , 1 }, // unsigned char char Gyro_I; // Wert : 0-250
{ param_Gyro_D , 1 }, // unsigned char char Gyro_D; // Wert : 0-250
{ param_Gyro_Gier_P , 1 }, // unsigned char char Gyro_Gier_P; // Wert : 10-250
{ param_Gyro_Gier_I , 1 }, // unsigned char char Gyro_Gier_I; // Wert : 0-250
{ param_Gyro_Stability , 1 }, // unsigned char char Gyro_Stability; // Wert : 0-16
{ param_UnterspannungsWarnung , 1 }, // unsigned char char UnterspannungsWarnung; // Wert : 0-250
{ param_NotGas , 1 }, // unsigned char char NotGas; // Wert : 0-250 //Gaswert bei Empängsverlust
{ param_NotGasZeit , 1 }, // unsigned char char NotGasZeit; // Wert : 0-250 // Zeitbis auf NotGas geschaltet wird, wg. Rx-Problemen
{ param_Receiver , 1 }, // unsigned char char Receiver; // 0= Summensignal, 1= Spektrum, 2 =Jeti, 3=ACT DSL, 4=ACT S3D
{ param_I_Faktor , 1 }, // unsigned char char I_Faktor; // Wert : 0-250
{ param_UserParam1 , 1 }, // unsigned char char UserParam1; // Wert : 0-250
{ param_UserParam2 , 1 }, // unsigned char char UserParam2; // Wert : 0-250
{ param_UserParam3 , 1 }, // unsigned char char UserParam3; // Wert : 0-250
{ param_UserParam4 , 1 }, // unsigned char char UserParam4; // Wert : 0-250
{ param_ServoNickControl , 1 }, // unsigned char char ServoNickControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoNickComp , 1 }, // unsigned char char ServoNickComp; // Wert : 0-250 // Einfluss Gyro/Servo
{ param_ServoNickMin , 1 }, // unsigned char char ServoNickMin; // Wert : 0-250 // Anschlag
{ param_ServoNickMax , 1 }, // unsigned char char ServoNickMax; // Wert : 0-250 // Anschlag
{ param_ServoRollControl , 1 }, // unsigned char char ServoRollControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoRollComp , 1 }, // unsigned char char ServoRollComp; // Wert : 0-250
{ param_ServoRollMin , 1 }, // unsigned char char ServoRollMin; // Wert : 0-250
{ param_ServoRollMax , 1 }, // unsigned char char ServoRollMax; // Wert : 0-250
{ param_ServoNickRefresh , 1 }, // unsigned char char ServoNickRefresh; // Speed of the Servo
{ param_ServoManualControlSpeed , 1 }, // unsigned char char ServoManualControlSpeed; //
{ param_CamOrientation , 1 }, // unsigned char char CamOrientation; //
{ param_Servo3 , 1 }, // unsigned char char Servo3; // Value or mapping of the Servo Output
{ param_Servo4 , 1 }, // unsigned char char Servo4; // Value or mapping of the Servo Output
{ param_Servo5 , 1 }, // unsigned char char Servo5; // Value or mapping of the Servo Output
{ param_LoopGasLimit , 1 }, // unsigned char char LoopGasLimit; // Wert: 0-250 max. Gas während Looping
{ param_LoopThreshold , 1 }, // unsigned char char LoopThreshold; // Wert: 0-250 Schwelle für Stickausschlag
{ param_LoopHysterese , 1 }, // unsigned char char LoopHysterese; // Wert: 0-250 Hysterese für Stickausschlag
{ param_AchsKopplung1 , 1 }, // unsigned char char AchsKopplung1; // Wert: 0-250 Faktor, mit dem Gier die Achsen Roll und Nick koppelt (NickRollMitkopplung)
{ param_AchsKopplung2 , 1 }, // unsigned char char AchsKopplung2; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_CouplingYawCorrection , 1 }, // unsigned char char CouplingYawCorrection; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_WinkelUmschlagNick , 1 }, // unsigned char char WinkelUmschlagNick; // Wert: 0-250 180°-Punkt
{ param_WinkelUmschlagRoll , 1 }, // unsigned char char WinkelUmschlagRoll; // Wert: 0-250 180°-Punkt
{ param_GyroAccAbgleich , 1 }, // unsigned char char GyroAccAbgleich; // 1/k (Koppel_ACC_Wirkung)
{ param_Driftkomp , 1 }, // unsigned char char Driftkomp;
{ param_DynamicStability , 1 }, // unsigned char char DynamicStability;
{ param_UserParam5 , 1 }, // unsigned char char UserParam5; // Wert : 0-250
{ param_UserParam6 , 1 }, // unsigned char char UserParam6; // Wert : 0-250
{ param_UserParam7 , 1 }, // unsigned char char UserParam7; // Wert : 0-250
{ param_UserParam8 , 1 }, // unsigned char char UserParam8; // Wert : 0-250
{ param_J16Bitmask , 1 }, // unsigned char char J16Bitmask; // for the J16 Output
{ param_J16Timing , 1 }, // unsigned char char J16Timing; // for the J16 Output
{ param_J17Bitmask , 1 }, // unsigned char char J17Bitmask; // for the J17 Output
{ param_J17Timing , 1 }, // unsigned char char J17Timing; // for the J17 Output
{ param_WARN_J16_Bitmask , 1 }, // unsigned char char WARN_J16_Bitmask; // for the J16 Output
{ param_WARN_J17_Bitmask , 1 }, // unsigned char char WARN_J17_Bitmask; // for the J17 Output
{ param_AutoPhotoDistance , 1 }, // unsigned char char AutoPhotoDistance; // Auto Photo // ab Rev. 100 (ehemals NaviOut1Parameter)
{ param_NaviGpsModeChannel , 1 }, // unsigned char char NaviGpsModeChannel; // Parameters for the Naviboard
{ param_NaviGpsGain , 1 }, // unsigned char char NaviGpsGain;
{ param_NaviGpsP , 1 }, // unsigned char char NaviGpsP;
{ param_NaviGpsI , 1 }, // unsigned char char NaviGpsI;
{ param_NaviGpsD , 1 }, // unsigned char char NaviGpsD;
{ param_NaviGpsPLimit , 1 }, // unsigned char char NaviGpsPLimit;
{ param_NaviGpsILimit , 1 }, // unsigned char char NaviGpsILimit;
{ param_NaviGpsDLimit , 1 }, // unsigned char char NaviGpsDLimit;
{ param_NaviGpsA , 1 }, // unsigned char char NaviGpsA;
{ param_NaviGpsMinSat , 1 }, // unsigned char char NaviGpsMinSat;
{ param_NaviStickThreshold , 1 }, // unsigned char char NaviStickThreshold;
{ param_NaviWindCorrection , 1 }, // unsigned char char NaviWindCorrection;
{ param_NaviAccCompensation , 1 }, // unsigned char char NaviAccCompensation; // New since 0.86 -> was: SpeedCompensation
{ param_NaviMaxFlyingRange , 1 }, // unsigned char char NaviMaxFlyingRange; // in 10m
{ param_NaviAngleLimitation , 1 }, // unsigned char char NaviAngleLimitation;
{ param_NaviPH_LoginTime , 1 }, // unsigned char char NaviPH_LoginTime;
{ param_NaviDescendRange , 1 }, // unsigned char char NaviDescendRange;
{ param_ExternalControl , 1 }, // unsigned char char ExternalControl; // for serial Control
{ param_OrientationAngle , 1 }, // unsigned char char OrientationAngle; // Where is the front-direction?
{ param_CareFreeChannel , 1 }, // unsigned char char CareFreeChannel; // switch for CareFree
{ param_MotorSafetySwitch , 1 }, // unsigned char char MotorSafetySwitch;
{ param_MotorSmooth , 1 }, // unsigned char char MotorSmooth;
{ param_ComingHomeAltitude , 1 }, // unsigned char char ComingHomeAltitude;
{ param_FailSafeTime , 1 }, // unsigned char char FailSafeTime;
{ param_MaxAltitude , 1 }, // unsigned char char MaxAltitude;
{ param_FailsafeChannel , 1 }, // unsigned char char FailsafeChannel; // if the value of this channel is > 100, the MK reports "RC-Lost"
{ param_ServoFilterNick , 1 }, // unsigned char char ServoFilterNick;
{ param_ServoFilterRoll , 1 }, // unsigned char char ServoFilterRoll;
{ param_Servo3OnValue , 1 }, // unsigned char char Servo3OnValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo3OffValue , 1 }, // unsigned char char Servo3OffValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo4OnValue , 1 }, // unsigned char char Servo4OnValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo4OffValue , 1 }, // unsigned char char Servo4OffValue; // ab Rev. 101 (FC 2.05f)
{ param_ServoFS_Pos , 5 }, // unsigned char ServoFS_Pos[5]; // ab Rev. 105 (FC 2.09i)
{ param_StartLandChannel , 1 }, // unsigned char char StartLandChannel;
{ param_LandingSpeed , 1 }, // unsigned char char LandingSpeed;
{ param_CompassOffset , 1 }, // unsigned char char CompassOffset;
{ param_AutoLandingVoltage , 1 }, // unsigned char char AutoLandingVoltage; // in 0,1V 0 -> disabled
{ param_ComingHomeVoltage , 1 }, // unsigned char char ComingHomeVoltage; // in 0,1V 0 -> disabled
{ param_AutoPhotoAtitudes , 1 }, // unsigned char char AutoPhotoAtitudes; // ab Rev. 100
{ param_SingleWpSpeed , 1 }, // unsigned char char SingleWpSpeed; // ab Rev. 100
{ param_LandingPulse , 1 }, // unsigned char char LandingPulse; // ab Rev. 104 (FC 2.09d)
{ param_BitConfig , 1 }, // unsigned char char BitConfig; // (war Loop-Cfg) Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
{ param_ServoCompInvert , 1 }, // unsigned char char ServoCompInvert; // 0x01 = Nick, 0x02 = Roll, 0x04 = relative moving // WICHTIG!!! am Ende lassen
{ param_ExtraConfig , 1 }, // unsigned char char ExtraConfig; // bitcodiert
{ param_GlobalConfig3 , 1 }, // unsigned char char GlobalConfig3; // bitcodiert
{ param_Name , 12 }, // char Name[12];
{ param_crc , 1 }, // unsigned char char crc; // must be the last byte!
 
{ param_EOF , 0 } // END OF PARAM-LIST - MUST BE THE LAST!!
 
}; // end: paramset_105[]
 
 
//-----------------------------------------------
// FC-Parameter Revision: 106
//
// ab FC-Version: ab 2.11a bis ???
// gefunden in: 2.11a
//
// STRUKTUR-DIFF zu 105:
// add: unsigned char SingleWpControlChannel;
// unsigned char MenuKeyChannel;
 
//
 
//-----------------------------------------------
paramRevItem_t const paramset_106[] PROGMEM =
{
{ param_Revision , 1 }, // unsigned char Revision;
{ param_Kanalbelegung , 12 }, // unsigned char char Kanalbelegung[12]; // GAS[0], GIER[1],NICK[2], ROLL[3], POTI1, POTI2, POTI3
{ param_GlobalConfig , 1 }, // unsigned char char GlobalConfig; // 0x01=Höhenregler aktiv,0x02=Kompass aktiv, 0x04=GPS aktiv, 0x08=Heading Hold aktiv
{ param_Hoehe_MinGas , 1 }, // unsigned char char Hoehe_MinGas; // Wert : 0-100
{ param_Luftdruck_D , 1 }, // unsigned char char Luftdruck_D; // Wert : 0-250
{ param_HoeheChannel , 1 }, // unsigned char char HoeheChannel; // Wert : 0-32
{ param_Hoehe_P , 1 }, // unsigned char char Hoehe_P; // Wert : 0-32
{ param_Hoehe_Verstaerkung , 1 }, // unsigned char char Hoehe_Verstaerkung; // Wert : 0-50
{ param_Hoehe_ACC_Wirkung , 1 }, // unsigned char char Hoehe_ACC_Wirkung; // Wert : 0-250
{ param_Hoehe_HoverBand , 1 }, // unsigned char char Hoehe_HoverBand; // Wert : 0-250
{ param_Hoehe_TiltCompensation , 1 }, // unsigned char char Hoehe_TiltCompensation; // Wert : 0-250
{ param_Hoehe_StickNeutralPoint , 1 }, // unsigned char char Hoehe_StickNeutralPoint; // Wert : 0-250
{ param_Stick_P , 1 }, // unsigned char char Stick_P; // Wert : 1-6
{ param_Stick_D , 1 }, // unsigned char char Stick_D; // Wert : 0-64
{ param_StickGier_P , 1 }, // unsigned char char StickGier_P; // Wert : 1-20
{ param_Gas_Min , 1 }, // unsigned char char Gas_Min; // Wert : 0-32
{ param_Gas_Max , 1 }, // unsigned char char Gas_Max; // Wert : 33-250
{ param_GyroAccFaktor , 1 }, // unsigned char char GyroAccFaktor; // Wert : 1-64
{ param_KompassWirkung , 1 }, // unsigned char char KompassWirkung; // Wert : 0-32
{ param_Gyro_P , 1 }, // unsigned char char Gyro_P; // Wert : 10-250
{ param_Gyro_I , 1 }, // unsigned char char Gyro_I; // Wert : 0-250
{ param_Gyro_D , 1 }, // unsigned char char Gyro_D; // Wert : 0-250
{ param_Gyro_Gier_P , 1 }, // unsigned char char Gyro_Gier_P; // Wert : 10-250
{ param_Gyro_Gier_I , 1 }, // unsigned char char Gyro_Gier_I; // Wert : 0-250
{ param_Gyro_Stability , 1 }, // unsigned char char Gyro_Stability; // Wert : 0-16
{ param_UnterspannungsWarnung , 1 }, // unsigned char char UnterspannungsWarnung; // Wert : 0-250
{ param_NotGas , 1 }, // unsigned char char NotGas; // Wert : 0-250 //Gaswert bei Empängsverlust
{ param_NotGasZeit , 1 }, // unsigned char char NotGasZeit; // Wert : 0-250 // Zeitbis auf NotGas geschaltet wird, wg. Rx-Problemen
{ param_Receiver , 1 }, // unsigned char char Receiver; // 0= Summensignal, 1= Spektrum, 2 =Jeti, 3=ACT DSL, 4=ACT S3D
{ param_I_Faktor , 1 }, // unsigned char char I_Faktor; // Wert : 0-250
{ param_UserParam1 , 1 }, // unsigned char char UserParam1; // Wert : 0-250
{ param_UserParam2 , 1 }, // unsigned char char UserParam2; // Wert : 0-250
{ param_UserParam3 , 1 }, // unsigned char char UserParam3; // Wert : 0-250
{ param_UserParam4 , 1 }, // unsigned char char UserParam4; // Wert : 0-250
{ param_ServoNickControl , 1 }, // unsigned char char ServoNickControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoNickComp , 1 }, // unsigned char char ServoNickComp; // Wert : 0-250 // Einfluss Gyro/Servo
{ param_ServoNickMin , 1 }, // unsigned char char ServoNickMin; // Wert : 0-250 // Anschlag
{ param_ServoNickMax , 1 }, // unsigned char char ServoNickMax; // Wert : 0-250 // Anschlag
{ param_ServoRollControl , 1 }, // unsigned char char ServoRollControl; // Wert : 0-250 // Stellung des Servos
{ param_ServoRollComp , 1 }, // unsigned char char ServoRollComp; // Wert : 0-250
{ param_ServoRollMin , 1 }, // unsigned char char ServoRollMin; // Wert : 0-250
{ param_ServoRollMax , 1 }, // unsigned char char ServoRollMax; // Wert : 0-250
{ param_ServoNickRefresh , 1 }, // unsigned char char ServoNickRefresh; // Speed of the Servo
{ param_ServoManualControlSpeed , 1 }, // unsigned char char ServoManualControlSpeed; //
{ param_CamOrientation , 1 }, // unsigned char char CamOrientation; //
{ param_Servo3 , 1 }, // unsigned char char Servo3; // Value or mapping of the Servo Output
{ param_Servo4 , 1 }, // unsigned char char Servo4; // Value or mapping of the Servo Output
{ param_Servo5 , 1 }, // unsigned char char Servo5; // Value or mapping of the Servo Output
{ param_LoopGasLimit , 1 }, // unsigned char char LoopGasLimit; // Wert: 0-250 max. Gas während Looping
{ param_LoopThreshold , 1 }, // unsigned char char LoopThreshold; // Wert: 0-250 Schwelle für Stickausschlag
{ param_LoopHysterese , 1 }, // unsigned char char LoopHysterese; // Wert: 0-250 Hysterese für Stickausschlag
{ param_AchsKopplung1 , 1 }, // unsigned char char AchsKopplung1; // Wert: 0-250 Faktor, mit dem Gier die Achsen Roll und Nick koppelt (NickRollMitkopplung)
{ param_AchsKopplung2 , 1 }, // unsigned char char AchsKopplung2; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_CouplingYawCorrection , 1 }, // unsigned char char CouplingYawCorrection; // Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
{ param_WinkelUmschlagNick , 1 }, // unsigned char char WinkelUmschlagNick; // Wert: 0-250 180°-Punkt
{ param_WinkelUmschlagRoll , 1 }, // unsigned char char WinkelUmschlagRoll; // Wert: 0-250 180°-Punkt
{ param_GyroAccAbgleich , 1 }, // unsigned char char GyroAccAbgleich; // 1/k (Koppel_ACC_Wirkung)
{ param_Driftkomp , 1 }, // unsigned char char Driftkomp;
{ param_DynamicStability , 1 }, // unsigned char char DynamicStability;
{ param_UserParam5 , 1 }, // unsigned char char UserParam5; // Wert : 0-250
{ param_UserParam6 , 1 }, // unsigned char char UserParam6; // Wert : 0-250
{ param_UserParam7 , 1 }, // unsigned char char UserParam7; // Wert : 0-250
{ param_UserParam8 , 1 }, // unsigned char char UserParam8; // Wert : 0-250
{ param_J16Bitmask , 1 }, // unsigned char char J16Bitmask; // for the J16 Output
{ param_J16Timing , 1 }, // unsigned char char J16Timing; // for the J16 Output
{ param_J17Bitmask , 1 }, // unsigned char char J17Bitmask; // for the J17 Output
{ param_J17Timing , 1 }, // unsigned char char J17Timing; // for the J17 Output
{ param_WARN_J16_Bitmask , 1 }, // unsigned char char WARN_J16_Bitmask; // for the J16 Output
{ param_WARN_J17_Bitmask , 1 }, // unsigned char char WARN_J17_Bitmask; // for the J17 Output
{ param_AutoPhotoDistance , 1 }, // unsigned char char AutoPhotoDistance; // Auto Photo // ab Rev. 100 (ehemals NaviOut1Parameter)
{ param_NaviGpsModeChannel , 1 }, // unsigned char char NaviGpsModeChannel; // Parameters for the Naviboard
{ param_NaviGpsGain , 1 }, // unsigned char char NaviGpsGain;
{ param_NaviGpsP , 1 }, // unsigned char char NaviGpsP;
{ param_NaviGpsI , 1 }, // unsigned char char NaviGpsI;
{ param_NaviGpsD , 1 }, // unsigned char char NaviGpsD;
{ param_NaviGpsPLimit , 1 }, // unsigned char char NaviGpsPLimit;
{ param_NaviGpsILimit , 1 }, // unsigned char char NaviGpsILimit;
{ param_NaviGpsDLimit , 1 }, // unsigned char char NaviGpsDLimit;
{ param_NaviGpsA , 1 }, // unsigned char char NaviGpsA;
{ param_NaviGpsMinSat , 1 }, // unsigned char char NaviGpsMinSat;
{ param_NaviStickThreshold , 1 }, // unsigned char char NaviStickThreshold;
{ param_NaviWindCorrection , 1 }, // unsigned char char NaviWindCorrection;
{ param_NaviAccCompensation , 1 }, // unsigned char char NaviAccCompensation; // New since 0.86 -> was: SpeedCompensation
{ param_NaviMaxFlyingRange , 1 }, // unsigned char char NaviMaxFlyingRange; // in 10m
{ param_NaviAngleLimitation , 1 }, // unsigned char char NaviAngleLimitation;
{ param_NaviPH_LoginTime , 1 }, // unsigned char char NaviPH_LoginTime;
{ param_NaviDescendRange , 1 }, // unsigned char char NaviDescendRange;
{ param_ExternalControl , 1 }, // unsigned char char ExternalControl; // for serial Control
{ param_OrientationAngle , 1 }, // unsigned char char OrientationAngle; // Where is the front-direction?
{ param_CareFreeChannel , 1 }, // unsigned char char CareFreeChannel; // switch for CareFree
{ param_MotorSafetySwitch , 1 }, // unsigned char char MotorSafetySwitch;
{ param_MotorSmooth , 1 }, // unsigned char char MotorSmooth;
{ param_ComingHomeAltitude , 1 }, // unsigned char char ComingHomeAltitude;
{ param_FailSafeTime , 1 }, // unsigned char char FailSafeTime;
{ param_MaxAltitude , 1 }, // unsigned char char MaxAltitude;
{ param_FailsafeChannel , 1 }, // unsigned char char FailsafeChannel; // if the value of this channel is > 100, the MK reports "RC-Lost"
{ param_ServoFilterNick , 1 }, // unsigned char char ServoFilterNick;
{ param_ServoFilterRoll , 1 }, // unsigned char char ServoFilterRoll;
{ param_Servo3OnValue , 1 }, // unsigned char char Servo3OnValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo3OffValue , 1 }, // unsigned char char Servo3OffValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo4OnValue , 1 }, // unsigned char char Servo4OnValue; // ab Rev. 101 (FC 2.05f)
{ param_Servo4OffValue , 1 }, // unsigned char char Servo4OffValue; // ab Rev. 101 (FC 2.05f)
{ param_ServoFS_Pos , 5 }, // unsigned char ServoFS_Pos[5]; // ab Rev. 105 (FC 2.09i)
{ param_StartLandChannel , 1 }, // unsigned char char StartLandChannel;
{ param_LandingSpeed , 1 }, // unsigned char char LandingSpeed;
{ param_CompassOffset , 1 }, // unsigned char char CompassOffset;
{ param_AutoLandingVoltage , 1 }, // unsigned char char AutoLandingVoltage; // in 0,1V 0 -> disabled
{ param_ComingHomeVoltage , 1 }, // unsigned char char ComingHomeVoltage; // in 0,1V 0 -> disabled
{ param_AutoPhotoAtitudes , 1 }, // unsigned char char AutoPhotoAtitudes; // ab Rev. 100
{ param_SingleWpSpeed , 1 }, // unsigned char char SingleWpSpeed; // ab Rev. 100
{ param_LandingPulse , 1 }, // unsigned char char LandingPulse; // ab Rev. 104 (FC 2.09d)
{ param_SingleWpControlChannel , 1 }, // unsigned char SingleWpControlChannel; // ab Rev. 106 (FC2.11a)
{ param_MenuKeyChannel , 1 }, // unsigned char MenuKeyChannel; // ab Rev. 106 (FC2.11a)
{ param_BitConfig , 1 }, // unsigned char char BitConfig; // (war Loop-Cfg) Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
{ param_ServoCompInvert , 1 }, // unsigned char char ServoCompInvert; // 0x01 = Nick, 0x02 = Roll, 0x04 = relative moving // WICHTIG!!! am Ende lassen
{ param_ExtraConfig , 1 }, // unsigned char char ExtraConfig; // bitcodiert
{ param_GlobalConfig3 , 1 }, // unsigned char char GlobalConfig3; // bitcodiert
{ param_Name , 12 }, // char Name[12];
{ param_crc , 1 }, // unsigned char char crc; // must be the last byte!
 
{ param_EOF , 0 } // END OF PARAM-LIST - MUST BE THE LAST!!
 
}; // end: paramset_106[]
 
 
 
 
//#############################################################################################
//# 1b. Zuweisungstabelle: Revision -> paramset_xxx
//#############################################################################################
 
typedef struct
{
unsigned char Revision;
const paramRevItem_t *RevisionTable;
} paramsetRevMap_t;
 
#define MAPEOF 255
 
 
//----------------------------------------------------------------
// Mappingtabelle zwischen FC-Revision und Paramset-Tabelle
//
// Anmerkung bzgl. Groesse:
// Angenommen man wuerde die Rev 97 bis 90 weglassen, dann
// wuerde man ca. 1 KByte sparen
//----------------------------------------------------------------
paramsetRevMap_t paramsetRevMap[] =
{
{ 106 , paramset_106 }, // 2.11a
{ 105 , paramset_105 }, // 2.09j
{ 104 , paramset_104 }, // 2.09d
{ 103 , paramset_103 }, // 2.07f
{ 102 , paramset_102 }, // 2.05g (bis min. 2.06b)
{ 101 , paramset_101 }, // 2.05f (eingeschraenkte Unterstuetzung - ) nur in einer einzigen Betaversion vorhanden!)
{ 100 , paramset_100 }, // 2.05e (Anmerkung OG 06.04.2014: ggf. spaeter loeschen um Platz zu sparen da diese Version nur in einigen wenigen Betaversionen vorhanden ist)
// Rev. 99: nicht vorhanden; ignorieren
{ 98 , paramset_098 }, // 2.03d
{ 97 , paramset_097 }, // 2.02b
{ 96 , paramset_095 }, // ??? (keine Struktur-Aenderung zu 095)
{ 95 , paramset_095 }, // 0.90L, 2.00a, 2.00e
{ 94 , paramset_094 }, // eingeschraenkte Unterstuetzung; 0.91a
{ 93 , paramset_093 }, // eingeschraenkte Unterstuetzung; 0.90e, 0.90g, 0.90j
{ 92 , paramset_093 }, // eingeschraenkte Unterstuetzung; 0.90d (keine Struktur-Aenderung zu 093)
{ 91 , paramset_091 }, // eingeschraenkte Unterstuetzung; 0.88m, 0.88n
{ 90 , paramset_091 }, // eingeschraenkte Unterstuetzung; 0.88e (keine Struktur-Aenderung zu 091)
 
{ MAPEOF, 0 } // END OF LIST - MUST BE THE LAST!!
};
 
 
 
 
//#############################################################################################
//# 2. Konfigurationstabelle der paramSubID's (Bit- und Bytefelder)
//#############################################################################################
 
//---------------------------------------
// struct: einzelnes Parameter-SubItem
//---------------------------------------
typedef struct
{
unsigned char paramSubID; // groesser/gleich PARAMSUBITEMS
unsigned char paramID; // -> mapping auf entsprechende paramID
unsigned char subType; // SUBTYPE_BIT oder SUBTYPE_BYTE
unsigned char subIndex; // bei SUBTYPE_BIT: Bitmask z.b. 0x02
// bei SUBTYPE_BYTE: index des Bytes (siehe param_Kanalbelegung)
unsigned char von_Revision; // ab welcher FC-Revision ist das SubItem vorhanden (0=immer)
unsigned char bis_Revision; // bis zu welcher FC-Revision ist das SubItem vorhanden (0=immer)
} paramSubItem_t;
 
 
//-----------------------------------------------------------------------------------------------------------------------------------------------------------------------
// +- von_Revision
// |
// +- paramSubID +- gehoert zu? +- Bit/Byte? +- Bit/Byte der paramID | +- bis_Revision
// | | | | | |
//--|-----------------------------------------|----------------------|--------------|----------------------------------|--|----------------------------------------------
paramSubItem_t const paramSubItem[] PROGMEM =
{
{ param_ServoCompInvert_SERVO_NICK_INV , param_ServoCompInvert, SUBTYPE_BIT, SERVO_NICK_INV , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: SVNick 0x01
{ param_ServoCompInvert_SERVO_ROLL_INV , param_ServoCompInvert, SUBTYPE_BIT, SERVO_ROLL_INV , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: SVRoll 0x02
{ param_ServoCompInvert_SERVO_RELATIVE , param_ServoCompInvert, SUBTYPE_BIT, SERVO_RELATIVE , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: SVRelMov 0x04
 
{ param_ExtraConfig_HeightLimit , param_ExtraConfig, SUBTYPE_BIT, CFG2_HEIGHT_LIMIT , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG2_HEIGHT_LIMIT 0x01
{ param_ExtraConfig_HeightVario , param_ExtraConfig, SUBTYPE_BITN, CFG2_HEIGHT_LIMIT , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG2_HEIGHT_LIMIT 0x01 negiert zu param_ExtraConfig_HeightLimit
{ param_ExtraConfig_VarioBeep , param_ExtraConfig, SUBTYPE_BIT, CFG2_VARIO_BEEP , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG2_VARIO_BEEP 0x02
{ param_ExtraConfig_SensitiveRc , param_ExtraConfig, SUBTYPE_BIT, CFG_SENSITIVE_RC , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_SENSITIVE_RC 0x04
{ param_ExtraConfig_33vReference , param_ExtraConfig, SUBTYPE_BIT, CFG_3_3V_REFERENCE , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_3_3V_REFERENCE 0x08
{ param_ExtraConfig_NoRcOffBeeping , param_ExtraConfig, SUBTYPE_BIT, CFG_NO_RCOFF_BEEPING , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_NO_RCOFF_BEEPING 0x10
{ param_ExtraConfig_GpsAid , param_ExtraConfig, SUBTYPE_BIT, CFG_GPS_AID , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_GPS_AID 0x20
{ param_ExtraConfig_LearnableCarefree , param_ExtraConfig, SUBTYPE_BIT, CFG_LEARNABLE_CAREFREE , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_LEARNABLE_CAREFREE 0x40
{ param_ExtraConfig_IgnoreMagErrAtStartup , param_ExtraConfig, SUBTYPE_BIT, CFG_IGNORE_MAG_ERR_AT_STARTUP , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_IGNORE_MAG_ERR_AT_STARTUP 0x80
 
{ param_BitConfig_LoopOben , param_BitConfig, SUBTYPE_BIT, CFG_LOOP_OBEN , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_LOOP_OBEN 0x01
{ param_BitConfig_LoopUnten , param_BitConfig, SUBTYPE_BIT, CFG_LOOP_UNTEN , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_LOOP_UNTEN 0x02
{ param_BitConfig_LoopLinks , param_BitConfig, SUBTYPE_BIT, CFG_LOOP_LINKS , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_LOOP_LINKS 0x04
{ param_BitConfig_LoopRechts , param_BitConfig, SUBTYPE_BIT, CFG_LOOP_RECHTS , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_LOOP_RECHTS 0x08
{ param_BitConfig_MotorBlink1 , param_BitConfig, SUBTYPE_BIT, CFG_MOTOR_BLINK1 , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_MOTOR_BLINK1 0x10
{ param_BitConfig_MotorOffLed1 , param_BitConfig, SUBTYPE_BIT, CFG_MOTOR_OFF_LED1 , 0,101}, // SUBTYPE_BIT - mk-data-structs.h: CFG_MOTOR_OFF_LED1 0x20
{ param_BitConfig_MotorOffLed2 , param_BitConfig, SUBTYPE_BIT, CFG_MOTOR_OFF_LED2 , 0,101}, // SUBTYPE_BIT - mk-data-structs.h: CFG_MOTOR_OFF_LED2 0x40
{ param_BitConfig_MotorBlink2 , param_BitConfig, SUBTYPE_BIT, CFG_MOTOR_BLINK2 , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_MOTOR_BLINK2 0x80
 
{ param_GlobalConfig3_NoSdCardNoStart , param_GlobalConfig3, SUBTYPE_BIT, CFG3_NO_SDCARD_NO_START , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG3_NO_SDCARD_NO_START 0x01
{ param_GlobalConfig3_DphMaxRadius , param_GlobalConfig3, SUBTYPE_BIT, CFG3_DPH_MAX_RADIUS , 0,100}, // SUBTYPE_BIT - mk-data-structs.h: CFG3_DPH_MAX_RADIUS 0x02
{ param_GlobalConfig3_VarioFailsafe , param_GlobalConfig3, SUBTYPE_BIT, CFG3_VARIO_FAILSAFE , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG3_VARIO_FAILSAFE 0x04
{ param_GlobalConfig3_MotorSwitchMode , param_GlobalConfig3, SUBTYPE_BIT, CFG3_MOTOR_SWITCH_MODE , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG3_MOTOR_SWITCH_MODE 0x08
{ param_GlobalConfig3_NoGpsFixNoStart , param_GlobalConfig3, SUBTYPE_BIT, CFG3_NO_GPSFIX_NO_START , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG3_NO_GPSFIX_NO_START 0x10
{ param_GlobalConfig3_UseNcForOut1 , param_GlobalConfig3, SUBTYPE_BIT, CFG3_USE_NC_FOR_OUT1 , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG3_USE_NC_FOR_OUT1 0x20
{ param_GlobalConfig3_SpeakAll , param_GlobalConfig3, SUBTYPE_BIT, CFG3_SPEAK_ALL , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG3_SPEAK_ALL 0x40
{ param_GlobalConfig3_ServoNickCompOff , param_GlobalConfig3, SUBTYPE_BIT, CFG3_SERVO_NICK_COMP_OFF , 96, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG3_SERVO_NICK_COMP_OFF 0x80
 
{ param_GlobalConfig_HoehenRegelung , param_GlobalConfig, SUBTYPE_BIT, CFG_HOEHENREGELUNG , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_HOEHENREGELUNG 0x01
{ param_GlobalConfig_HoehenSchalter , param_GlobalConfig, SUBTYPE_BIT, CFG_HOEHEN_SCHALTER , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_HOEHEN_SCHALTER 0x02
{ param_GlobalConfig_HeadingHold , param_GlobalConfig, SUBTYPE_BIT, CFG_HEADING_HOLD , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_HEADING_HOLD 0x04
{ param_GlobalConfig_KompassAktiv , param_GlobalConfig, SUBTYPE_BIT, CFG_KOMPASS_AKTIV , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_KOMPASS_AKTIV 0x08
{ param_GlobalConfig_KompassFix , param_GlobalConfig, SUBTYPE_BIT, CFG_KOMPASS_FIX , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_KOMPASS_FIX 0x10
{ param_GlobalConfig_GpsAktiv , param_GlobalConfig, SUBTYPE_BIT, CFG_GPS_AKTIV , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_GPS_AKTIV 0x20
{ param_GlobalConfig_AchsenkopplungAktiv , param_GlobalConfig, SUBTYPE_BIT, CFG_ACHSENKOPPLUNG_AKTIV , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_ACHSENKOPPLUNG_AKTIV 0x40
{ param_GlobalConfig_DrehratenBegrenzer , param_GlobalConfig, SUBTYPE_BIT, CFG_DREHRATEN_BEGRENZER , 0, 0}, // SUBTYPE_BIT - mk-data-structs.h: CFG_DREHRATEN_BEGRENZER 0x80
 
{ param_Kanalbelegung_Nick , param_Kanalbelegung, SUBTYPE_BYTE, 0 , 0, 0}, // -> Kanalbelegung[12]
{ param_Kanalbelegung_Roll , param_Kanalbelegung, SUBTYPE_BYTE, 1 , 0, 0},
{ param_Kanalbelegung_Gas , param_Kanalbelegung, SUBTYPE_BYTE, 2 , 0, 0},
{ param_Kanalbelegung_Gear , param_Kanalbelegung, SUBTYPE_BYTE, 3 , 0, 0},
{ param_Kanalbelegung_Poti1 , param_Kanalbelegung, SUBTYPE_BYTE, 4 , 0, 0},
{ param_Kanalbelegung_Poti2 , param_Kanalbelegung, SUBTYPE_BYTE, 5 , 0, 0},
{ param_Kanalbelegung_Poti3 , param_Kanalbelegung, SUBTYPE_BYTE, 6 , 0, 0},
{ param_Kanalbelegung_Poti4 , param_Kanalbelegung, SUBTYPE_BYTE, 7 , 0, 0},
{ param_Kanalbelegung_Poti5 , param_Kanalbelegung, SUBTYPE_BYTE, 8 , 0, 0},
{ param_Kanalbelegung_Poti6 , param_Kanalbelegung, SUBTYPE_BYTE, 9 , 0, 0},
{ param_Kanalbelegung_Poti7 , param_Kanalbelegung, SUBTYPE_BYTE, 10 , 0, 0},
{ param_Kanalbelegung_Poti8 , param_Kanalbelegung, SUBTYPE_BYTE, 11 , 0, 0},
 
{ param_CompassOffset_DisableDeclCalc , param_CompassOffset, SUBTYPE_BYTE, 0 , 0, 0}, // ist in Bit 8 und 7 von CompassOffset kodiert
{ param_ComingHomeOrientation , param_ServoCompInvert, SUBTYPE_BYTE, 0 , 0, 0}, // ist in Bit 5 und 4 von CervoCompInvert
 
{ param_ServoNickFailsave , param_ServoFS_Pos, SUBTYPE_BYTE, 0 , 0, 0},
{ param_ServoRollFailsave , param_ServoFS_Pos, SUBTYPE_BYTE, 1 , 0, 0},
{ param_Servo3Failsave , param_ServoFS_Pos, SUBTYPE_BYTE, 2 , 0, 0},
{ param_Servo4Failsave , param_ServoFS_Pos, SUBTYPE_BYTE, 3 , 0, 0},
{ param_Servo5Failsave , param_ServoFS_Pos, SUBTYPE_BYTE, 4 , 0, 0},
 
{ param_EOF , 0,0,0,0,0 } // END - MUST BE THE LAST!!
}; // end: paramSubItem[]
 
 
 
//#############################################################################################
//# 3a. Transformations-Tabelle
//#############################################################################################
 
//---------------------------------------
// struct: einzelnes Parameter-SubItem
//---------------------------------------
typedef struct
{
unsigned char paramID; // paramID oder paramSubID
unsigned char (*transformfunc)( uint8_t cmd, unsigned char value, unsigned char newvalue ); // Edit-Funktion (z.B. editGeneric()); cmd = CMD_EDIT oder CMD_SHORTVALUE
} paramTransform_t;
 
 
 
//---------------------------------------
// forward Deklarationen fuer transform
//---------------------------------------
unsigned char transform_CompassOffset_DisableDeclCalc( uint8_t cmd, unsigned char value, unsigned char newvalue );
unsigned char transform_ComingHomeOrientation( uint8_t cmd, unsigned char value, unsigned char newvalue );
//unsigned char transform_ValueACCZ( uint16_t cmd, uint16_t value, uint16_t newvalue );
 
//---------------------------------------
//---------------------------------------
paramTransform_t const paramTransform[] =
{
{ param_CompassOffset_DisableDeclCalc , &transform_CompassOffset_DisableDeclCalc },
{ param_ComingHomeOrientation , &transform_ComingHomeOrientation },
// { param_LandingPulse, &transform_ValueACCZ},
 
{ param_EOF , NULL } // END - MUST BE THE LAST!!
};
 
 
 
 
//#############################################################################################
//# 3b. Transformations-Funktionen
//#############################################################################################
 
//---------------------------------------
// transform_CompassOffset_DisableDeclCalc()
//
// PARAMETER:
// cmd : GETVALUE || SETVALUE
// value :
// newvalue: nur wenn cmd == SETVALUE
//
// Der true/false (Ja/Nein) Wert von param_CompassOffset_DisableDeclCalc
// ist in dem Byte von param_CompassOffset in den Bits 7 & 8 einkodiert.
//---------------------------------------
unsigned char transform_CompassOffset_DisableDeclCalc( uint8_t cmd, unsigned char value, unsigned char newvalue )
{
uint8_t bit7;
uint8_t bit8;
 
bit7 = ((value & 0x40) ? true : false);
bit8 = ((value & 0x80) ? true : false);
 
if( cmd == GETVALUE )
{
// Bit 8 == Bit 7: Disable dec. Calc AUS
// Bit 8 != Bit 7: Disable dec. Calc AN
value = ((bit8 == bit7) ? 0 : 1);
}
 
if( cmd == SETVALUE )
{
if( newvalue ) bit8 = !bit7; // Bit 8 != Bit 7: Disable dec. Calc AN
else bit8 = bit7; // Bit 8 == Bit 7: Disable dec. Calc AUS
 
if( bit8 ) value = (value | 0x80); // Bit 8 setzen
else value = (value & (0x80 ^ 0xff)); // Bit 8 loeschen
}
 
 
//lcdx_printf_at_P( 0, 7, MINVERS, 0,0 , PSTR(" %d => %d "), value, newvalue );
 
return value;
}
 
//---------------------------------------
// transform_ComingHomeOrientation()
//
// PARAMETER:
// cmd : GETVALUE || SETVALUE
// value :
// newvalue: nur wenn cmd == SETVALUE
//
//
// ist in dem Byte von param_ServoCompInvert in den Bits 4 & 5 einkodiert, Bits 1-3 bleiben unverändert
//---------------------------------------
 
uint8_t save =0; // globale Variable zum Sichern des alten Byte ServoCompInvert Wertes
 
unsigned char transform_ComingHomeOrientation( uint8_t cmd, unsigned char value, unsigned char newvalue )
{
 
if( cmd == GETVALUE )
{
save = value; // altes "gemeinsames" Byte ServoCompInvert sichern
value =((value & 0x18) >> 3); // CominghomeOrientation Bits nach rechts verschieben
}
 
if( cmd == SETVALUE )
{
value = ((newvalue << 3)|(save & 0x07)); // CominghomeOrientation Bits nach links verschieben und "alte" Bits 1-3 wieder dazufügen
}
 
 
//lcdx_printf_at_P( 0, 7, MINVERS, 0,0 , PSTR(" %d => %d "), value, newvalue );
 
return value;
}
 
//
//
////---------------------------------------
//// transform_ValueACCZ()
////
//// PARAMETER:
//// cmd : GETVALUE || SETVALUE
//// value :
//// newvalue: nur wenn cmd == SETVALUE
////
////
//// ACC Z Landing Pulse Wert für die Anzeige x 4
////---------------------------------------
//
//
//unsigned char transform_ValueACCZ( uint16_t cmd, uint16_t value, unint16_t newvalue )
//
//uint16_t save16 =0; // globale Variable zum Sichern des alten Byte ServoCompInvert Wertes
//
//{
// if( cmd == GETVALUE )
// {
// save16 = value; // altes Byte ACC Z Landing Pulse sichern
// value = (value * 4); // Wert x 4
// }
//
// if( cmd == SETVALUE )
// {
// value = (newvalue / 4); // Neuer Wert ACC Z Landingpulse /4
// }
//
//
// return value;
//}
 
//#############################################################################################
//# 4a. interne Zugriffsfunktionen
//#############################################################################################
 
//--------------------------------------------------------------
// INTERN
//
// Parameter:
// paramSubID: 'echter' Parameter zum Suchen in paramSubItem[] zum
// nachfolgeden Parameter geben das Suchergebnis zurueck
// und sind alle 0 wenn nichts gefunden wurde
//
// Rueckgabe:
// true/false
//--------------------------------------------------------------
unsigned char _paramset_getsubitemid( unsigned char paramSubID, unsigned char *paramID, unsigned char *subType, unsigned char *subIndex )
{
unsigned char id;
unsigned char *p;
unsigned char von_Revision;
unsigned char bis_Revision;
 
*paramID = 0;
*subType = 0;
*subIndex = 0;
 
p = (unsigned char *) paramSubItem;
 
while( true )
{
id = pgm_read_byte(p+0); // paramSubItem[..].paramSubID - die aktuelle paramSubID
 
if( (id == paramSubID) ) // gefunden?
{
von_Revision = pgm_read_byte(p+4); // paramSubItem[..].von_Revision;
bis_Revision = pgm_read_byte(p+5); // paramSubItem[..].bis_Revision;
 
// in aktueller FC-Revision vorhanden?
if( von_Revision && (MKVersion.paramsetRevision < von_Revision) ) return false; // passt nicht zur aktuellen FC-Revision -> exit
if( bis_Revision && (MKVersion.paramsetRevision > bis_Revision) ) return false; // passt nicht zur aktuellen FC-Revision -> exit
 
*paramID = pgm_read_byte(p+1); // paramSubItem[..].paramID;
*subType = pgm_read_byte(p+2); // paramSubItem[..].subType;
*subIndex = pgm_read_byte(p+3); // paramSubItem[..].subIndex;
return true;
}
 
if( id == param_EOF ) break;
 
p += sizeof( paramSubItem_t );
}
 
return false;
}
 
 
 
 
//--------------------------------------------------------------
// INTERN
//
// Parameter:
// retItemSize: false = offset zurueckgeben (normaler Modus)
// true = size von paramID zurueckgeben (fuer paramSize())
//--------------------------------------------------------------
unsigned char _paramset_getoffsetX( unsigned char paramID, unsigned char retItemSize, unsigned char *subType, unsigned char *subIndex )
{
unsigned char *p;
unsigned char offset;
unsigned char size;
unsigned char this_paramID;
unsigned char paramSubID;
 
*subType = SUBTYPE_NO; // =0
*subIndex = 0;
 
 
size = 0;
offset = param_NOTFOUND;
 
if( MKVersion.paramsetOK )
{
//-----------------------
// eine paramSubID wurde uebergeben
// -> ermittle zugehoerige paramID!
//-----------------------
if( (paramID >= param_SUBITEM) && (paramID != param_EOF) )
{
paramSubID = paramID;
if( !_paramset_getsubitemid( paramSubID, &paramID, subType, subIndex ) )
{
// keine paramID gefunden...
if( retItemSize ) return size; // size == 0
else return offset; // offset == param_NOTFOUND
}
}
 
 
//-----------------------
// paramID suchen
//-----------------------
offset = 0;
 
p = (unsigned char *) paramsetRevTable;
 
while( true )
{
this_paramID = pgm_read_byte(p); // die aktuelle paramID
size = pgm_read_byte(p+1); // size von paramID
 
// gefunden oder Ende
if( (this_paramID == paramID) || (this_paramID == param_EOF) )
{
break;
}
 
offset += size;
p += sizeof( paramRevItem_t );
}
 
 
// paramID nicht gefunden?
if( (this_paramID == param_EOF) && (paramID != param_EOF) )
{
offset = param_NOTFOUND;
size = 0;
}
 
}
 
if( retItemSize ) return size;
else return offset;
}
 
 
 
//--------------------------------------------------------------
// INTERN
//
// Parameter:
// retItemSize == false: offset zurueckgeben (normaler Modus)
// retItemSize == true : size von paramID zurueckgeben
// --> fuer paramSize()
//--------------------------------------------------------------
unsigned char _paramset_getoffset( unsigned char paramID, unsigned char retItemSize )
{
unsigned char subType;
unsigned char subIndex;
 
return _paramset_getoffsetX( paramID, retItemSize, &subType, &subIndex );
}
 
 
 
//--------------------------------------------------------------
// INTERN
//
// sucht/prueft ob eine Transform-Funktion vorhanden ist
//
// RUECKGABE:
// Index: (Num 0..n) auf paramTransform[]
// => param_EOF (=255) wenn keine transform-Funktion vorhanden
//--------------------------------------------------------------
unsigned char _paramset_gettransformIndex( unsigned char paramID )
{
unsigned char i;
 
i = 0;
while( paramTransform[i].paramID != param_EOF )
{
if( paramTransform[i].paramID == paramID ) return i;
if( paramTransform[i].paramID == param_EOF ) return param_EOF;
i++;
}
 
return param_EOF;
}
 
 
 
//#############################################################################################
//# 4b. oeffentliche Zugriffsfunktionen fuer paramID / paramSubID Elemente
//#
//# Hier sind die Getter/Setter um auf die einzelnen Werte der paramset-Struktur zuzugreifen.
//# Dazu muss vorher das richtige paramset initialisert worden sein!
//#
//# ACHTUNG!
//# Fuer die Daten wird direkt auf den RX-Buffer vom PKT zugegriffen!
//# ==> der Buffer darf NICHT durch andere Datenpakete bereits wieder ueberschrieben worden sein!
//#
//# Anmerkung:
//# Das obige 'Achtung' koennte man aendern durch eine Kopie des RX-Buffers. Das verbraucht
//# zusaetzlichen RAM-Speicher -> probieren wir es erstmal so...
//#############################################################################################
 
//--------------------------------------------------------------
// size = paramSize( paramID )
//--------------------------------------------------------------
unsigned char paramSize( unsigned char paramID )
{
return( _paramset_getoffset(paramID,true) ); // true = size (in Bytes) der paramID zurueckgeben (nicht offset)
}
 
 
 
//--------------------------------------------------------------
// exist = paramExist( paramID )
//
// Rueckgabe:
// true : die paramID existiert im aktuellen paramset
// false : die paramID existiert nicht
//--------------------------------------------------------------
unsigned char paramExist( unsigned char paramID )
{
return( (_paramset_getoffset(paramID,true) != 0) ); // true = size (in Bytes) der paramID zurueckgeben (nicht offset)
}
 
 
 
//--------------------------------------------------------------
// pointer = paramGet_p( paramID )
//
// ACHTUNG! Nicht faehig fuer Transform!
//
// RUECKGABE:
// pointer direkt auf~ein Byte im Parameterset
// (paramSubID nicht moeglich!)
//--------------------------------------------------------------
unsigned char *paramGet_p( unsigned char paramID )
{
unsigned char offset;
 
offset = _paramset_getoffset( paramID, false ); // false = offset zurueckgeben
 
if( offset != param_NOTFOUND )
{
return( (unsigned char *) (mkparamset + offset) ); // Rueckgabe: Pointer auf die Daten
}
return 0;
}
 
 
 
//--------------------------------------------------------------
// value = paramGet( paramID )
//
// holt den Wert von paramID. paramSubID's werden dabei
// unterstuetzt (Bit- und Bytefelder).
//
// Bei Bit-Feldern (z.B. GlobalConfig3) wird eine enstprechende
// Bit-Maskierung automatisch durchgefuehrt
// Ergebnis: true (=1) oder false (=0)false (=0)
//
// Bei Byte-Feldern (z.B. Kanalbelegung) wird der Wert des
// entsprechenden Byte's zurueckgegeben
//
// Hinweis: anhand des Rueckgabewertes kann nicht ueberprueft
// werden ob die paramID gefunden wurde bzw. existiert!
// -> ggf. erst mit paramExist() pruefen ob der Wert existiert!
//--------------------------------------------------------------
unsigned char paramGet( unsigned char paramID )
{
unsigned char offset;
unsigned char subType;
unsigned char subIndex;
unsigned char value;
unsigned char transformIdx;
 
offset = _paramset_getoffsetX( paramID, false, &subType, &subIndex ); // false = offset zurueckgeben
 
if( offset == param_NOTFOUND ) return false; // paramID nicht gefunden / nicht unterstuetzt
 
value = (unsigned char) *(mkparamset + offset); // offset Inhalt lesen (paramID)
 
//-------------------
// subIndex: Bit
//-------------------
if( subType == SUBTYPE_BIT )
{
value = ((value & subIndex) ? true : false); // Rueckgabe: true/false des gewaehlten Bit's
}
 
//-------------------
// subIndex: Bit negiert
//-------------------
if( subType == SUBTYPE_BITN )
{
value = ((value & subIndex) ? false : true); // Rueckgabe: true/false des gewaehlten Bit's (negiert)
}
 
//-------------------
// subIndex: Byte
//-------------------
if( subType == SUBTYPE_BYTE )
{
value = (unsigned char) *(mkparamset + (offset+subIndex)); // subIndex Inhalt lesen
}
 
 
//-------------------
// Transform
//-------------------
transformIdx = _paramset_gettransformIndex( paramID );
if( transformIdx != param_EOF )
{
value = paramTransform[transformIdx].transformfunc( GETVALUE, value, value);
}
 
return value; // ubyte zurueckgeben
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
unsigned char paramSet( unsigned char paramID, unsigned char newvalue )
{
unsigned char offset;
unsigned char subOffset = 0;
unsigned char subType;
unsigned char subIndex;
unsigned char byte;
unsigned char value;
unsigned char transformIdx;
 
value = newvalue;
 
offset = _paramset_getoffsetX( paramID, false, &subType, &subIndex ); // false = offset zurueckgeben
 
if( offset == param_NOTFOUND ) return false; // paramID nicht gefunden / nicht unterstuetzt
 
//-------------------
// subIndex: Bit
//-------------------
if( (subType == SUBTYPE_BIT) || (subType == SUBTYPE_BITN) )
{
byte = (unsigned char) *(mkparamset + offset); // offset Inhalt lesen
 
if( subType == SUBTYPE_BITN ) // SUBTYPE_BITN = negiertes BIT
value = (value ? false : true); // negieren
 
if(value) byte = byte | subIndex; // Bit setzen
else byte = byte & (subIndex ^ 0xff); // Bit loeschen
 
value = byte; // neues Value fuer das gesamte Byte (mit eingerechnetem BIT)
}
 
//-------------------
// subIndex: Byte
//-------------------
if( subType == SUBTYPE_BYTE )
{
subOffset = subIndex; // das 'verschobene' Byte (hier nur den Offset verschieben)
}
 
 
//-------------------
// Transform
//-------------------
transformIdx = _paramset_gettransformIndex( paramID );
if( transformIdx != param_EOF )
{
byte = (unsigned char) *(mkparamset + offset + subOffset); // offset Inhalt lesen
value = paramTransform[transformIdx].transformfunc( SETVALUE, byte, newvalue);
}
 
 
//-------------------
// Byte speichern
//-------------------
*(mkparamset + offset + subOffset) = value;
return true; // OK
}
 
 
 
 
//#############################################################################################
//# 4c. oeffentliche Zugriffsfunktionen fuer das gesamte Paramset (Int usw.)
//#
//# Init und Abfrage der Groesse in Bytes ddes gesamten Paramset's
//#############################################################################################
 
 
//--------------------------------------------------------------
// ok = paramsetInit( *pData )
//
// Ermittelt zu einer empfangenen Revision die passende paramset-Tabelle
// und setzt entsprechende Werte in MKVersion
//
// Wird von MK_load_setting() aufgerufen nach dem Einlesen der
// MK-Parameter (Setting-Request 'q')
//
// Parameter:
// *pData : Zeiger direkt auf den RX-Buffer des PKT
//
// Rueckgabe:
// true : OK - Paramset ist initialisert; die aktuelle FC-Revision
// steht in MKVersion.paramsetRevision
// false : Fehler - keine passende paramset-Tabelle gefunden
//--------------------------------------------------------------
unsigned char paramsetInit( unsigned char *pData )
{
unsigned char i;
unsigned char *p;
 
paramsetRevTable = 0;
mkparamset = 0;
MKVersion.paramsetOK = false;
MKVersion.paramsetRevision = 0;
MKVersion.mksetting = 0;
MKVersion.mksettingName[0] = 0;
 
//--------------------------------------------------
// pData == 0 -> nur 'reset' der Daten
//--------------------------------------------------
if( pData == 0 )
{
return 0;
}
 
//--------------------------------------------------
// diese beiden Werte koennen in jedem Fall gesetzt werden
// unabhaengig ob das gefundene Parameterset vom PKT
// unterstuetzt wird oder nicht
//--------------------------------------------------
MKVersion.mksetting = (unsigned char) *pData;
MKVersion.paramsetRevision = (unsigned char) *(pData + 1);
 
 
//--------------------------------------------------
// FC-Revision in paramsetRevMap suchen
//--------------------------------------------------
i = 0;
while( true )
{
if( (paramsetRevMap[i].Revision == MKVersion.paramsetRevision) || (paramsetRevMap[i].Revision == MAPEOF) )
break;
i++;
}
 
 
//--------------------------------------
// Revision nicht gefunden -> return 0
//--------------------------------------
if( paramsetRevMap[i].Revision == MAPEOF )
{
return 0;
}
 
//--------------------------------------
// Revision gefunden
//--------------------------------------
mkparamset = (unsigned char *) (pData + 1);
paramsetRevTable = (paramRevItem_t *) paramsetRevMap[i].RevisionTable;
MKVersion.paramsetOK = true;
 
 
//--------------------------------------
// den aktuellen Setting-Namen kopieren
// wird u.a. vom OSD verwendet
//--------------------------------------
p = paramGet_p( param_Name );
if( p ) memcpy( MKVersion.mksettingName, p, 12 );
 
return MKVersion.paramsetOK;
}
 
 
 
//--------------------------------------------------------------
// size = paramsetSize()
//
// Gibt die Groesse des gesamten aktuellen Parameterset's
// zurueck. Fuer Revision 098 z.B. 130 = 130 Bytes.
//
// Rueckgabe:
// =0 : Fehler; nicht unterstuetzte FC-Revision oder nicht
// initialisiert
//--------------------------------------------------------------
unsigned char paramsetSize( void )
{
if( MKVersion.paramsetOK )
return _paramset_getoffset( param_EOF, false ); // false = offset zurueckgeben; der offset von param_EOF entspricht der Groesse des paramSet's!
else
return 0;
}
 
 
 
 
 
//#############################################################################################
//# x. TEST / DEBUG
//#############################################################################################
 
//--------------------------------------------------------------
// TEST / DEBUG
//--------------------------------------------------------------
#ifdef DEBUG_PARAMSET
void paramsetDEBUG( void )
{
lcd_cls();
 
//lcdx_printp_at( 0, 0, PSTR("NEW PARAM TEST..."), MNORMAL, 0,0);
lcd_printp_at(12, 7, strGet(ENDE), MNORMAL); // Keyline
 
//memcpy( &MKVersion.NCVersion, (Version_t *) (pRxData), sizeof(MKVersion_t) );
 
/*
 
typedef struct
{
Version_t NCVersion; //
Version_t FCVersion; //
unsigned char paramsetRevision; // von der FC
unsigned char paramsetOk; // true wenn Revision in paramset.c vorhanden
} MKVersion_t;
 
 
//-------------------------------------
// zur Orientierung: Version_t
//-------------------------------------
//typedef struct
//{
// unsigned char SWMajor;
// unsigned char SWMinor;
// unsigned char ProtoMajor;
// unsigned char ProtoMinor;
// unsigned char SWPatch;
// unsigned char HardwareError[5];
//} __attribute__((packed)) Version_t;
*/
 
//setting = MK_Setting_load( 0xff, 20); // aktuelles MK Setting ermitteln
MK_Setting_load( 0xff, 20); // aktuelles MK Setting ermitteln
 
//----------------------------------
// Anzeige: FC/NC Version
//----------------------------------
lcdx_printp_at( 0, 0, PSTR("FC:"), MNORMAL, 0,0);
MKVersion_print_at( 3, 0, FC, MNORMAL, 0,0);
 
lcdx_printp_at( 13, 0, PSTR("NC:"), MNORMAL, 0,0);
MKVersion_print_at( 16, 0, NC, MNORMAL, 0,0);
 
 
//----------------------------------
// Anzeige: FC Revision
//----------------------------------
lcd_printf_at_P( 0, 1, MNORMAL, PSTR("Rev: %03u"), MKVersion.paramsetRevision );
if( MKVersion.paramsetOK )
lcdx_printp_at( 8, 1, PSTR(" ok!"), MINVERS, 0,0);
else
lcdx_printp_at( 8, 1, PSTR(" err"), MINVERS, 0,0);
 
// Size von paramset
lcd_printf_at_P( 13, 1, MNORMAL, PSTR("Size=%3u"), paramsetSize() );
 
 
//----------------------------------
// Anzeige: aktuelles MK Setting
//----------------------------------
//lcd_printf_at_P( 0, 2, MNORMAL, PSTR("Set:%2u %s"), MKVersion.mksetting, MKVersion.mksettingName );
 
/*
unsigned char *p;
 
p = paramGet_p( param_Name );
if( p )
{
lcd_printf_at_P( 0, 3, MNORMAL, PSTR("%c"), *p );
p++;
lcd_printf_at_P( 1, 3, MNORMAL, PSTR("%c"), *p );
p++;
lcd_printf_at_P( 2, 3, MNORMAL, PSTR("%c"), *p );
}
*/
 
//----------------------------------
//----------------------------------
 
/*
lcd_printf_at_P( 0, 3, MNORMAL, PSTR("Size Name:%3u"), paramSize(param_Name) );
lcd_printf_at_P( 0, 5, MNORMAL, PSTR("%c"), paramGet_UByte( param_Name ) );
paramSet_UByte( param_Name, 'x' );
lcd_printf_at_P( 3, 5, MNORMAL, PSTR("%c"), paramGet_UByte( param_Name ) );
*/
 
/*
uint8_t v;
v = MKVersion_Cmp( MKVersion.FCVer, 2,0,'f' );
 
lcd_printf_at_P( 0, 4, MNORMAL, PSTR("v:%3u"), v );
*/
 
 
/*
unsigned char paramID = 1;
unsigned char paramSubType = 1;
unsigned char paramSubIndex =1;
 
_paramset_getsubitemid( param_GlobalConfig_DrehratenBegrenzer, &paramID, &paramSubType, &paramSubIndex );
 
//lcd_printf_at_P( 0, 4, MNORMAL, PSTR("ID:%u T:%u I:%u"), paramID, paramSubType, paramSubIndex );
*/
 
//#define param_ExtraConfig_NoRcOffBeeping 204 // SUBTYPE_BIT - mk-data-structs.h: CFG_NO_RCOFF_BEEPING 0x10
//#define param_ExtraConfig_GpsAid 205 // SUBTYPE_BIT - mk-data-structs.h: CFG_GPS_AID 0x20
//#define param_ExtraConfig_LearnableCarefree 206 // SUBTYPE_BIT - mk-data-structs.h: CFG_LEARNABLE_CAREFREE 0x40
//#define param_ExtraConfig_IgnoreMagErrAtStartup 207 // SUBTYPE_BIT - mk-data-structs.h: CFG_IGNORE_MAG_ERR_AT_STARTUP 0x80
 
//#define param_GlobalConfig3_NoSdCardNoStart 220 // SUBTYPE_BIT - mk-data-structs.h: CFG3_NO_SDCARD_NO_START 0x01
//#define param_GlobalConfig3_NoGpsFixNoStart 224 // SUBTYPE_BIT - mk-data-structs.h: CFG3_NO_GPSFIX_NO_START 0x10
 
//paramGet( unsigned char paramID );
 
//lcd_printf_at_P( 0, 5, MNORMAL, PSTR("%u %u %u"), paramGet(param_ExtraConfig_NoRcOffBeeping), paramGet(param_GlobalConfig3_NoSdCardNoStart), paramGet(param_GlobalConfig3_NoGpsFixNoStart) );
 
//#define param_Kanalbelegung_Gas 242 // SUBTYPE_BYTE - Kanalbelegung [2] (unsigned char)
//#define param_Kanalbelegung_Gear 243 // SUBTYPE_BYTE - Kanalbelegung [3] (unsigned char)
//#define param_Kanalbelegung_Nick 240 // SUBTYPE_BYTE - Kanalbelegung [0] (unsigned char)
//#define param_Kanalbelegung_Roll 241 // SUBTYPE_BYTE - Kanalbelegung [1] (unsigned char)
 
// lcd_printf_at_P( 0, 4, MNORMAL, PSTR("%u %u %u %u"), paramGet(param_Kanalbelegung_Gas), paramGet(param_Kanalbelegung_Gear), paramGet(param_Kanalbelegung_Nick), paramGet(param_Kanalbelegung_Roll) );
 
// lcd_printf_at_P( 0, 5, MNORMAL, PSTR("%u"), paramGet(param_Kanalbelegung) );
 
 
/*
lcd_printf_at_P( 0, 4, MNORMAL, PSTR("%u %u %u"), paramGet(param_ExtraConfig_NoRcOffBeeping), paramGet(param_GlobalConfig3_NoSdCardNoStart), paramGet(param_GlobalConfig3_NoGpsFixNoStart) );
 
unsigned char v;
 
v = paramGet(param_GlobalConfig3_NoSdCardNoStart);
v = (v ? false : true);
paramSet(param_GlobalConfig3_NoSdCardNoStart, v);
 
lcd_printf_at_P( 0, 5, MNORMAL, PSTR("%u %u %u"), paramGet(param_ExtraConfig_NoRcOffBeeping), paramGet(param_GlobalConfig3_NoSdCardNoStart), paramGet(param_GlobalConfig3_NoGpsFixNoStart) );
 
v = paramGet(param_GlobalConfig3_NoSdCardNoStart);
v = (v ? false : true);
paramSet(param_GlobalConfig3_NoSdCardNoStart, v);
 
lcd_printf_at_P( 0, 6, MNORMAL, PSTR("%u %u %u"), paramGet(param_ExtraConfig_NoRcOffBeeping), paramGet(param_GlobalConfig3_NoSdCardNoStart), paramGet(param_GlobalConfig3_NoGpsFixNoStart) );
*/
 
/*
lcd_printf_at_P( 0, 3, MNORMAL, PSTR("%u %u"),
paramGet( param_Kanalbelegung_Gas ),
paramGet( param_Kanalbelegung_Gear )
);
 
lcd_printf_at_P( 0, 4, MNORMAL, PSTR("%u %u %u %u"),
paramGet( param_Kanalbelegung_Poti1 ),
paramGet( param_Kanalbelegung_Poti2 ),
paramGet( param_Kanalbelegung_Poti3 ),
paramGet( param_Kanalbelegung_Poti4 )
);
 
lcd_printf_at_P( 0, 5, MNORMAL, PSTR("%u %u %u %u"),
paramGet( param_Kanalbelegung_Poti5 ),
paramGet( param_Kanalbelegung_Poti6 ),
paramGet( param_Kanalbelegung_Poti7 ),
paramGet( param_Kanalbelegung_Poti8 )
);
*/
 
// lcd_printf_at_P( 0, 3, MNORMAL, PSTR("HR:%u H-Limit:%u"),
// paramGet( param_GlobalConfig_HoehenRegelung ),
// paramGet( param_ExtraConfig_HeightLimit )
// );
 
// lcd_printf_at_P( 0, 5, MNORMAL, PSTR("Auto-S-L:%u"),
// paramGet( param_StartLandChannel )
// );
 
lcd_printf_at_P( 0, 4, MNORMAL, PSTR("CH Orientation:%x"), paramGet( param_ServoCompInvert));
 
lcd_printf_at_P( 0, 5, MNORMAL, PSTR("ACC Land pulse:%x"), paramGet( param_LandingPulse));
 
 
;
 
while( true )
{
PKT_CtrlHook();
if (get_key_press (1 << KEY_ESC))
{
break;
}
}
}
#endif // #ifdef DEBUG_PARAMSET
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mksettings/paramset.h
0,0 → 1,357
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2012 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2012 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY paramset.h
//#
//# 16.07.2015 Cebra (PKT385a)
//# - add: #define param_SingleWpControlChannel (FC2.11a)
//# #define param_MenuKeyChannel (FC2.11a)
//#
//# 09.04.2015 Cebra
//# - add: #define param_ServoNickFailsave, #define param_ServoRollFailsave, #define param_Servo3Failsave
//# #define param_Servo4Failsave, #define param_Servo5Failsave
//#
//# 26.01.2015 Cebra
//# - add: #define param_ComingHomeOrientation 241 ab FC 209a im Wert ServoCompInvert, Bit4 + Bit5
//#
//# 26.09.2014 Cebra
//# - add: paramID fuer Rev.103 (FC 2.07f)
//# -> param_Hoehe_TiltCompensation
//#
//# 08.04.2014 OG
//# - add: paramID's fuer Rev.102 (FC 2.05g)
//# -> param_NaviMaxFlyingRange, param_NaviDescendRange
//#
//# 06.04.2014 OG
//# - add: paramID's fuer Rev.101
//# -> param_Servo3OnValue, param_Servo3OffValue
//# -> param_Servo4OnValue, param_Servo4OffValue
//#
//# 28.03.2014 OG
//# - add: paramID's fuer Rev.100
//# -> param_AutoPhotoDistance, param_AutoPhotoAtitudes
//# -> param_SingleWpSpeed
//#
//# 26.03.2014 OG
//# - add: param_CompassOffset_DisableDeclCalc (Sub-Item)
//#
//# 27.02.2014 OG
//# - del: paramID's fuer FC-Revisionen < 95 entfernt
//#
//# 27.02.2014 OG
//# - chg: paramGet(), paramSet() - Unterstuetzen auch Bit- und Bytefelder
//#
//# 26.02.2014 OG
//# - add: defines fuer die Unterstuetzung von paramSubID's ergaenzt
//# paramSubItems bieten direkten Zugriff auf Bit- und Bytefelder
//# von paramID's - die paramSubItems wurde in die defines der
//# paramID's integriert indem sie am Ende gelistet werden (>=160)
//# - chg: paramsetTest() umbenannt zu paramsetDEBUG()
//#
//# 25.02.2014 OG
//# - add: defines zu param_Kanalbelegung_xyz (240 bis 251)
//#
//# 14.02.2014 OG
//# - add: diverse Zugriffsfunktionen fuer paramID's und paramSet's
//#
//# 05.02.2014 OG - NEU
//############################################################################
 
#ifndef _PARAMSET_H
#define _PARAMSET_H
 
 
//---------------------------
// Typ einer paramSubID
//---------------------------
#define SUBTYPE_NO 0 // keine paramSubID
#define SUBTYPE_BIT 1 // Bit-Feld (z.B. param_GlobalConfig)
#define SUBTYPE_BITN 2 // Bit-Feld (z.B. param_GlobalConfig) negiert!
#define SUBTYPE_BYTE 3 // Byte-Feld (z.B. Kanalbelegung)
 
 
 
//########################################################################################################################################################
 
//----------------------------------------------------------------------------------------
// Die Reihenfolge ist egal - aber(!) darauf achten das keine ID doppelt vergeben wird!
// Wenn neue Feleder hinzukommen an das Ende (vor EOF - keine ID 255!) hinzufuegen!
// Bitte die Datentypen im Kommentar notieren!
//
// -> paramID
//----------------------------------------------------------------------------------------
#define param_Revision 1 // unsigned char
#define param_Kanalbelegung 2 // unsigned char [12] GAS[0], GIER[1],NICK[2], ROLL[3], POTI1, POTI2, POTI3
#define param_GlobalConfig 3 // unsigned char 0x01=Höhenregler aktiv,0x02=Kompass aktiv, 0x04=GPS aktiv, 0x08=Heading Hold aktiv
#define param_Hoehe_MinGas 4 // unsigned char Wert : 0-100
#define param_Luftdruck_D 5 // unsigned char Wert : 0-250
#define param_HoeheChannel 6 // unsigned char Wert : 0-32
#define param_Hoehe_P 7 // unsigned char Wert : 0-32
#define param_Hoehe_Verstaerkung 8 // unsigned char Wert : 0-50
#define param_Hoehe_ACC_Wirkung 9 // unsigned char Wert : 0-250
#define param_Hoehe_HoverBand 10 // unsigned char Wert : 0-250
#define param_Hoehe_GPS_Z 11 // unsigned char Wert : 0-250
#define param_Hoehe_StickNeutralPoint 12 // unsigned char Wert : 0-250
#define param_Stick_P 13 // unsigned char WERT : 0..20
#define param_Stick_D 14 // unsigned char WERT : 0..20
#define param_StickGier_P 15 // unsigned char Wert :
#define param_Gas_Min 16 // unsigned char Wert : 0-32
#define param_Gas_Max 17 // unsigned char Wert : 33-250
#define param_GyroAccFaktor 18 // unsigned char Wert : 1-64
#define param_KompassWirkung 19 // unsigned char Wert : 0-32
#define param_Gyro_P 20 // unsigned char Wert : 10-250
#define param_Gyro_I 21 // unsigned char Wert : 0-250
#define param_Gyro_D 22 // unsigned char Wert : 0-250
#define param_Gyro_Gier_P 23 // unsigned char Wert : 10-250
#define param_Gyro_Gier_I 24 // unsigned char Wert : 0-250
#define param_Gyro_Stability 25 // unsigned char Wert : 0-16
#define param_UnterspannungsWarnung 26 // unsigned char Wert : 0-250
#define param_NotGas 27 // unsigned char Wert : 0-250 //Gaswert bei Empängsverlust
#define param_NotGasZeit 28 // unsigned char Wert : 0-250 // Zeitbis auf NotGas geschaltet wird, wg. Rx-Problemen
#define param_Receiver 29 // unsigned char 0= Summensignal, 1= Spektrum, 2 =Jeti, 3=ACT DSL, 4=ACT S3D
#define param_I_Faktor 30 // unsigned char Wert : 0-250
#define param_UserParam1 31 // unsigned char Wert : 0-250
#define param_UserParam2 32 // unsigned char Wert : 0-250
#define param_UserParam3 33 // unsigned char Wert : 0-250
#define param_UserParam4 34 // unsigned char Wert : 0-250
#define param_ServoNickControl 35 // unsigned char Wert : 0-250 // Stellung des Servos
#define param_ServoNickComp 36 // unsigned char Wert : 0-250 // Einfluss Gyro/Servo
#define param_ServoNickMin 37 // unsigned char Wert : 0-250 // Anschlag
#define param_ServoNickMax 38 // unsigned char Wert : 0-250 // Anschlag
#define param_ServoRollControl 39 // unsigned char Wert : 0-250 // Stellung des Servos
#define param_ServoRollComp 40 // unsigned char Wert : 0-250
#define param_ServoRollMin 41 // unsigned char Wert : 0-250
#define param_ServoRollMax 42 // unsigned char Wert : 0-250
#define param_ServoNickRefresh 43 // unsigned char Speed of the Servo
#define param_ServoManualControlSpeed 44 // unsigned char
#define param_CamOrientation 45 // unsigned char
#define param_Servo3 46 // unsigned char Value or mapping of the Servo Output
#define param_Servo4 47 // unsigned char Value or mapping of the Servo Output
#define param_Servo5 48 // unsigned char Value or mapping of the Servo Output
#define param_LoopGasLimit 49 // unsigned char Wert: 0-250 max. Gas während Looping
#define param_LoopThreshold 50 // unsigned char Wert: 0-250 Schwelle für Stickausschlag
#define param_LoopHysterese 51 // unsigned char Wert: 0-250 Hysterese für Stickausschlag
#define param_AchsKopplung1 52 // unsigned char Wert: 0-250 Faktor, mit dem Gier die Achsen Roll und Nick koppelt (NickRollMitkopplung)
#define param_AchsKopplung2 53 // unsigned char Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
#define param_CouplingYawCorrection 54 // unsigned char Wert: 0-250 Faktor, mit dem Nick und Roll verkoppelt werden
#define param_WinkelUmschlagNick 55 // unsigned char Wert: 0-250 180°-Punkt
#define param_WinkelUmschlagRoll 56 // unsigned char Wert: 0-250 180°-Punkt
#define param_GyroAccAbgleich 57 // unsigned char 1/k (Koppel_ACC_Wirkung)
#define param_Driftkomp 58 // unsigned char
#define param_DynamicStability 59 // unsigned char
#define param_UserParam5 60 // unsigned char Wert : 0-250
#define param_UserParam6 61 // unsigned char Wert : 0-250
#define param_UserParam7 62 // unsigned char Wert : 0-250
#define param_UserParam8 63 // unsigned char Wert : 0-250
#define param_J16Bitmask 64 // unsigned char for the J16 Output
#define param_J16Timing 65 // unsigned char for the J16 Output
#define param_J17Bitmask 66 // unsigned char for the J17 Output
#define param_J17Timing 67 // unsigned char for the J17 Output
#define param_WARN_J16_Bitmask 68 // unsigned char for the J16 Output
#define param_WARN_J17_Bitmask 69 // unsigned char for the J17 Output
#define param_NaviOut1Parameter 70 // unsigned char for the J16 Output
#define param_NaviGpsModeChannel 71 // unsigned char Parameters for the Naviboard
#define param_NaviGpsGain 72 // unsigned char
#define param_NaviGpsP 73 // unsigned char
#define param_NaviGpsI 74 // unsigned char
#define param_NaviGpsD 75 // unsigned char
#define param_NaviGpsPLimit 76 // unsigned char
#define param_NaviGpsILimit 77 // unsigned char
#define param_NaviGpsDLimit 78 // unsigned char
#define param_NaviGpsA 79 // unsigned char
#define param_NaviGpsMinSat 80 // unsigned char
#define param_NaviStickThreshold 81 // unsigned char
#define param_NaviWindCorrection 82 // unsigned char
#define param_NaviAccCompensation 83 // unsigned char New since 0.86 -> was: SpeedCompensation
#define param_NaviOperatingRadius 84 // unsigned char bis Rev. 101
#define param_NaviAngleLimitation 85 // unsigned char
#define param_NaviPH_LoginTime 86 // unsigned char
#define param_ExternalControl 87 // unsigned char for serial Control
#define param_OrientationAngle 88 // unsigned char Where is the front-direction?
#define param_CareFreeChannel 89 // unsigned char switch for CareFree
#define param_MotorSafetySwitch 90 // unsigned char
#define param_MotorSmooth 91 // unsigned char
#define param_ComingHomeAltitude 92 // unsigned char
#define param_FailSafeTime 93 // unsigned char
#define param_MaxAltitude 94 // unsigned char
#define param_FailsafeChannel 95 // unsigned char if the value of this channel is > 100, the MK reports "RC-Lost"
#define param_ServoFilterNick 96 // unsigned char
#define param_ServoFilterRoll 97 // unsigned char
#define param_StartLandChannel 98 // unsigned char
#define param_LandingSpeed 99 // unsigned char
#define param_CompassOffset 100 // unsigned char
#define param_AutoLandingVoltage 101 // unsigned char in 0,1V 0 -> disabled
#define param_ComingHomeVoltage 102 // unsigned char in 0,1V 0 -> disabled
#define param_BitConfig 103 // unsigned char (war Loop-Cfg) Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
#define param_ServoCompInvert 104 // unsigned char 0x01 = Nick, 0x02 = Roll, 0x04 = relative moving // WICHTIG!!! am Ende lassen
#define param_ExtraConfig 105 // unsigned char bitcodiert
#define param_GlobalConfig3 106 // unsigned char bitcodiert
#define param_Name 107 // char [12] Name vom Parameterset
#define param_crc 108 // unsigned char
#define param_AutoPhotoDistance 109 // unsigned char ab Rev. 100 (ersetzt NaviOut1Parameter) // Auto Photo
#define param_AutoPhotoAtitudes 110 // unsigned char ab Rev. 100
#define param_SingleWpSpeed 111 // unsigned char ab Rev. 100
#define param_Servo3OnValue 112 // unsigned char ab Rev. 101 (FC 2.05f)
#define param_Servo3OffValue 113 // unsigned char ab Rev. 101 (FC 2.05f)
#define param_Servo4OnValue 114 // unsigned char ab Rev. 101 (FC 2.05f)
#define param_Servo4OffValue 115 // unsigned char ab Rev. 101 (FC 2.05f)
#define param_NaviMaxFlyingRange 116 // unsigned char ab Rev. 102 (FC 2.05g) (ersetzt NaviOperatingRadius) // in 10m
#define param_NaviDescendRange 117 // unsigned char ab Rev. 102 (FC 2.05g)
#define param_Hoehe_TiltCompensation 118 // unsigned char ab Rev. 103 (FC 2.07f)
#define param_LandingPulse 119 // unsigned char ab Rev. 104 (FC 2.09d)
#define param_ServoFS_Pos 120 // unsigned char [5] ServoNickFailsave[0],ServoRollFailsave[1],Servo3Failsave[2],Servo4Failsave[3],Servo5Failsave[4] ab Rev. 105 (FC 2.09i)
#define param_SingleWpControlChannel 121 // unsigned char ab Rev. 106 (FC 2.11a)
#define param_MenuKeyChannel 122 // unsigned char ab Rev. 106 (FC 2.11a)
 
//------- ^^^ HIER NEUE paramID's einfuegen! ^^^
 
 
// ab hier sind Sub-Items zu einer paramID definiert
// - einige paramID's werden nochmals untergliedert in Bit- oder Bytefelder
// - die Zuordnung der Sub-Items zu paramID's erfolgt in paramset.c
#define param_SUBITEM 160 // <- ab diesem Wert handelt es sich um ein paramSubID und nicht um eine paramID
 
#define param_Kanalbelegung_Nick 170 // SUBTYPE_BYTE - Kanalbelegung [0] (unsigned char)
#define param_Kanalbelegung_Roll 171 // SUBTYPE_BYTE - Kanalbelegung [1] (unsigned char)
#define param_Kanalbelegung_Gas 172 // SUBTYPE_BYTE - Kanalbelegung [2] (unsigned char)
#define param_Kanalbelegung_Gear 173 // SUBTYPE_BYTE - Kanalbelegung [3] (unsigned char)
#define param_Kanalbelegung_Poti1 174 // SUBTYPE_BYTE - Kanalbelegung [4] (unsigned char)
#define param_Kanalbelegung_Poti2 175 // SUBTYPE_BYTE - Kanalbelegung [5] (unsigned char)
#define param_Kanalbelegung_Poti3 176 // SUBTYPE_BYTE - Kanalbelegung [6] (unsigned char)
#define param_Kanalbelegung_Poti4 177 // SUBTYPE_BYTE - Kanalbelegung [7] (unsigned char)
#define param_Kanalbelegung_Poti5 178 // SUBTYPE_BYTE - Kanalbelegung [8] (unsigned char)
#define param_Kanalbelegung_Poti6 179 // SUBTYPE_BYTE - Kanalbelegung [9] (unsigned char)
#define param_Kanalbelegung_Poti7 180 // SUBTYPE_BYTE - Kanalbelegung [10] (unsigned char)
#define param_Kanalbelegung_Poti8 181 // SUBTYPE_BYTE - Kanalbelegung [11] (unsigned char)
 
#define param_ServoCompInvert_SERVO_NICK_INV 190 // SUBTYPE_BIT - mk-data-structs.h: SVNick 0x01
#define param_ServoCompInvert_SERVO_ROLL_INV 191 // SUBTYPE_BIT - mk-data-structs.h: SVRoll 0x02
#define param_ServoCompInvert_SERVO_RELATIVE 192 // SUBTYPE_BIT - mk-data-structs.h: SVRelMov 0x04
 
 
#define param_ExtraConfig_HeightLimit 200 // SUBTYPE_BIT - mk-data-structs.h: CFG2_HEIGHT_LIMIT 0x01
#define param_ExtraConfig_HeightVario 201 // SUBTYPE_BIT - mk-data-structs.h: CFG2_HEIGHT_LIMIT 0x01 ist negiert zu param_ExtraConfig_HeightLimit
#define param_ExtraConfig_VarioBeep 202 // SUBTYPE_BIT - mk-data-structs.h: CFG2_VARIO_BEEP 0x02
#define param_ExtraConfig_SensitiveRc 203 // SUBTYPE_BIT - mk-data-structs.h: CFG_SENSITIVE_RC 0x04
#define param_ExtraConfig_33vReference 204 // SUBTYPE_BIT - mk-data-structs.h: CFG_3_3V_REFERENCE 0x08
#define param_ExtraConfig_NoRcOffBeeping 205 // SUBTYPE_BIT - mk-data-structs.h: CFG_NO_RCOFF_BEEPING 0x10
#define param_ExtraConfig_GpsAid 206 // SUBTYPE_BIT - mk-data-structs.h: CFG_GPS_AID 0x20
#define param_ExtraConfig_LearnableCarefree 207 // SUBTYPE_BIT - mk-data-structs.h: CFG_LEARNABLE_CAREFREE 0x40
#define param_ExtraConfig_IgnoreMagErrAtStartup 208 // SUBTYPE_BIT - mk-data-structs.h: CFG_IGNORE_MAG_ERR_AT_STARTUP 0x80
 
 
#define param_BitConfig_LoopOben 210 // SUBTYPE_BIT - mk-data-structs.h: CFG_LOOP_OBEN 0x01
#define param_BitConfig_LoopUnten 211 // SUBTYPE_BIT - mk-data-structs.h: CFG_LOOP_UNTEN 0x02
#define param_BitConfig_LoopLinks 212 // SUBTYPE_BIT - mk-data-structs.h: CFG_LOOP_LINKS 0x04
#define param_BitConfig_LoopRechts 213 // SUBTYPE_BIT - mk-data-structs.h: CFG_LOOP_RECHTS 0x08
#define param_BitConfig_MotorBlink1 214 // SUBTYPE_BIT - mk-data-structs.h: CFG_MOTOR_BLINK1 0x10
#define param_BitConfig_MotorOffLed1 215 // SUBTYPE_BIT - mk-data-structs.h: CFG_MOTOR_OFF_LED1 0x20
#define param_BitConfig_MotorOffLed2 216 // SUBTYPE_BIT - mk-data-structs.h: CFG_MOTOR_OFF_LED2 0x40
#define param_BitConfig_MotorBlink2 217 // SUBTYPE_BIT - mk-data-structs.h: CFG_MOTOR_BLINK2 0x80
 
#define param_GlobalConfig3_NoSdCardNoStart 220 // SUBTYPE_BIT - mk-data-structs.h: CFG3_NO_SDCARD_NO_START 0x01
#define param_GlobalConfig3_DphMaxRadius 221 // SUBTYPE_BIT - mk-data-structs.h: CFG3_DPH_MAX_RADIUS 0x02 nur bis Rev 101
#define param_GlobalConfig3_VarioFailsafe 222 // SUBTYPE_BIT - mk-data-structs.h: CFG3_VARIO_FAILSAFE 0x04
#define param_GlobalConfig3_MotorSwitchMode 223 // SUBTYPE_BIT - mk-data-structs.h: CFG3_MOTOR_SWITCH_MODE 0x08
#define param_GlobalConfig3_NoGpsFixNoStart 224 // SUBTYPE_BIT - mk-data-structs.h: CFG3_NO_GPSFIX_NO_START 0x10
#define param_GlobalConfig3_UseNcForOut1 225 // SUBTYPE_BIT - mk-data-structs.h: CFG3_USE_NC_FOR_OUT1 0x20
#define param_GlobalConfig3_SpeakAll 226 // SUBTYPE_BIT - mk-data-structs.h: CFG3_SPEAK_ALL 0x40
#define param_GlobalConfig3_ServoNickCompOff 227 // SUBTYPE_BIT - mk-data-structs.h: CFG3_SERVO_NICK_COMP_OFF 0x80
 
#define param_GlobalConfig_HoehenRegelung 230 // SUBTYPE_BIT - mk-data-structs.h: CFG_HOEHENREGELUNG 0x01
#define param_GlobalConfig_HoehenSchalter 231 // SUBTYPE_BIT - mk-data-structs.h: CFG_HOEHEN_SCHALTER 0x02
#define param_GlobalConfig_HeadingHold 232 // SUBTYPE_BIT - mk-data-structs.h: CFG_HEADING_HOLD 0x04
#define param_GlobalConfig_KompassAktiv 233 // SUBTYPE_BIT - mk-data-structs.h: CFG_KOMPASS_AKTIV 0x08
#define param_GlobalConfig_KompassFix 234 // SUBTYPE_BIT - mk-data-structs.h: CFG_KOMPASS_FIX 0x10
#define param_GlobalConfig_GpsAktiv 235 // SUBTYPE_BIT - mk-data-structs.h: CFG_GPS_AKTIV 0x20
#define param_GlobalConfig_AchsenkopplungAktiv 236 // SUBTYPE_BIT - mk-data-structs.h: CFG_ACHSENKOPPLUNG_AKTIV 0x40
#define param_GlobalConfig_DrehratenBegrenzer 237 // SUBTYPE_BIT - mk-data-structs.h: CFG_DREHRATEN_BEGRENZER 0x80
#define param_ServoNickFailsave 238 // SUBTYPE_BYTE- mk-data-structs.h: ServoFS_Pos[0] ab FC 2.09j
#define param_ServoRollFailsave 239 // SUBTYPE_BYTE- mk-data-structs.h: ServoFS_Pos[1] ab FC 2.09j
#define param_Servo3Failsave 240 // SUBTYPE_BYTE- mk-data-structs.h: ServoFS_Pos[2] ab FC 2.09j
#define param_Servo4Failsave 241 // SUBTYPE_BYTE- mk-data-structs.h: ServoFS_Pos[3] ab FC 2.09j
#define param_Servo5Failsave 242 // SUBTYPE_BYTE- mk-data-structs.h: ServoFS_Pos[4] ab FC 2.09j
 
 
 
 
// hier: spezielle Subitems
#define param_CompassOffset_DisableDeclCalc 243 // wird gemappt auf: param_CompassOffset - der Wert ist dort in Bit 8 und 7 kodiert
#define param_ComingHomeOrientation 244 // unsigned char 0x08, 0x10, Bits im Feld ServoCompInvert
 
 
 
 
 
//---------------------------------------------------------------------------------------
// IMMER am Ende!!
#define param_DUMMY 254 // DO NOT CHANGE! DUMMY => spacer werte
#define param_EOF 255 // DO NOT CHANGE! EOF => markiert das Ende von paramID-Listen
#define param_NOTFOUND 255 // DO NOT CHANGE! NOTFOUND => kein paramID gefunden
 
//########################################################################################################################################################
 
 
 
//---------------------------
// struct: einzelnes Parameter-Item
//---------------------------
typedef struct
{
unsigned char paramID;
unsigned char size;
} paramRevItem_t;
 
 
 
 
//---------------------------
// exportierte Funktionen
//---------------------------
unsigned char paramsetInit( unsigned char *pData );
unsigned char paramsetSize( void );
 
unsigned char paramExist( unsigned char paramID );
unsigned char paramSize( unsigned char paramID );
unsigned char paramGet( unsigned char paramID );
unsigned char paramSet( unsigned char paramID, unsigned char newvalue );
unsigned char *paramGet_p( unsigned char paramID );
 
 
 
 
// TEST / DEBUG
void paramsetDEBUG( void );
 
#endif // _PARAMSET_H
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/mksettings
Property changes:
Added: svn:ignore
+_FC_eeprom_Versions_Archiv
+
+_old_source
+
+mkparameters.c_sic
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/motortest/motortest.c
0,0 → 1,396
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
 
//############################################################################
//# HISTORY motortest.c
//#
//# 13.05.2014 OG
//# - chg: motor_test() - #ifdef USE_I2CMOTORTEST erweitert um unsigned int SerLoop;
//# wegen Warning: variable set but not used
//#
//# 12.02.2014 OG
//# - chg: motor_test() Verschiebung von var 'buffer' wegen "unused variable 'buffer'"
//#
//# 13.05.2013 Cebra
//# - chg: #define USE_I2CMOTORTEST, I2C Funktionen schaltbar
//#
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <string.h>
#include <stdlib.h>
#include "../main.h"
#include "motortest.h"
#include "../lcd/lcd.h"
#include "../timer/timer.h"
#include "../motortest/twimaster.h"
//#include "menu.h"
#include "../uart/uart1.h"
#include "../uart/usart.h"
#include "../messages.h"
 
 
 
 
uint8_t m;
uint8_t mmode; // 0=Value 1=Motor
uint8_t v;
 
volatile uint8_t i2c_state;
volatile uint8_t motor_addr = 0;
 
#ifdef USE_I2CMOTORTEST
//--------------------------------------------------------------
// Senden der Motorwerte per I2C-Bus
//
void SendMotorData(uint8_t m,uint8_t v)
{
if (m==0)
 
for(m=0;m<MAX_MOTORS;m++) // alle Motoren
{
// Motor[m].SetPoint = MotorTest[m];
Motor[m].SetPoint = v;
Motor[m].SetPointLowerBits = 0;
 
// Motor[i].SetPoint = MotorTest[i] / 4; // testing the high resolution
// Motor[i].SetPointLowerBits = MotorTest[i] % 4;
 
}
else
{
Motor[m-1].SetPoint = v;
Motor[m-1].SetPointLowerBits = 0;
}
 
 
 
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
}
}
 
 
//--------------------------------------------------------------
//
void Search_BL (void)
{
uint8_t i = 0;
unsigned int timer;
lcd_cls ();
MotorenEin =0;
MotorTest[i] = 0;
 
lcd_printp (PSTR("Suche BL-Ctrl"), 0);
 
// Check connected BL-Ctrls
BLFlags |= BLFLAG_READ_VERSION;
motor_read = 0; // read the first I2C-Data
 
SendMotorData(0,0);
timer = SetDelay(1);
while(!(BLFlags & BLFLAG_TX_COMPLETE) && !CheckDelay(timer)); //wait for complete transfer
 
timer = SetDelay(1);
for(i=0; i < MAX_MOTORS; i++)
{
 
SendMotorData(i,0);
 
 
while(!(BLFlags & BLFLAG_TX_COMPLETE) && !CheckDelay(timer)); //wait for complete transfer
 
 
if(Motor[i].State & MOTOR_STATE_PRESENT_MASK)
{
 
lcd_printp_at (0, 1, PSTR("Found BL-Ctrl:"), 0);
lcd_print_hex_at (18,1,i,0);
 
lcd_printp_at (0, 2, PSTR("Version:"), 0);
lcd_print_hex_at (8,2,Motor[i].Version,0);
lcd_printp_at (11, 2, PSTR("SetPoi:"), 0);
lcd_print_hex_at (18,2,Motor[i].SetPoint,0);
 
lcd_printp_at (0, 3, PSTR("SetPoiL:"), 0);
lcd_print_hex_at (8,3,Motor[i].SetPointLowerBits,0);
lcd_printp_at (11, 3, PSTR("State :"), 0);
lcd_print_hex_at (18,3,Motor[i].State,0);
 
lcd_printp_at (0, 4, PSTR("ReadMod:"), 0);
lcd_print_hex_at (8,4,Motor[i].ReadMode,0);
lcd_printp_at (11, 4, PSTR("Currnt:"), 0);
lcd_print_hex_at (18,4,Motor[i].Current,0);
 
lcd_printp_at (0, 5, PSTR("MaxPWM :"), 0);
lcd_print_hex_at (8,5,Motor[i].MaxPWM,0);
lcd_printp_at (11, 5, PSTR("Temp :"), 0);
write_ndigit_number_u (18,5,Motor[i].Temperature,3,1,0);
}
 
} //End For I
}
#endif
 
 
//--------------------------------------------------------------
//
void motor (uint8_t m,uint8_t v)
{
memset (buffer, 0, 16);
 
if(m == 0)
{
memset (buffer, v, 16);
}
else
{
buffer[m-1] = v;
}
 
SendOutData('t', ADDRESS_FC, 1, buffer, 16);
}
 
 
 
//--------------------------------------------------------------
//
void motor_test (uint8_t MotorMode)
{
 
lcd_cls ();
mmode = 1; // 1=Motor
m = 1;
v = 0;
 
#ifdef USE_I2CMOTORTEST
unsigned int SerLoop;
SerLoop = 10;
 
char buffer[7];
 
if (MotorMode == I2C_Mode)
{
Search_BL();
do
{
lcd_printp_at (11, 7, PSTR("Ende Check"), 0);
if (get_key_press (1 << KEY_ESC))
{
get_key_press(KEY_ALL);
return;
}
}
while (!get_key_press (1 << KEY_ENTER));
}
#endif
lcd_cls();
lcd_printp (PSTR(" BL-Ctrl Test "), 2);
lcd_printp_at (2, 2, PSTR("Motor: 1"), 0);
lcd_printp_at (2, 3, PSTR("Value: 0"), 0);
lcd_frect ((8*1), (8*5), (0 * (14*8)) / 255, 6, 1);
// lcd_printp_at (0, 7, PSTR(KEY_LINE_3), 0);
lcd_printp_at(0, 7, strGet(KEYLINE3), 0);
lcd_printp_at (18, 7, PSTR("\x1a \x1b"), 0);
lcd_printp_at (0, 2, PSTR("\x1d"), 0);
 
 
#ifdef USE_I2CMOTORTEST
if (MotorMode == I2C_Mode)
uart1_puts("Motor;Version;Setpoint high;Setpoint low;State;ReadMode;Current;MaxPWM;Temperature\r");
#endif
 
if (MotorMode == FC_Mode)
{
if (hardware == NC && current_hardware == NC)
{
SwitchToFC();
}
}
do
{
// mmode 0=Value 1=Motor
 
if ((mmode == 0) && (get_key_press (1 << KEY_PLUS) || get_key_long_rpt_sp ((1 << KEY_PLUS), 3)) && (v < 254))
{
v++;
write_ndigit_number_u (9, 3, v, 3, 0,0);
if (MotorMode == FC_Mode)
lcd_frect ((8*1), (8*5), (v * (14*8)) / 255, 6, 1);
}
 
if ((mmode == 0) && (get_key_press (1 << KEY_MINUS) || get_key_long_rpt_sp ((1 << KEY_MINUS), 3)) && (v > 0))
{
if (MotorMode == FC_Mode)
lcd_frect (((v * (14*8) / 255) + 8), (8*5), ((14*8) / 255), 6, 0);
 
v--;
write_ndigit_number_u (9, 3, v, 3, 0,0);
if (MotorMode == FC_Mode)
lcd_frect ((8*1), (8*5), (v * (14*8)) / 255, 6, 1);
}
 
if ((mmode == 1) && (get_key_press (1 << KEY_PLUS) || get_key_long_rpt_sp ((1 << KEY_PLUS), 1)) && (m < 16))
{
m++;
write_ndigit_number_u (9, 2, m, 3, 0,0);
}
 
if ((mmode == 1) && (get_key_press (1 << KEY_MINUS) || get_key_long_rpt_sp ((1 << KEY_MINUS), 1)) && (m > 0))
{
m--;
if(m > 0)
write_ndigit_number_u (9, 2, m, 3, 0,0);
if(m == 0)
lcd_printp_at (9, 2, PSTR("All"), 0);
}
 
if (get_key_press (1 << KEY_ENTER))
{
#ifdef USE_I2CMOTORTEST
if (MotorMode == I2C_Mode)
{
if (v > 0)
{
m = 0;
v=0;
lcd_frect ((8*1), (8*5), (0 * (14*8)) / 255, 6, 1);
lcd_cls_line (0, 5, 21);
if(m > 0) write_ndigit_number_u (9, 2, m, 3, 0,0);
if(m == 0) lcd_printp_at (9, 2, PSTR("All"), 0);
write_ndigit_number_u (9, 3, v, 3, 0,0);
SendMotorData(m,v);
timer = SetDelay(1);
while(!(BLFlags & BLFLAG_TX_COMPLETE) && !CheckDelay(timer)); //wait for complete transfer
}
}
#endif
 
if(mmode == 0) // 0=Value
{
lcd_printp_at (0, 2, PSTR("\x1d"), 0);
lcd_printp_at (0, 3, PSTR(" "), 0);
mmode = 1; // 1=Motor
}
else
{
lcd_printp_at (0, 2, PSTR(" "), 0);
lcd_printp_at (0, 3, PSTR("\x1d"), 0);
mmode = 0; // 0=Value
}
}
//if (get_key_press (1 << KEY_ENTER))//
#ifdef USE_I2CMOTORTEST
if (MotorMode == I2C_Mode)
{
SendMotorData(m,v);
timer = SetDelay(1);
lcd_printp_at (0, 3, PSTR("SetPoint :"), 0);
 
write_ndigit_number_u (13,3,Motor[m-1].SetPoint,3,0,0);
lcd_printp_at (0, 4, PSTR("Current :"), 0);
lcd_print_hex_at (13,4,Motor[m-1].Current,0);
write_ndigit_number_u (13,4,Motor[m-1].Current,3,0,0);
lcd_printp_at (0, 5, PSTR("Temperature:"), 0);
write_ndigit_number_u (13,5,Motor[m-1].Temperature,3,0,0);
lcd_printp_at (0, 6, PSTR("Version:"), 0);
lcd_print_hex_at (8,6,Motor[m-1].Version,0);
lcd_printp_at (11, 6, PSTR("State :"), 0);
lcd_print_hex_at (18,6,Motor[m-1].State,0);
 
 
if (Motor[m-1].SetPoint > 0)
{
if (SerLoop == 0)
{
itoa( m-1, buffer, 10); // convert interger into string (decimal format)
uart1_puts(buffer); // and transmit string to UART
uart1_puts(";");
itoa( Motor[m-1].Version, buffer, 10); //
uart1_puts(buffer);
uart1_puts(";");
itoa( Motor[m-1].SetPoint, buffer, 10); //
uart1_puts(buffer);
uart1_puts(";");
itoa( Motor[m-1].SetPointLowerBits, buffer, 10); //
uart1_puts(buffer);
uart1_puts(";");
itoa( Motor[m-1].State, buffer, 10); //
uart1_puts(buffer);
uart1_puts(";");
itoa( Motor[m-1].ReadMode, buffer, 10); //
uart1_puts(buffer);
uart1_puts(";");
itoa( Motor[m-1].Current, buffer, 10); //
uart1_puts(buffer);
uart1_puts(";");
itoa( Motor[m-1].MaxPWM, buffer, 10); //
uart1_puts(buffer);
uart1_puts(";");
itoa( Motor[m-1].Temperature, buffer, 10); //
uart1_puts(buffer);
uart1_puts("\r");
uart1_puts("\n");
SerLoop =200;
}
else
SerLoop--;
}
 
while(!(BLFlags & BLFLAG_TX_COMPLETE) && !CheckDelay(timer)); //wait for complete transfer
}
else
#endif
motor (m,v); //if (MotorMode == I2C_Mode)//
 
}
while (!get_key_press (1 << KEY_ESC));
 
get_key_press(KEY_ALL);
 
if (MotorMode == FC_Mode)
{
motor(0,0); // switch all engines off at exit
}
 
}
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/motortest/motortest.h
0,0 → 1,46
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
 
#ifndef _MOTORTEST_H
#define _MOTORTEST_H
 
#define I2C_Mode 1 // Motortest Lokal
#define FC_Mode 2 // Motortest ueber FC
 
 
 
void motor_test (uint8_t MotorMode);
void SendMotorData(uint8_t m,uint8_t v);
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/motortest/twimaster.c
0,0 → 1,523
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + 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.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
//############################################################################
//# HISTORY twimaster.c
//#
//# 13.05.2013 Cebra
//# - chg: #define USE_I2CMOTORTEST, I2C Funktionen schaltbar
//#
//############################################################################
 
#include "../cpu.h"
#include <avr/io.h>
#include <avr/interrupt.h>
#include <util/twi.h>
#include <util/delay.h>
#include "../eeprom/eeprom.h"
#include "../motortest/twimaster.h"
#include "../timer/timer.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;
uint8_t RequiredMotors = 1;
char MotorenEin = 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
 
 
 
 
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;
}
 
 
 
//--------------------------------------------------------------
// Initialize I2C (TWI)
//
void I2C_Init(char clear)
{
 
#ifdef USE_I2CMOTORTEST
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;
#endif
}
 
 
#ifdef USE_I2CMOTORTEST
//--------------------------------------------------------------
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;
}
#endif
 
#ifdef USE_I2CMOTORTEST
//--------------------------------------------------------------
// 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;
if((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;
 
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(MotorenEin)
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(MotorenEin)
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);
}
#endif
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/motortest/twimaster.h
0,0 → 1,80
#ifndef _I2C_MASTER_H
#define _I2C_MASTER_H
+
+#include <inttypes.h>
+#include "../mk-data-structs.h"
+
+#define TWI_STATE_MOTOR_TX 0
+#define TWI_STATE_MOTOR_RX 5
+#define TWI_STATE_GYRO_OFFSET_TX 18
+
+extern volatile uint8_t twi_state;
+extern volatile uint8_t motor_write;
+extern volatile uint8_t motor_read;
+extern volatile uint8_t I2C_TransferActive;
+
+extern uint8_t MissingMotor;
+
+#define MAX_MOTORS 12
+#define MOTOR_STATE_PRESENT_MASK 0x80
+#define MOTOR_STATE_ERROR_MASK 0x7F
+#define MOTOR_STATE_NEW_PROTOCOL_MASK 0x01
+#define BLFLAG_TX_COMPLETE 0x01
+#define BLFLAG_READ_VERSION 0x02
+
+extern volatile uint8_t BLFlags;
+extern char MotorenEin;
+unsigned char MotorTest[16];
+#define BL_READMODE_STATUS 0
+#define BL_READMODE_CONFIG 16
+
+
+
+extern MotorData_t Motor[MAX_MOTORS];
+
+#define BLCONFIG_REVISION 2
+
+#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
+
+#define BITCONF_REVERSE_ROTATION 0x01
+#define BITCONF_RES1 0x02
+#define BITCONF_RES2 0x04
+#define BITCONF_RES3 0x08
+#define BITCONF_RES4 0x10
+#define BITCONF_RES5 0x20
+#define BITCONF_RES6 0x40
+#define BITCONF_RES7 0x80
+
+
+
+extern BLConfig_t BLConfig;
+
+extern volatile uint16_t I2CTimeout;
+
+void I2C_Init(char); // Initialize I2C
+#define I2C_Start(start_state) {twi_state = start_state; BLFlags &= ~BLFLAG_TX_COMPLETE; TWCR = (1<<TWSTA) | (1<<TWEN) | (1<<TWINT) | (1<<TWIE);}
+#define I2C_Stop(start_state) {twi_state = start_state; TWCR = (1<<TWEN) | (1<<TWSTO) | (1<<TWINT);}
+void I2C_Reset(void); // Reset I2C
+
+#define BLCONFIG_SUCCESS 0
+#define BLCONFIG_ERR_MOTOR_RUNNING 1
+#define BLCONFIG_ERR_MOTOR_NOT_EXIST 2
+#define BLCONFIG_ERR_HW_NOT_COMPATIBLE 3
+#define BLCONFIG_ERR_SW_NOT_COMPATIBLE 4
+#define BLCONFIG_ERR_CHECKSUM 5
+#define BLCONFIG_ERR_READ_NOT_POSSIBLE 6
+
+uint8_t I2C_WriteBLConfig(uint8_t motor);
+uint8_t I2C_ReadBLConfig(uint8_t motor);
+
+#endif
+
+
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/osd/osd.c
0,0 → 1,4919
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
* Oliver Gemesi "olli42" for additions und changes in OSDScreen *
*****************************************************************************/
 
 
//--------------------
// Debug
//--------------------
//#define DEBUG_OSD_TIME // mit dem NC-Simulator koennen keine brauchbaren Zeit/Datum Daten ermittelt werden
// am Anfang von osd() wird mit dieser Einstellung eine gueltige Fake-Zeit/Date gesetzt
//#define DEBUG_OSD_STAT_MOTORRUN // erzwingt Statistik Aufzeichnung auch wenn die Motoren nicht laufen
 
//############################################################################
//# HISTORY osd.c
//#
//# 05.04.2015 Cebra
//# - chg: SendOutData( 'h', ADDRESS_ANY, 2, &mkdisplayCmd, 1, 0x00,1) ergänzt um 2. Parameter wegen Fehlfunktion mit NC 2.09h
//#
//# 21.06.2014 OG
//# - chg: osd() - bei auftreten von mk_timeout wieder OSD_MK_Connect(MK_CONNECT)
//# aktiviert -> dadurch wird u.a. wieder auf die NC umgeschaltet falls
//# etwas anderes (z.B. ein anderes PKT) auf die FC umgeschaltet hat
//# - add: draw_icon_mk()
//#
//# 18.06.2014 OG
//# - add: MKLiPoCells_Init(), MKLiPoCells_Check()
//# - chg: define ORIENTATION_H, ORIENTATION_V verschoben nach osd.h
//#
//# 02.06.2014 OG
//# - fix: Beep_Waypoint() Target-Reach Beep auch bei Single-WP's (WP-Listen
//# die nur aus einem WP bestehen)
//#
//# 01.06.2014 OG
//# Beginn von Auslagerungen von Code alter OSD-Screens nach osdold_screens.c/h
//# - add: include "../osd/osdold_screens.h"
//# - add: include "../osd/osdold_messages.h"
//# - chg: osd() - Check bzgl. NC-Hardware entfernt da das bereits durch das
//# aufrufende Menue erledigt wird
//# - add: OSD_Screen_MKDisplay() um Beep_Waypoint() ergaenzt
//# - chg: OSD_Screen_Waypoints() umgestellt auf Beep_Waypoint()
//# - add: Beep_Waypoint()
//#
//# 31.05.2014 OG
//# - chg: OSD_Screen_MKDisplay() - umgestellt auf PKT_KeylineUpDown()
//#
//# 26.05.2014 OG
//# - add: etliche Aenderungen/Erweiterung am Screen "Waypoints" (auch neues Layout)
//#
//# 24.05.2014 OG
//# - fix: OSD_Screen_Waypoints(), OSD_Screen_MKDisplay() - Anzeige des akt. WP-Index
//# - chg: OSD_Screen_3DLage() - optisches Facelift
//# - fix: OSD_Screen_3DLage() - es wurden ggf. Kreise gezeichnet die ungueltig
//# und in undefinierten Speicher gingen - wurde korrigiert
//# - chg: OSD0,1,2 angepasst an OSD_Element_CompassDirection() mit xoffs,yoffs
//# - chg: OSD_Element_CompassDirection() - erweitert um xoffs,yoffs
//#
//# 20.05.2014 OG
//# - chg: OSD_Element_Flag_Label() - Anpassung zur Rahmenbestimmung eines Flags
//#
//# 19.05.2014 OG
//# - fix: osd() - Tastensteuerung bei MK-Empfangsverlust
//# - chg: osd() - wenn MK-Setting nicht ermittelt werden konnte dann exit
//# - add: OSD_Screen_MKDisplay() - Anzeige von akt. Waypoint und Anzahl der Waypoints
//# - chg: OSD_Popup_MKSetting() - gibt true/false fuer Ok zurueck und Beep bei Fehler
//# - chg: OSD_Popup_MKSetting() - timeout von 15 auf 9 reduziert
//# - chg: OSD_Popup_MKSetting(), OSD_Popup_MKError() - Layout, Multi-Sprachenunterstuetzung
//#
//# 02.05.2014 OG
//# - del: Popup_Draw() (jetzt in lcd.c)
//#
//# 02.05.2014 OG
//# - chg: kleine Aenderung an Codereihenfolge von MkError_Save() wegen Compiler-Warning
//#
//# 28.04.2014 OG
//# Anmerkung OSD-MK-Display: wenn der MK-Display Modus eingeschaltet wird, dann werden die Display Daten
//# angefordert und die BL-Daten etwas reduziert. Hin und wieder kann es passieren das ein Tastendruck im
//# OSD-MK-Display-Modus nicht durch kommt (aber nicht allzu stoerend) - kann evtl. verbessert werden wenn
//# auch die OSD-Daten reduziert werden (waere jedoch einiges mehr Aufwand).
//# - Unterstuetzung von MK-Display (nur NC-Modus) im OSD
//# (einschalten mit langem Druck dritte Taste von links, abschalten ebenso)
//# - Info-Anzeige bzgl. langem Tastendruck fuer MK-Display erweitert und deutsche Uebersetzung von "long press"
//# - Umstrukturierung von osd.c fuer MK-Display
//# - Aenderungen/Erweiterungen an verschiedenen weiteren Funktionen wie OSD_MK_GetData() fuer MK-Display
//# - add: OSD_MK_ShowTimeout() - neues Design/Layout
//# - del: OSD_Timeout() (ersetzt durch OSD_MK_ShowTimeout())
//# - chg: verschiedene Aenderungen an Timings
//# - add: neuer Timer fuer MK-Display: timer_get_displaydata
//# - fix: es gab bei einem Datenpaket-Timer einen Konflikt mit 'timer' - ein neuer Timer wurde aktiviert (timer_mk_timeout)
//#
//# 22.04.2014 OG
//# - add: OSD_Element_HomeCircleX() - soll das alte OSD_Element_HomeCircle() ersetzen, wenn
//# die alten OSD-Screens endgueltig rausfliegen
//# - chg: Aenderung Anzeige OSD_Screen_UserGPS() (abgerundete Ecken und Code Einsparung)
//# - chg: Aenderung Anzeige OSD_Screen_MKStatus() (abgerundete Ecken und Code Einsparung)
//# - chg: Aenderung Anzeige OSD_Screen_Electric() (abgerundete Ecken und Code Einsparung)
//#
//# 01.03.2014 OG
//# - chg: OSD_Popup_MKError() auf lcdx_printp_center() umgestellt
//#
//# 16.02.2014 OG
//# - chg: OSD_Popup_MKSetting() umgestellt auf MK_Setting_load()
//#
//# 13.02.2014 OG
//# - chg: OSD_MK_GetData() prueft mit MKVersion_Cmp() auf NC-Version v0.30g
//# ob GPS-Zeit-Datenpakete ('t') von der NC angefordert werden koennen
//#
//# 12.02.2014 OG
//# - chg: define MKVERSIONnnn rund um OSD_MK_UTCTime() entfernt
//# -> TODO OG: auf neue MKVersion bzgl. Versionsprüfung anpassen!
//# -> keine Unterstuetzung mehr durch zu alte NC-Versionen
//# - del: die includes zu den alten parameter... entfernt
//#
//# 10.02.2014 OG
//# - chg: OSD_Popup_MKSetting() umgestellt auf MKVersion_Setting_print()
//#
//# 08.02.2014 OG
//# - chg: OSD_Popup_MKSetting() umgestellt auf neue MKVersion Struktur
//#
//# 04.02.2014 OG
//# - fix: OSD_Element_BattLevel2() Aufruf von writex_ndigit_number_u_100th()
//#
//# 03.02.2014 OG
//# - chg: OSD_Element_BattLevel2() unterstuetzt Config.OSD_ShowCellU zur Anzeige
//# der MK-Spannung als Einzelzelle (kalk. auf Basis der ermittelten Zellenzahl)
//#
//# 29.01.2014 OG
//# - add: neue MK-Errorcodes 32,33,34
//# - add: #include "mk/mkbase.h"
//#
//# 24.01.2014 OG
//# - chg: OSD_Popup_MKSetting(): MK-Settings wird beim Start vom OSD wieder angezeigt
//# auch wenn die falsche FC-Revision vorhanden ist mit folgender Regel:
//# a) wenn falsche FC-Settings-Revision dann nur die Nummer
//# b) wenn richtige FC-Revision dann mit Nummer und Namen
//#
//# 06.01.2014 Cebra
//# - add: MK-Settingsname wird bei falscher FC Version nicht angezeigt
//#
//# 07.07.2013 OG
//# - add: OSD-Screens koennen vom Benutzer an-/ausgeschaltet werden (osd(), ScreenCtrl_Push())
//# - chg: OSD-Screen Namen jetzt in messages.c
//# - fix: MK-Error Check prueft ob die Fehlernummer gueltig ist
//# - del: alten Screen Electric (der ohne Nachkomma bei den Stroemen)
//#
//# 03.07.2013 OG
//# - chg: OSD_Popup_MKSetting() - zentrierte Anzeige des Setting-Namens
//# - chg: OSD_Popup_MKSetting() - timing
//# - chg: osd() - Screen-Umschaltung beschleunigt
//# - chg: timinigs bei OSD_MK_Connect(), osd() (werden Verbindungsfehler reduziert?)
//#
//# 02.07.2013 OG
//# - chg: CheckMKLipo() - MK-Unterspannungs-Beep nur wenn Motoren laufen
//# - del: unbenutzte Variablen
//#
//# 30.06.2013 OG
//# - add: grafische Akku-Anzeige auch fuer Screen Navigation und ElectricN
//#
//# 30.06.2013 OG
//# - add: Screen General: das Batt-Symbol zeigt grafisch den Fuellstand
//# des MK-Lipos
//# - add: Mittelwert fuer Gesamtstrom
//# - add: calc_avg() - Mittelwertberechnung
//# - chg: Benamung Statistik-Var's von mid_* auf avg_* geaendert
//# - add: USE_OSD_PKTHOOK in osd() - aktuell noch nicht klar ob PKT_Hook()
//# die Kommunikation stoert
//#
//# 27.06.2013 OG
//# - chg: numerische Winkelanzeige im Screen "Navigation" von -180 bis 180 Grad
//# 0 Grad = vorderer Ausleger zeigt zur Startposition
//# - fix: Homesicht des MK's (Winkelanzeige, Grafik)
//# ab nun: keine Benutzereinstellung mehr dafuer
//# es gilt: 0 Grad bzw. Strich nach unten -> der vordere Ausleger des MK
//# zeigt auf seine Startposition
//#
//# 19.06.2013 OG
//# - fix: redundante PKT-Error 40 eliminiert durch merken via old_PKTErrorcode
//# -> hilft wenn der MK ausgeschaltet wird waehrend man in der PKT-OSD-Anzeige ist
//# - fix: last_FlyTime in osd()
//#
//# 18.06.2013 OG
//# - chg: OSD_Timeout() erweitert um Errorlogging (Code 40 = "PKT RX lost")
//# - add: Fehlerliste "PKT RX lost" (Code: 40)
//#
//# 15.06.2013 OG
//# - chg: Anzeige OSD_Popup_MKSetting() kann durch Benutzer via Setup an/ausgeschaltet werden
//#
//# 15.06.2013 OG
//# - chg: OSD_Popup_MKSetting() optimiert, Layout, fix
//# - chg: PKT_CtrlHook erstmal wieder disabled in osd() (evtl. Probleme mit Timings?)
//#
//# 13.06.2013 cebra
//# - add: Settings Popup beim Start des OSD-Screens
//#
//# 11.06.2013 OG
//# - add: Mittelwertberechnung BL-Strom [MK_GetData()]
//# - chg: Config.OSD_ScreenMode wird vor PKT_CtrlHook() gesetzt [osd()]
//#
//# 27.05.2013 OG
//# - fix: OSD_MK_UTCTime() (neue "t" Version) Problem wegen cast fuer Sekunden
//#
//# 19.05.2013 OG
//# - chg: osd() erweitert um PKT_CtrlHook() um u.a. PKT-Updates zu ermoeglichen
//#
//# 16.05.2013 OG
//# - add: USE_OSD_SCREEN_NAVIGATION, USE_OSD_SCREEN_ELECTRIC, USE_OSD_SCREEN_ELECTRIC_N,
//# USE_OSD_SCREEN_MKSTATUS, USE_OSD_SCREEN_USERGPS, USE_OSD_SCREEN_3DLAGE,
//# USE_OSD_SCREEN_STATISTIC
//# - add: OSD_Screen_ElectricN() - zeigt BL-Stroeme mit Nachkomma an
//# - del: define SHOW_OSD_BLCURRENT_10TH (ersetzt durch neue Screen-Variante)
//# - chg: osd() umgestellt auf OSD Screen Controler; Anpassungen dafuer an allen Screens
//# - add: Funktionen fuer Screen Controler (Screen_*())
//#
//# 15.05.2013 OG
//# - chg: OSD_Screen_Electric() zeigt BL-Strom mit Nachkomma an
//# (einstellbar via define SHOW_OSD_BLCURRENT_10TH bzgl. neue/alte Anzeige)
//# - add: define DEBUG_OSD_STAT_MOTORRUN erzwingt Statistik Aufzeichnung auch wenn
//# die Motoren nicht laufen
//# - fix: osd() Statistik-Ende Zeit wird nach Landung gesetzt
//# - chg: diverse Aufraeumarbeiten
//# - chg: OSD_Screen_Statistics() umgetsellt auf calc_BLmax(()
//# - add: calc_BLmax() ermittelt max. BL Current & Temp
//# - del: draw_symbol_degree(), draw_symbol_rc() - wurden ersetzt durch
//# Zeichen im font 8x6 (SYMBOL_SMALLDEGREE, SYMBOL_RCQUALITY)
//#
//# 14.05.2013 OG
//# - add: OSD_MK_Connect() vereinheitlicht MK-Verbindungsinitialisierung
//# und MK-Abo-Renew
//# - chg: OSD_MK_UTCTime() atomisiert via ATOMIC_BLOCK()
//# - chg: OSD_Screen_Debug_RX() verschiedene Optimierungen und Beschreibungen
//#
//# 14.05.2013 OG
//# - chg: OSD_MK_UTCTime() wird mittels define jetzt mit neuem oder mit altem
//# Algorithmus einkompiliert.
//# ALT bei: defined MKVERSION088n || defined MKVERSION090b || defined MKVERSION090e
//# NEU bei: alles andere (also neuer): die neue Zeit/Datumsermittlung
//#
//# 13.05.2013 OG
//# - fix: an allen Stellen mit naviData->CompassHeading ein Modulo 360 ergaenzt
//# um Winkelangaben der FC geradezuziehen falls der Kopter beim Mixersetup
//# 'verdreht' wurde (Problem von helitron im Forum - Winkelanzeige > 360 Grad)
//# Ist ggf. ab Firmware NC 0.30h nicht mehr notwendig da Holger das
//# korrigieren wollte (muesste noch geprueft werden)
//#
//# 11.05.2013 OG
//# - add: OSD_MK_UTCTime_NEW() - ab NC 0.30g (Alpha, noch nicht im Einsatz)
//#
//# 05.05.2013 OG
//# - chg: OSD_Popup_Info() & OSD_Popup_MKError() wurden vereinheitlicht
//# mittels Popup_Draw()
//# - chg: Anzeigezeiten der Popup's etwas verkuerzt
//#
//# 03.05.2013 OG
//# - fix: OSD_MK_GetData() - griff beim lesen der BL's auf naviData fuer
//# die Statistik - relevante naviData-Werte werden nun vor dem
//# wechseln auf BL-Data gemerkt
//# - chg: Erfassung der Statistik Start/Ende-Zeit verbessert
//# - chg: bei Aufrufen von writex_datetime_time()/writex_datetime_time() den
//# Parameter 'timeoffset' entfernt
//# - add: define DEBUG_OSD_TIME um eine Fake-Zeit/Datum bei Gebrauch des
//# NC-Simulators zu setzen
//#
//# 29.04.2013 OG
//# - chg: Plausibilitaetscheck in OSD_MK_UTCTime() bzgl. des Datums
//#
//# 28.04.2013 OG
//# - chg: die alten OSD-Screens angepasst auf define USE_FONT_BIG
//#
//# 24.04.2013 OG
//# - chg: directions_p[] geaendert auf Kompatibilitaet mit Atmel Studio 6
//#
//# 21.04.2013 OG
//# - chg: define AltimeterAdjust nach osd.h verschoben
//#
//# 14.04.2013 OG
//# - add: weitere Statistik-Aufzeichnungen
//# - fix: MK_GetData() - Statistik-Aufzeichnung nur fuer wirklich vorhandene BL's
//#
//# 04.04.2013 OG
//# - fix: 3 warnings
//#
//# 04.04.2013 OG
//# - chg: MK-Errortext-Anzeige umgestellt auf naviData->Errorcode
//# weniger Datenkomminkation mit dem MK und schnelleres Ansprechverhalten
//#
//# 03.04.2013 OG
//# - chg: defines OSD_DEMO, OSD_SCREEN_DEBUG, OSD_SCREEN_OLD
//# umbenannt nach: USE_OSD_DEMO, USE_OSD_SCREEN_DEBUG, USE_OSD_SCREEN_OLD
//# und verschoben nach: main.h
//#
//# 28.03.2013 OG
//# - fix: MKErr_Log_Init() - es fehlte Multiplikation mit MAX_MKERR_LOG
//# - chg: Code Formatierungen
//#
//# 28.03.2013 CB
//# - add: replace OSD_Statistic, GPS_User, MKErr_Log in EEProm structure variable
//#
//# 28.03.2013 OG
//# - fix: abo_timer wieder aktiviert fuer 'o' und 'k'
//#
//# 28.03.2013 OG
//# - chg: osd_statistic_t - erweitert um diverse Werte und Timestamps (werden apeter implementiert)
//# - add: mkerror_t MKErr_Log[MAX_MKERR_LOG] - Vorbereitung um MK-Errors zu loggen
//#
//# 27.03.2013 OG
//# - add: Datum / Zeit vom MK lesen
//# - chg: Kommunikation mit dem MK optimiert
//# - chg: auf neue messages.c angepasst
//# - struct von den Statistiken auf PKTdatetime PKTdatetime_t
//# - verschiedene andere Aenderungen
//#
//# 22.03.2013 OG
//# erhebliche Aenderungen / Ergaenzungen - hier nur das Wichtigste
//# - neue Funktion "User GPS" (UGPS) - mit langem Druck auf Taste KEY_ENTER werden die aktuellen GPS-Daten abgespeichert
//# * gespeichert wird nur wenn wenn der MK GPS-Ok meldet
//# * wenn Ok erfolgt ein bestaetigungs Beep; wenn nicht Ok erfolgt ein Error-Beep
//# - neuer Screen "User GPS" - Anzeige der letzten der 3 UGPS-Koordinaten (intern wird mehr gespeichert)
//# - Anzeige von MK-Error Messages als Popup mit einstellbarer Anzeigezeit (kann mit Taste abgebrochen werden)
//# * kann getestet werden z.B. durch Ausschalten der Funke (= "RC Signal lost")
//# * siehe: http://www.mikrokopter.de/ucwiki/ErrorCodes
//# - OSD-Info ist nun ein Popup - autom. ausblenden nach einstellbarer Zeit; im Hintergrund werden weiterhin MK-Daten empfangen und ausgewertet
//# - neuer Debug-Screen "Debug RXPackages" - zeigt die Anzahl empfangener Datenpakete der verschiedenen Bereiche (um z.B. Timings einzustellen)
//# - erweiterte Kommunikation mit dem MK fuer BL-Daten und Error-Messages
//# - Timings der MK-Datenkommunikation weitreichend einstellbar durch defines
//# - Datenstrukturen fuer OSD-Statistiken und BL-Statistiken
//# - neue timer: timer_get_erdata, timer_get_bldata, timer_osd_refresh, timer_pkt_uptime
//# - mit dem define OSD_SCREEN_OLD koennen ggf. die alten OSD-Screens ausgeblendet werden (spart ein paar KByte's)
//# - verschiedene Optimierungen
//#
//# 12.03.2013 OG
//# - add: Get_BL_Data() - BL-Ctrl via NC auslesen (BETA) (siehe dort auch Kommentare im func-Header)
//# - add: neuer Screen "Electric"
//# - chg: Layout von Screen "Navigation" - Pixelverschiebungen
//# - chg: Layout von Screen "MK-Status" - Pixelverschiebungen und Anzeige 'Strom' ersetzt durch 'entn. Kapazitaet'
//# - add: in osd() LiPO-Cell Erkennung hinzugefuegt (fuer Screen "Electric")
//#
//# 10.03.2013 OG
//# - fix: doppelte Degree-Anzeige in OSD_Element_CompassDegree()
//# - add: neuer Screen "MK-Status"
//# - add: 7 neue OSD-Flags
//# - chg: Screen-Refresh Zeit via timer2 (einstellbar durch define TIME_OSD_REFRESH)
//# - chg: mit define OSD_DEBUG_SCREEN kann ein zusaetzlicher Screen verwendet werden zum testen/entwickeln
//# - del: entfernt CFG2_HEIGHT_LIMIT in OSD_Element_AltitudeControl() (bis bessere Loesung gefunden ist)
//#
//# 08.03.2013 OG
//# - del: OSD_Screen_Element() und cleanup in osd.h
//# - add: OSD_Element_UpDown() (steigend/sinken via Pfeilen)
//# - chg: OSD_Element_UpDown() in Screen "General" und "Navigation" hinzugefuegt (rechts neben der Hoehenanzeige)
//# - chg: Screen "General" die Sat-Warnung wurde auf OSD_Element_Flag(OSD_FLAG_S0) geaendert
//# - chg: Anzeige von Flag 'nicht genug GPS-Sateliten' (OSD_FLAG_S0) auf "S!" geändert
//#
//# 07.03.2013 OG
//# - Hinweis bzgl. LowBatt-Anzeige in den Screens "General" und "Navigation":
//# Es gibt zwei unabhängige LowBatt-Warnungen.
//# 1. die PKT LowBatt-Warnung: sie arbeitet mit der im PKT hinterlegten
//# LowBatt Spannung und stellt den Spannungswert inkl. der Einheit "V"
//# invers dar wenn der Warnwert erreicht wurde (inkl. lautem PKT-Peepen)
//# 2. die MK-LowBatt Warnung: hierbeit wird das Flag "BA" angezeigt wenn
//# der MK eine LowBatt Warnung sendet
//# Dadurch hat man nun zwei verschiedene LowBatt Warnungen die man auf Wunsch
//# verschieden einstellen kann. Bei mir ist die PKT-LowBatt etwas niedriger
//# eingestellt als die MK-Warnung und bedeutet "es ist aller hoechste Zeit zu landen".
//# Die Spannung der MK-LowBat ist ein wenig hoeher eingestellt und
//# zeigt mir "es ist bald Zeit zu landen".
//# - del: Kommunikation zu FC - siehe Kommentare in osd()
//# - chg: Kommunikation zu NC - siehe Kommentare in osd()
//# - add: neuer Screen "Navigation"
//# - chg: Layout Screen "Statistics" - Einheiten um zwei Pixel nach rechts verschoben
//# - chg: Layout von Screen "General" modifiziert (u.a. xoffs,yoffs Pixelverschiebungen)
//# - add: OSD_FLAG_BA in Screen "General"
//# - add: die OSD_Element_xyz() Funktionen in osd.h aufgenommen
//# - chg: an verschiedenen Stellen die Char-Drawmode defines MNORMAL, MINVERS, usw. eingebaut
//# - del: Kompatibilitaetscode fuer "3D-Lage" ueber Hauptmenue entfernt
//# - chg: die Funktionen OSD_Element_Switch() und OSD_Element_SwitchLabel() heissen
//# nun OSD_Element_Flag() und OSD_Element_Flag_Label()
//# - chg: die defines OSD_SWITCH_xy heissen jetzt OSD_FLAG_xy
//# - fix: letzte GPS-Koordinaten werden jetzt permanent Config.LastLatitude, Config.LastLongitude gespeichert
//#
//# 03.03.2013 OG
//# - add: delay in Mainloop von osd() um springende Werte abzudaempfen (TEST)
//# - add: Startverzoegerung der Screens bis NaviData sich etwas stabilisiert hat (TEST)
//# - add: OSD Startup Message "connecting MK..."
//# - add: 'Emergency Landing' (EL) Anzeige in Screen "General"
//# - del: OUT1/OUT2 Anzeige in Screen "General"
//# - add: RC-Quality in Screen "General"
//# - add: func: draw_symbol_rc() (alternative RC-Quality Symbol)
//# - fix: Hoehenanzeige fuer Screens "OSD0" und "OSD1"
//# - fix: OSD_Element_SwitchLabel() angepasst fuer x=0 und y=0
//# - add: OSD_Element_Switch/Label() erweitert um OSD_SWITCH_FS
//# - fix: Screen-Redraw nach OSD_MK_TIMEOUT() und anderen Fehlermeldungen
//# - chg: messages.c: STATS_ITEM_0 bis STATS_ITEM_6 angepasst (1 char kuerzer)
//# - chg: Layout von OSD_Info() - mehr background-clear und etwas kleiner
//#
//# 02.03.2013 OG
//# - chg: keine internal func in Screen's wegen warnings bei anderen
//# - del: Screen "OSD3"
//# - fix: Hoehenanzeige in Screen "General" (Minuszeichen)
//# - add: MK LowBat Warning in Screen "General"
//# - add: neues Degree Symbol (als func) in Screen General (kleiner als das Char 0x1E)
//# - add: weitere Flags in OSD_Element_Flag()
//#
//# 01.03.2013 OG
//# - Reskrukturierung Code (+ neuer OSD-Screens und einiges mehr)
//############################################################################
 
 
//############################################################################
//# HINWEISE:
//#
//# 1. define: USE_OSD_DEMO (main.h)
//# mit define OSD_DEMO wird ein Demo-Modus bei den neuen Screens einge-
//# schaltet - damit werden u.a. alle Flag's angezeigt fuer Scree-Fotos
//#
//# 2. define: USE_OSD_SCREEN_DEBUG (main.h)
//# mit diesem define wird ein zusaetzlicher Screen "Debug" einkompiliert
//# fuer Test / Experimente / Debug von OSD-Elementen
//#
//# 3. define: USE_OSD_SCREEN_OLD (main.h)
//# ein-/ ausschalten der alten OSD-Screens OSD0, OSD1, OSD2 (spart ca. 3 KByte)
//#
//# 4. Timings der MK-Datenkommunikation
//# die Timings sind weitreichend enstellbar ueber die define im Abschnitt 'Timings'
//# der Debug-Screen 'Debug RXPackages' informiert ueber die Anzahl eingegangener
//# Datenpakete der verschiedenen Bereiche (OSD, BL-Daten, Error-Message)
//#
//# 5. Informationen zum Display
//# DOG: 128 x 64 Pixel with 6x8 Font => 21 x 8
//#
//# 6. MK-Kommunikationsprotokoll Referenz
//# http://www.mikrokopter.de/ucwiki/en/SerialProtocol?highlight=%28%28----%28-*%29%28\r%29%3F\n%29%28.*%29CategoryCoding%29#en.2BAC8-SerialCommands.Flight-Ctrl
//############################################################################
 
#include "../cpu.h"
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <string.h>
#include <util/atomic.h>
 
#include "../main.h"
#include "../lcd/lcd.h"
#include "../timer/timer.h"
#include "../uart/usart.h"
#include "../eeprom/eeprom.h"
#include "../messages.h"
#include "../sound/pwmsine8bit.h"
#include "../mk-data-structs.h"
#include "../pkt/pkt.h"
#include "../osd/osd.h"
#include "../utils/xutils.h"
#include "../mk/mkbase.h"
#include "../osd/osdold_messages.h"
#include "../osd/osdold_screens.h"
 
 
//--------------------
// Funktionen ein-/ausbinden
//--------------------
// -> siehe main.h
 
 
//--------------------
// Timings
//--------------------
#define TIME_OSD_REFRESH 45 // Screen Refresh (Steuerung via 'timer_osd_refresh') (n*10 = ms; 100 entspricht 1 Sekunde)
#define TIME_POPUP_INFO 400 // 4 Sekunden Popup-Info zeigen (kann mit Taste abgebrochen werden)
#define TIME_POPUP_MKERROR 700 // 7 Sekunden Popup-MK-Error zeigen (kann mit Taste abgebrochen werden)
 
#define TXINTERVAL_OSDDATA 10 // Intervall mit der der MK OSD-Daten senden soll (n*10 = ms)
 
#define TIME_GET_BLDATA 35 // Zeitintervall in der BL-Daten vom MK geholt werden (Steuerung via 'timer_get_bldata') (n*10 = ms; 100 entspricht 1 Sekunde)
#define TIME_READ_BLDATA 20 // fuer n Zeit werden BL-Daten vom MK gelesen (Steuerung via timer) (n*10 = ms; 100 entspricht 1 Sekunde))
#define TXINTERVAL_BLDATA 7 // Intervall mit der der MK BL-Daten senden soll (n*10 = ms)
 
#define TIME_GET_TIDATA 12000 // alles 120 Sekunden Zeit/Datum vom MK lesen (die Zwischenzeit wird von einem PKT-Timer uebernommen)
 
#define TIME_GET_DISPLAYDATA 20 // fuer n Zeit werden BL-Daten vom MK gelesen (Steuerung via timer) (n*10 = ms; 100 entspricht 1 Sekunde))
 
 
//#define MK_TIMEOUT 300 // MK-Verbindungsfehler wenn fuer n Zeit keine gueltigen Daten hereinkommen (3 sec)
#define MK_TIMEOUT 400 // MK-Verbindungsfehler wenn fuer n Zeit keine gueltigen Daten hereinkommen (4 sec)
 
 
//--------------------
// weiteres
//--------------------
#define OSD_POPUP_NONE 0
#define OSD_POPUP_INFO 1
#define OSD_POPUP_MKERROR 2
 
#define MK_CONNECT 1
#define MK_ABORENEW 2
 
 
 
// global definitions and global vars
NaviData_t *naviData;
uint16_t heading_home;
uint8_t drawmode;
uint8_t OSDScreenRefresh;
 
 
// flags from last round to check for changes
uint8_t old_AngleNick = 0;
uint8_t old_AngleRoll = 0;
uint16_t old_hh = 0;
 
 
// aktuell nicht benoetigt - siehe Kommentar in osd.c
//mk_param_struct_t *mk_param_struct;
//uint8_t Flags_ExtraConfig;
//uint8_t Flags_GlobalConfig;
//uint8_t Flags_GlobalConfig3;
 
 
// cache old vars for blinking attribute, checkup is faster than full
// attribute write each time
 
volatile uint8_t OSD_active = 0;
 
uint8_t Vario_Beep_Up = 0;
uint8_t Vario_Beep_Down = 0;
uint8_t Vario_Beep_Up_Interval = 9;
uint8_t Vario_Beep_Down_Interval = 6;
uint8_t Vario_Threshold = 0;
uint8_t Vario_Threshold_Value = 7;
uint8_t OldWP = 0;
uint8_t NextWP = 0;
 
uint8_t WP_old = 0; // Screen: "Waypoints"
uint8_t WP_last = false; // Screen: "Waypoints"
 
 
 
#define MAX_CELL_VOLTAGE 43 // max cell voltage for LiPO
#define MIN_CELL_VOLTAGE 32 // min cell voltage for LiPO
 
// Flags
volatile uint8_t error = 0;
uint8_t cells = 0;
uint8_t BattLowVoltageWarning = 0;
uint8_t CellIsChecked = 0;
uint8_t AkkuWarnThreshold = 0;
uint16_t duration = 0;
 
 
//-----------------------------------------------------------
// Buffer
//-----------------------------------------------------------
BLData_t blData[OSD_MAX_MOTORS]; // speichert gelesene BL-Datenpakete
pkt_gpspos_t GPS_Current; // aktuelle GPS-Position
u8 old_PKTErrorcode; // speichert den letzen Errorcode vom PKT damit dieser nicht wiederholt gespeichert wird
u8 old_MKErrorcode; // speichert den letzen Errorcode vom MK damit dieser nicht wiederholt angezeigt wird
 
 
//-----------------------------------------------------------
// OSD Daten
//-----------------------------------------------------------
NaviData_t osdData; // Buffer
 
//-----------------------------------------------------------
// MK-DISPLAY
//-----------------------------------------------------------
uint8_t mkdisplayMode = false;
uint8_t mkdisplayCmd = 0xff;
char mkdisplayData[81]; // Buffer (80 +1 fuer term. Char)
 
 
//---------------------
// DEBUG
//---------------------
#ifdef USE_OSD_SCREEN_DEBUG
uint16_t readCounterOSD; // Anzahl gelesener Datenpakete von NC Modus 'o' (Request OSD-Data)
uint16_t readCounterTIME; // Anzahl gelesener Datenpakete von NC (Time)
uint16_t readCounterDISPLAY;
uint16_t readCounterBL[OSD_MAX_MOTORS]; // Anzahl gelesener Datenpakete pro BL via NC Modus 'k' (BL Ctrl Status)
#endif // USE_OSD_SCREEN_DEBUG
 
 
//---------------------
// Strings & Co.
//---------------------
static const char mkerror00[] PROGMEM = "No Error";
static const char mkerror01[] PROGMEM = "FC not compatible";
static const char mkerror02[] PROGMEM = "MK3Mag not compati.";
static const char mkerror03[] PROGMEM = "no FC communication";
static const char mkerror04[] PROGMEM = "no MK3Mag communic.";
static const char mkerror05[] PROGMEM = "no GPS communication";
static const char mkerror06[] PROGMEM = "bad compass value";
static const char mkerror07[] PROGMEM = "RC Signal lost";
static const char mkerror08[] PROGMEM = "FC spi rx error";
static const char mkerror09[] PROGMEM = "no NC communication";
static const char mkerror10[] PROGMEM = "FC Nick Gyro";
static const char mkerror11[] PROGMEM = "FC Roll Gyro";
static const char mkerror12[] PROGMEM = "FC Yaw Gyro";
static const char mkerror13[] PROGMEM = "FC Nick ACC";
static const char mkerror14[] PROGMEM = "FC Roll ACC";
static const char mkerror15[] PROGMEM = "FC Z-ACC";
static const char mkerror16[] PROGMEM = "Pressure sensor";
static const char mkerror17[] PROGMEM = "FC I2C";
static const char mkerror18[] PROGMEM = "Bl Missing";
static const char mkerror19[] PROGMEM = "Mixer Error";
static const char mkerror20[] PROGMEM = "Carefree Error";
static const char mkerror21[] PROGMEM = "GPS lost";
static const char mkerror22[] PROGMEM = "Magnet Error";
static const char mkerror23[] PROGMEM = "Motor restart";
static const char mkerror24[] PROGMEM = "BL Limitation";
static const char mkerror25[] PROGMEM = "Waypoint range";
static const char mkerror26[] PROGMEM = "No SD-Card";
static const char mkerror27[] PROGMEM = "SD Logging aborted";
static const char mkerror28[] PROGMEM = "Flying range!";
static const char mkerror29[] PROGMEM = "Max Altitude";
static const char mkerror30[] PROGMEM = "No GPS Fix";
static const char mkerror31[] PROGMEM = "compass not calibr.";
static const char mkerror32[] PROGMEM = "BL selftest";
static const char mkerror33[] PROGMEM = "no ext. compass";
static const char mkerror34[] PROGMEM = "compass sensor";
 
#define MAX_MKERROR_NUM 34 // maximale Error-Nummer vom MK (verwendet in osd())
 
static const char mkerror35[] PROGMEM = ""; // free for MK
static const char mkerror36[] PROGMEM = ""; // free for MK
static const char mkerror37[] PROGMEM = ""; // free for MK
static const char mkerror38[] PROGMEM = ""; // free for MK
static const char mkerror39[] PROGMEM = ""; // free for MK
 
static const char pkterror40[] PROGMEM = "PKT RX lost";
 
 
//---------------------------------------
// wenn die Liste erweitert wird,
// MAX_MKERROR_NUM in osd.h anpassen!
//---------------------------------------
const char * const mkerrortext[] PROGMEM=
{
mkerror00,
mkerror01,
mkerror02,
mkerror03,
mkerror04,
mkerror05,
mkerror06,
mkerror07,
mkerror08,
mkerror09,
mkerror10,
mkerror11,
mkerror12,
mkerror13,
mkerror14,
mkerror15,
mkerror16,
mkerror17,
mkerror18,
mkerror19,
mkerror20,
mkerror21,
mkerror22,
mkerror23,
mkerror24,
mkerror25,
mkerror26,
mkerror27,
mkerror28,
mkerror29,
mkerror30,
mkerror31,
mkerror32,
mkerror33,
mkerror34,
mkerror35,
mkerror36,
mkerror37,
mkerror38,
mkerror39,
pkterror40
};
 
 
//char* rose = "-+-N-+-O-+-S-+-W-+-N-+-O-+-S-+-W-+-N-+-O-+-S-+-W";
const char rose[48] PROGMEM = {
0x0e, 0x0f, 0x0e, 'N', 0x0e, 0x0f, 0x0e, 'O', 0x0e, 0x0f, 0x0e, 'S',
0x0e, 0x0f, 0x0e, 'W', 0x0e, 0x0f, 0x0e, 'N', 0x0e, 0x0f, 0x0e, 'O',
0x0e, 0x0f, 0x0e, 'S', 0x0e, 0x0f, 0x0e, 'W', 0x0e, 0x0f, 0x0e, 'N',
0x0e, 0x0f, 0x0e, 'O', 0x0e, 0x0f, 0x0e, 'S', 0x0e, 0x0f, 0x0e, 'W',
};
 
 
// the center is char 19 (north), we add the current heading in 8th
// which would be 22.5 degrees, but float would bloat up the code
// and *10 / 225 would take ages... so we take the uncorrect way
static const char str_NE[] PROGMEM = "NE";
static const char str_E[] PROGMEM = "E ";
static const char str_SE[] PROGMEM = "SE";
static const char str_S[] PROGMEM = "S ";
static const char str_SW[] PROGMEM = "SW";
static const char str_W[] PROGMEM = "W ";
static const char str_NW[] PROGMEM = "NW";
static const char str_N[] PROGMEM = "N ";
 
const char * const directions_p[] PROGMEM=
{
str_NE,
str_E,
str_SE,
str_S,
str_SW,
str_W,
str_NW,
str_N
};
 
 
//###########################################################
//# OSD Screen Controler
//###########################################################
 
#define SCREENCTRL_MAX 15 // Anzahl max. zu verwaltender Screens
 
//---------------------------
// typedef: einzelner Screen
//---------------------------
typedef struct
{
const char *screenname;
void (*screen)(void);
} screen_t;
 
 
//---------------------------
// typedef: Screenliste
//---------------------------
typedef struct
{
uint8_t active;
uint8_t count;
screen_t screen[SCREENCTRL_MAX];
} screenlist_t;
 
screenlist_t osdscreens;
 
 
//--------------------------------------------------------------
// ScreenCtrl_Init()
//
// initialisiert die Screenliste - muss vor dem ersten
// ScreenCtrl_Push() aufgerufen werden
//--------------------------------------------------------------
void ScreenCtrl_Init( void )
{
osdscreens.active = 0;
osdscreens.count = 0;
}
 
 
//--------------------------------------------------------------
// ScreenCtrl_Push( *screenname, *screenfunc)
//
// fuegt einen Screen der Screenliste hinzu (siehe osd())
//--------------------------------------------------------------
void ScreenCtrl_Push( uint8_t screenid, const char *screenname, void (*screenfunc)(void))
{
if( osdscreens.count < SCREENCTRL_MAX )
{
// wenn screenid = 0 dann immer anzeigen (Screen ist nicht vom Benutzer auswaehlbar)
if( (screenid==0) || ((Config.OSD_UseScreen & (1 << screenid)) != 0) )
{
osdscreens.screen[osdscreens.count].screenname = screenname;
osdscreens.screen[osdscreens.count].screen = screenfunc;
osdscreens.count++;
}
}
}
 
 
//--------------------------------------------------------------
// ScreenCtrl_Set( screennum)
//
// aktiviert einen bestimmten Screen aus der Screenliste
//--------------------------------------------------------------
void ScreenCtrl_Set( uint8_t screennum )
{
osdscreens.active = 0;
if( screennum < osdscreens.count )
{
osdscreens.active = screennum;
}
}
 
 
//--------------------------------------------------------------
// num = ScreenCtrl_GetNum()
//
// gibt die Nummer des aktuell aktivierten Screens zurueck
//--------------------------------------------------------------
uint8_t ScreenCtrl_GetNum( void )
{
return osdscreens.active;
}
 
 
//--------------------------------------------------------------
// name = ScreenCtrl_GetName()
//
// gibt den Namen des aktuell aktivierten Screens zurueck
// Rueckgabe ist ein Pointer auf einen String im PROGMEM
//--------------------------------------------------------------
const char * ScreenCtrl_GetName( void )
{
return osdscreens.screen[osdscreens.active].screenname;
}
 
 
//--------------------------------------------------------------
// ScreenCtrl_Next()
//
// zum naechsten Screen wechseln
//--------------------------------------------------------------
void ScreenCtrl_Next( void )
{
osdscreens.active++;
if( osdscreens.active >= osdscreens.count )
{
osdscreens.active = 0;
}
OSDScreenRefresh = OSD_SCREEN_REDRAW;
}
 
 
//--------------------------------------------------------------
// ScreenCtrl_Previous()
//
// zum vorherigen Screen wechseln
//--------------------------------------------------------------
void ScreenCtrl_Previous( void )
{
if( osdscreens.active == 0 )
{
osdscreens.active = osdscreens.count-1;
}
else
{
osdscreens.active--;
}
OSDScreenRefresh = OSD_SCREEN_REDRAW;
}
 
 
//--------------------------------------------------------------
// ScreenCtrl_Show()
//
// ruft den aktuell Screen auf
//--------------------------------------------------------------
void ScreenCtrl_Show( void )
{
osdscreens.screen[osdscreens.active].screen();
}
 
 
//###########################################################
//###########################################################
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void calc_BLmax( osd_BLmax_t *blmax )
{
uint8_t i;
 
memset( blmax, 0, sizeof(osd_BLmax_t) );
 
for( i=0; i<Config.OSD_Statistic.BL_Count; i++)
{
if( Config.OSD_Statistic.BL[i].max_Current > blmax->max_BL_Current )
{
blmax->max_BL_Current = Config.OSD_Statistic.BL[i].max_Current;
blmax->max_BL_Current_Index = i;
}
 
if( Config.OSD_Statistic.BL[i].max_Temp > blmax->max_BL_Temp )
{
blmax->max_BL_Temp = Config.OSD_Statistic.BL[i].max_Temp;
blmax->max_BL_Temp_Index = i;
}
 
}
}
 
 
 
//--------------------------------------------------------------
// STAT_Init()
//
// initialisiert die Statistic Werte neu
//--------------------------------------------------------------
void STAT_Init(void)
{
// init: statistic
memset( &Config.OSD_Statistic, 0, sizeof(osd_statistic_t) );
 
Config.OSD_Statistic.min_UBat = 255;
Config.OSD_Statistic.min_RCQuality = 255;
Config.OSD_Statistic.min_AngleNick = 126;
Config.OSD_Statistic.min_AngleRoll = 126;
}
 
 
 
//--------------------------------------------------------------
// MKErr_Log_Init()
//
// initialisiert die MK Errorcodes neu
//--------------------------------------------------------------
void MKErr_Log_Init(void)
{
// init: MK Errorlog
memset( &Config.MKErr_Log, 0, sizeof(mkerror_t)*MAX_MKERR_LOG );
 
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void MkError_Save( uint8_t Errorcode )
{
uint8_t i;
 
for( i=MAX_MKERR_LOG-1; i>0; i--)
{
Config.MKErr_Log[i] = Config.MKErr_Log[i-1];
}
 
Config.MKErr_Log[0].Errorcode = Errorcode;
memcpy( &Config.MKErr_Log[0].set_Time, (char *)&UTCTime, sizeof(PKTdatetime_t) ); // sichern...
}
 
 
 
//--------------------------------------------------------------
// OSD_MK_Connect()
//
// Verbindung zum MK herstellen oder ABO-Renew
//
// modus: MK_CONNECT oder MK_ABORENEW
//--------------------------------------------------------------
void OSD_MK_Connect( uint8_t modus )
{
uint8_t tx_interval;
 
if( modus == MK_CONNECT )
{
SwitchToNC();
 
// switch off: 3d data => kompatibel mit SmartOSD????
//tx_interval = 0;
//SendOutData ('c', ADDRESS_ANY, 1, &tx_interval, 1);
//_delay_ms(25);
 
tx_interval = 0;
SendOutData( 'd', ADDRESS_ANY, 1, &tx_interval, 1); // switch off: debug
 
timer = 3; while( timer > 0 ); // short delay
}
 
tx_interval = TXINTERVAL_OSDDATA; // switch on: sending osd-data
SendOutData( 'o', ADDRESS_NC, 1, &tx_interval, 1); // request: OSD Data from NC every ..ms
 
timer = 3; while( timer > 0 ); // short delay
 
// switch on: sending bl-data
tx_interval = TXINTERVAL_BLDATA; // 5 => 50 ms (send packet every n*10 ms)
SendOutData( 'k', ADDRESS_ANY, 1, &tx_interval, 1); // request: BL Ctrl Status
 
mode = 'O';
abo_timer = ABO_TIMEOUT;
 
rxd_buffer_locked = FALSE;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void OSD_MK_ShowTimeout( void )
{
if( old_PKTErrorcode != 40 )
{
MkError_Save( 40 ); // Logge: "PKT RX lost"
old_PKTErrorcode = 40;
}
 
lcd_cls ();
 
lcd_frect_round( 0, 0, 127,10, 1, R1); // Rect: Invers (Titel)
lcdx_printp_center( 0, strGet(OSD_ERROR), MINVERS, 1,2); // "FEHLER: Datenverlust!"
 
lcdx_printp_at(3, 1, strGet(START_LASTPOS) , MNORMAL, 0,6); // "Letzte Position"
lcdx_printp_at(3, 2, strGet(START_LASTPOS3), MNORMAL, 0,6); // "Google Eingabe"
 
//----
lcd_frect( 0, (4*7)+5, 127, 7, 1); // Rect: Invers
lcdx_printp_at(1, 3, strGet(START_LASTPOS1), MINVERS, 0,9); // "Breitengr Längengr"
 
writex_gpspos( 1, 4, Config.LastLatitude , MNORMAL, 0,11); // Anzeige: Breitengrad
writex_gpspos( 12, 4, Config.LastLongitude, MNORMAL, -1,11); // Anzeige: Laengengrad
 
lcd_rect( 0, (3*8)+8, 127, (2*8)+4, 1); // Rahmen
 
lcd_printp_at(12, 7, strGet(ENDE) , MNORMAL); // Keyline: "Ende"
 
set_beep ( 0, 0, BeepOff); // Falls Spannungswarnung an war Beeper aus (ist das notwendig?)
}
 
 
 
/***************************************************************************************************************************************
 
//--------------------------------------------------------------
// OSD_MK_UTCTime()
// Fuer: defined MKVERSION088n || defined MKVERSION090b || defined MKVERSION090e
// -> erstmal keine Unterstuetzung mehr...
//--------------------------------------------------------------
 
//--------------------------------------------------------------
// OSD_MK_UTCTime()
//
// ALTE Funktion fuer FC < 0.90h (und dementsprechend NC < 0.30h)
//
// Setzt die PKT globale UTCTime mithilfe des MK.
//
// Foraussetzung:
// - der NC-Modus muss aktiv sein (SwitchToNC)
// - aktuell nur fuer osd.c
//
// Rueckgabe:
// true = ok, UTCTime gespeichert
// false = Zeit/Datum nicht gelesen
//
// Hack:
// Gelesen wird die Seite 3 des NC-Display's. Dort wird Zeit
// und Datum an den entsprechnenden Positionen via Zeichen an-
// gezeigt. Die Zeichen werden ausgelesen und in die interne UTCTime
// gespeichert.
//
// HINWEIS:
// Ab NC > v0.30b (evtl. v0.30c) wird die NC ein neues Datenpaket
// senden ("T") mit strukturierten Informationen zu Datum/Zeit.
// Das wurde von Holger eingebaut.
// Wird spaeter auch im PKT implementiert.
//--------------------------------------------------------------
int OSD_MK_UTCTime( uint8_t readtime )
{
uint32_t sec;
uint32_t min;
uint32_t hour;
uint16_t year;
uint8_t month;
uint8_t day;
uint8_t page;
uint8_t ok = false;
 
 
mode = 'L'; // read: MK-Display Page
page = 3; // anfordern von Seite 3 (der NC)
SendOutData ('l', ADDRESS_ANY, 1, &page, 1); // request: MK-Display Page 3
 
rxd_buffer_locked = FALSE;
 
timer = readtime; // fuer max. n*10 millisec versuchen Daten zu lesen
while( timer>0 && !ok ); // lese Daten-Pakete fuer die angegebene Zeit oder gelesen
{
if( rxd_buffer_locked )
{
Decode64();
 
#ifdef USE_OSD_SCREEN_DEBUG
readCounterTIME++;
#endif
 
sec = (uint32_t)(pRxData[66+7+2] - '0') + 10 * (uint32_t)(pRxData[66+6+2] - '0'); // seconds: sec
min = (uint32_t)(pRxData[66+4+2] - '0') + 10 * (uint32_t)(pRxData[66+3+2] - '0'); // seconds: min
hour = (uint32_t)(pRxData[66+1+2] - '0') + 10 * (uint32_t)(pRxData[66+0+2] - '0'); // seconds: hour
sec += (min * 60) + (hour * 3600);
 
year = (uint16_t)(pRxData[46+9+2] - '0') + 10 * (uint16_t)(pRxData[46+8+2] - '0'); // year
year += 100 * (uint16_t)(pRxData[46+7+2] - '0') + 1000 * (uint16_t)(pRxData[46+6+2] - '0'); // year
 
day = (uint8_t)(pRxData[46+4+2] - '0') + 10 * (uint8_t)(pRxData[46+3+2] - '0'); // day
 
month = (uint8_t)(pRxData[46+1+2] - '0') + 10 * (uint8_t)(pRxData[46+0+2] - '0'); // month
 
// in der globalen UTCTime speichern (hoffentlich funkt kein timer dazwischen)
if( year > 2000 && year < 2200 ) // plausibilitaets check
{
ATOMIC_BLOCK(ATOMIC_FORCEON)
{
UTCTime.seconds = sec;
UTCTime.day = day;
UTCTime.month = month;
UTCTime.year = year;
}
}
ok = true;
}
}
 
return ok; // wenn erfolgreich gelesen dann true (kein timeout)
}
***************************************************************************************************************************************/
 
 
 
//--------------------------------------------------------------
// OSD_MK_UTCTime()
//
// NEUE Ermittlung der Zeit vom MK
// ab NC v0.30g (bzw. NC 0.30h fuer FC 0.90h)
//
// TODO OG: auf neue MKVersion bzgl. Versionsprüfung anpassen!
//--------------------------------------------------------------
int OSD_MK_UTCTime( uint8_t readtime )
{
DateTime_t *rx_DateTime;
uint8_t tx_interval;
uint8_t ok = false;
 
mode = 'T'; // read: MK-Display Page
tx_interval = 1; //
SendOutData ('t', ADDRESS_NC, 1, &tx_interval, 1); // request: DateTime
 
rxd_buffer_locked = FALSE;
 
timer = readtime; // fuer max. n*10 millisec versuchen Daten zu lesen
while( timer>0 && !ok ); // lese Daten-Pakete fuer die angegebene Zeit oder gelesen
{
if( rxd_buffer_locked )
{
Decode64();
rx_DateTime = (DateTime_t *) (pRxData);
 
#ifdef USE_OSD_SCREEN_DEBUG
readCounterTIME++;
#endif
 
if( rx_DateTime->Year > 2000 && rx_DateTime->Year < 2200 ) // Plausibilitaets Check
{
ATOMIC_BLOCK(ATOMIC_FORCEON)
{
UTCTime.seconds = ((uint32_t)(rx_DateTime->Hour))*3600 + ((uint32_t)(rx_DateTime->Min))*60 + (uint32_t)(rx_DateTime->Sec);
UTCTime.day = rx_DateTime->Day;
UTCTime.month = rx_DateTime->Month;
UTCTime.year = rx_DateTime->Year;
}
}
 
ok = true;
}
}
 
return ok; // wenn erfolgreich gelesen dann true (kein timeout)
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
int32_t calc_avg( int32_t avg, int32_t nvalue, int32_t count, int32_t factor)
{
avg = avg + (( ( nvalue * factor) - avg) / count);
return avg;
}
 
 
 
//--------------------------------------------------------------
// OSD_MK_GetData()
//
// Holt Daten der BL-Ctrl via NC.
//
// Die Werte der BL's 1-12 kommen in mehr oder weniger beliebiger
// Reihenfolge an. Die Daten fuer vorhandene BL's werden oefter
// gesendet als die von nicht vorhandenen BL's.
//
// Diese Funktioen liest fuer die Zeit BL_READ_TIME die BL-Daten
// vom MK ein und ordnet diese der PKT-internen Speichstruktur zu.
//
// Hierbei ist nicht gewaehrleistet, dass die Daten von jedem BL
// in einem festen Zeitrahmen ermittelt werden. Die Folge ist
// ein 'zufaelliger' Aufbau der Anzeige der BL-Daten und auch
// eine nicht exakt bestimmbare Refreshtime der Werte.
//
// Optimieren kann man ggf. die Refreshzeit aller BL-Werte durch
// tx_intervall fuer Kommando "k" und durch BL_READ_TIME.
// Brauchbare Startwerte sind (noch experimentell):
// tx_interval = 5 (fuer "k") = 50 ms
// BL_READ_TIME = 25 = 250 ms
//
// Wenn dieses Verhalten verbessert werden soll muss ggf.
// die ISR() (usart.c) fuer Kommando "k" angepasst werden um
// in einem Schwung mehrere gesendete BL-Pakete aufeinmal
// aufzunehmen und als Paket zur Verfuegung zu stellen.
//--------------------------------------------------------------
void OSD_MK_GetData( void )
{
BLData_t *rx_blData;
uint8_t blIndex;
uint8_t FCStatusFlags;
uint8_t v;
uint8_t skipBL = false;
 
FCStatusFlags = naviData->FCStatusFlags; // save naviData->FCStatusFlags for use with BL-Data
 
 
//######################################
//# ZEIT/DATUM
//######################################
// lese UTC-Time vom MK
//--------------------------------------
if( timer_get_tidata == 0 )
{
//--------------------------------------------------
// das 'T' Datenpaket der NC fuer OSD_MK_UTCTime()
// gibt es erst ab NC v0.30g (!)
//
// --> Versionspruefung der NC-Firmware
//--------------------------------------------------
 
v = MKVersion_Cmp( MKVersion.NCVer, 0,30,'g' ); // pruefe auf NC-Version >= "0.30g"
 
if( v && (v >= GIVEN_VERSION) ) // wenn aktuelle NC-Version >= "0.30g"...
{
if( !OSD_MK_UTCTime(20) )
timer_get_tidata = 50; // erfolglos: versuche es nach einer 1/2 Sekunde erneut
else
timer_get_tidata = TIME_GET_TIDATA; // alle 60 Sekunden refresh - den Rest uebernimmt ein Timer des PKT
}
}
 
 
 
//######################################
//# MK-DISPLAY
//######################################
// switch to: (h)
//--------------------------------------
//if( timer_get_displaydata == 0 )
if( mkdisplayMode && timer_get_displaydata == 0 )
{
mode = 'H';
rxd_buffer_locked = FALSE;
 
/*
if( mkdisplayCmd != 0xff )
{
if( mkdisplayCmd == 0 ) mkdisplayCmd = 0xff;
SendOutData( 'h', ADDRESS_ANY, 1, &mkdisplayCmd, 1);
}
*/
if( mkdisplayCmd == 0 ) mkdisplayCmd = 0xff;
 
SendOutData( 'h', ADDRESS_ANY, 2, &mkdisplayCmd, 1, 0x00 ,1); // 05.04.2015 Cebra, 2.er Parameter wg NC 2.09i
 
mkdisplayCmd = 0xff; // 0xff = aktuelle Seite
 
timer = 20; while( (timer>0) && !rxd_buffer_locked ); //
 
if( rxd_buffer_locked )
{
Decode64();
memcpy( mkdisplayData, (const void *)&rxd_buffer[3+ 0], 80 ); // sichern...
 
#ifdef USE_OSD_SCREEN_DEBUG
readCounterDISPLAY++;
#endif // USE_OSD_SCREEN_DEBUG
}
 
timer_get_displaydata = TIME_GET_DISPLAYDATA; // n*10 ms
skipBL = true;
} // end: if( mkdisplayMode && timer_get_displaydata == 0 )
 
 
 
//######################################
//# BL-Daten
//######################################
// switch to: 'BL Ctrl Status' (k)
//--------------------------------------
if( !skipBL && timer_get_bldata == 0 )
{
mode = 'K'; // read: BL Ctrl Status
rxd_buffer_locked = FALSE;
 
timer = TIME_READ_BLDATA; // fuer x Zeit werden BL-Daten gelesen
while( timer>0 ) // lese Daten-Pakete fuer die angegebene Zeit
{
if( rxd_buffer_locked )
{
Decode64 ();
rx_blData = (BLData_t *) (pRxData);
 
// die BL-Daten kommen in beliebiger Reihenfolge an
// Hier werden sie entsprechend ihres Index gesichert
blIndex = rx_blData->Index;
if( blIndex >= 0 && blIndex < OSD_MAX_MOTORS )
{
memcpy( &blData[blIndex], rx_blData, sizeof(BLData_t)); // sichern...
 
#ifdef USE_OSD_SCREEN_DEBUG
readCounterBL[blIndex]++;
#endif // USE_OSD_SCREEN_DEBUG
 
// Statistiken
if( (blData[blIndex].Status & 0xf0) && (FCStatusFlags & FC_STATUS_MOTOR_RUN) ) // nur wenn BL/Motor vorhanden und Motoren laufen
{
// BL Statistik: Anzahl empf. Datenpakete (fuer Mittelwert)
Config.OSD_Statistic.BL[blIndex].count++;
 
// int32_t calc_avg( int32_t avg, int32_t value, int32_t count, int32_t factor)
Config.OSD_Statistic.BL[blIndex].avg_Current = (uint16_t) calc_avg( (int32_t)Config.OSD_Statistic.BL[blIndex].avg_Current,
(int32_t)blData[blIndex].Current,
(int32_t)Config.OSD_Statistic.BL[blIndex].count,
100);
 
// ALT
// BL Statistik: Mittelwert: Strom (*100 um Rundungsfehler zu reduzieren)
//avg = (int32_t)Config.OSD_Statistic.BL[blIndex].avg_Current;
//avg = avg + (( ( (int32_t)blData[blIndex].Current * 100) - avg) / (int32_t)Config.OSD_Statistic.BL[blIndex].count);
//Config.OSD_Statistic.BL[blIndex].avg_Current = (uint16_t)avg;
 
// BL Statistik: Max: Strom
if( blData[blIndex].Current > Config.OSD_Statistic.BL[blIndex].max_Current) Config.OSD_Statistic.BL[blIndex].max_Current = blData[blIndex].Current;
 
// BL Statistik: Max: Temperatur
if( blData[blIndex].Temperature > Config.OSD_Statistic.BL[blIndex].max_Temp) Config.OSD_Statistic.BL[blIndex].max_Temp = blData[blIndex].Temperature;
if( blIndex+1 > Config.OSD_Statistic.BL_Count ) Config.OSD_Statistic.BL_Count = blIndex+1;
}
}
rxd_buffer_locked = FALSE;
}
}
timer_get_bldata = TIME_GET_BLDATA; // n*10 ms
} // end: if( timer_get_bldata == 0 )
 
 
 
//--------------------------------------
// back to: OSD-Data
//--------------------------------------
mode = 'O'; // read: OSD-Data
rxd_buffer_locked = FALSE; // ready to receive new data
timer_mk_timeout = MK_TIMEOUT; // reset osd MK_TIMEOUT timer
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void variobeep(int16_t vario)
{
#ifdef USE_SOUND
{ //start Beep
 
if (vario >0 ) // MK steigt
{
Vario_Beep_Down = 0; // Down Beep freischalten
Vario_Threshold++;
 
if ((Vario_Beep_Up == 0) && (Vario_Threshold >= Vario_Threshold_Value))
{
// set_beep ( 100, 0xffff, BeepNormal);
duration = 52 -vario;
// if (duration =0); duration = 1;
 
// write_ndigit_number_u (0,6,duration,5,0);
 
playTone(300+vario*2,duration,Config.Volume);
 
// playTone(300,duration,volume);
Vario_Threshold = Vario_Threshold_Value; // auf Maximalwert begrenzen
}
Vario_Beep_Up++; // Interval hochzählen in dem nicht gepiept wird
if (Vario_Beep_Up == Vario_Beep_Up_Interval) Vario_Beep_Up = 0;
}
 
if (vario <0) // MK fällt
{
Vario_Beep_Up = 0; // Up Beep freischalten
Vario_Threshold++;
if ((Vario_Beep_Down == 0) && (Vario_Threshold >= Vario_Threshold_Value))
{
duration = 50 -vario;
// write_ndigit_number_u (0,7,duration,5,0);
// if (duration < vario) ; duration = 0;
// playTone(300,50,volume);
 
 
playTone(300+vario*2,duration,Config.Volume);
 
Vario_Threshold = Vario_Threshold_Value; // auf Maximalwert begrenzen
}
Vario_Beep_Down++; // Interval hochzählen in dem nicht gepiept wird
if (Vario_Beep_Down == Vario_Beep_Down_Interval) Vario_Beep_Down = 0;
}
 
if (vario == 0) Vario_Threshold = 0; //Startverzögerung löschen
} // end Beep
#endif
}
 
 
//--------------------------------------------------------------
// Diese Funktion Beept unabhaengig von der Einstellung Config.OSD_VarioBeep
// Aufruf ggf. mit: if( Config.OSD_VarioBeep ) Beep_Vario();
//
// Ansonten:
// -> hier noch aufräumen in Zusammenhang mit func variobeep()
//--------------------------------------------------------------
void Beep_Vario(void)
{
if ( (naviData->FCStatusFlags & FC_STATUS_MOTOR_RUN) && (naviData->FCStatusFlags2 & FC_STATUS2_ALTITUDE_CONTROL))
{ //start Beep
if (naviData->Variometer <0) // MK fällt
{
Vario_Beep_Up = 0; // Up Beep freischalten
Vario_Threshold++;
if ((Vario_Beep_Down == 0) && (Vario_Threshold >= Vario_Threshold_Value))
{
 
if (!Config.HWSound) set_beep ( 300, 0xffff, BeepNormal);
else variobeep(naviData->Variometer);
 
Vario_Threshold = Vario_Threshold_Value; // auf Maximalwert begrenzen
}
Vario_Beep_Down++; // Interval hochzählen in dem nicht gepiept wird
if (Vario_Beep_Down == Vario_Beep_Down_Interval) Vario_Beep_Down = 0;
}
 
if (naviData->Variometer == 0) Vario_Threshold = 0; //Startverzögerung löschen
 
if (naviData->Variometer >0 ) // MK steigt
{
Vario_Beep_Down = 0; // Down Beep freischalten
Vario_Threshold++;
 
if ((Vario_Beep_Up == 0) && (Vario_Threshold >= Vario_Threshold_Value))
{
if (!Config.HWSound) set_beep ( 100, 0xffff, BeepNormal);
else variobeep(naviData->Variometer);
Vario_Threshold = Vario_Threshold_Value; // auf Maximalwert begrenzen
}
Vario_Beep_Up++; // Interval hochzählen in dem nicht gepiept wird
if (Vario_Beep_Up == Vario_Beep_Up_Interval) Vario_Beep_Up = 0;
}
} // end Beep
}
 
 
 
//--------------------------------------------------------------
// Quelle Mikrokopter FC-Software Holger + Ingo
//--------------------------------------------------------------
void CheckMKLipo( void )
{
if( Config.MK_LowBat < 50 ) // automatische Zellenerkennung
{
if( CellIsChecked <= 2 ) // nur beim Start 1x prüfen
{
// up to 6s LiPo, less than 2s is technical impossible
for( cells = 2; cells < 7; cells++)
{
if( naviData->UBat < cells * MAX_CELL_VOLTAGE)
break;
}
BattLowVoltageWarning = cells * Config.MK_LowBat;
CellIsChecked++;
}
}
else BattLowVoltageWarning = Config.MK_LowBat;
 
if( naviData->UBat < BattLowVoltageWarning)
{
if( AkkuWarnThreshold <= 4)
{
AkkuWarnThreshold++;
}
else if( naviData->FCStatusFlags & FC_STATUS_MOTOR_RUN )
{
// MK-Unterspannungs-Beep nur wenn Motoren laufen
set_beep ( 1000, 0x0020, BeepSevere);
}
}
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void calc_heading_home(void)
{
int16_t degree;
 
//---------------------------------------
// warum modulo 360:
//
// die NC kann unter gewissen Umstaenden Winkel > 360 Grad
// senden -> fragt H&I warum
//---------------------------------------
degree = ((naviData->CompassHeading % 360) - (naviData->HomePositionDeviation.Bearing % 360));
 
if( degree < 0 )
heading_home = (int16_t)(360 + degree);
else
heading_home = (int16_t)degree;
}
 
 
//--------------------------------------------------------------
// convert the <heading> gotton from NC into an index
uint8_t heading_conv (uint16_t heading)
{
if (heading > 23 && heading < 68)
return 0; //direction = "NE";
else if (heading > 67 && heading < 113)
return 1; //direction = "E ";
else if (heading > 112 && heading < 158)
return 2; //direction = "SE";
else if (heading > 157 && heading < 203)
return 3; //direction = "S ";
else if (heading > 202 && heading < 248)
return 4; //direction = "SW";
else if (heading > 247 && heading < 293)
return 5; //direction = "W ";
else if (heading > 292 && heading < 338)
return 6; //direction = "NW";
 
return 7; //direction = "N ";
}
 
 
//--------------------------------------------------------------
// draw a compass rose at <x>/<y> for <heading>
void draw_compass (uint8_t x, uint8_t y, uint16_t heading, int8_t xoffs, int8_t yoffs)
{
 
uint8_t front = 19 + (heading / 22);
for (uint8_t i = 0; i < 9; i++)
lcdx_putc (x++, y, pgm_read_byte(&rose[front - 4 + i]), MNORMAL, xoffs,yoffs);
}
 
 
//--------------------------------------------------------------
// variometer
// x, y in Pixel!
//--------------------------------------------------------------
void draw_variometer (uint8_t x, uint8_t y, uint8_t width, uint8_t hight, int16_t variometer)
{
lcd_rect (x, y - ((hight) / 2), width, hight, 1);
lcd_frect (x + 1, y - ((hight) / 2) + 1, width - 2, hight - 2, 0);
lcd_line (x, y, x + width, y, 1);
 
if (variometer > 0) // steigend
{
switch (variometer / 5)
{
case 0:
lcd_line (x + 4, y - 1, x + 6, y - 1, 1); // 1 > 4
break;
 
case 1:
lcd_line (x + 4, y - 1, x + 6, y - 1, 1); // 1 > 4
lcd_frect (x + 3, y - 3, 4, 1, 1); // 5 > 9
break;
 
case 2:
lcd_line (x + 4, y - 1, x + 6, y - 1, 1); // 1 > 4
lcd_frect (x + 3, y - 3, 4, 1, 1); // 5 > 9
lcd_frect (x + 2, y - 5, 6, 1, 1); // 10 > 14
break;
 
default:
lcd_line (x + 4, y - 1, x + 6, y - 1, 1); // 1 > 4
lcd_frect (x + 3, y - 3, 4, 1, 1); // 5 > 9
lcd_frect (x + 2, y - 5, 6, 1, 1); // 10 > 14
lcd_frect (x + 1, y - 6, 8, 1, 1); // 15 >
break;
}
}
else if (variometer < 0) // fallend
{
switch ((variometer) / -5)
{
case 0:
lcd_line (x + 4, y + 1, x + 6, y + 1, 1); // - 1 > - 4
break;
 
case 1:
lcd_line (x + 4, y + 1, x + 6, y + 1, 1); // - 1 > - 4
lcd_frect (x + 3, y + 2, 4, 1, 1); // - 5 > - 9
break;
 
case 2:
lcd_line (x + 4, y + 1, x + 6, y + 1, 1); // - 1 > - 4
lcd_frect (x + 3, y + 2, 4, 1, 1); // - 5 > - 9
lcd_frect (x + 2, y + 4, 6, 1, 1); // -10 > -14
break;
 
default:
lcd_line (x + 4, y + 1, x + 6, y + 1, 1); // - 1 > - 4
lcd_frect (x + 3, y + 2, 4, 1, 1); // - 5 > - 9
lcd_frect (x + 2, y + 4, 6, 1, 1); // -10 > -14
lcd_frect (x + 1, y + 5, 8, 1, 1); // -15 >
break;
}
}
}
 
 
//--------------------------------------------------------------
// variometer 2
//
// x, y in Pixel
// x, y top, left
//--------------------------------------------------------------
/*
void draw_variometer2( uint8_t x, uint8_t y, uint8_t width, uint8_t hight, int16_t variometer)
{
uint8_t max = 5; // max: 5 m/sec == 100%
 
lcd_rect (x, y, width, hight, 1);
lcd_frect(x + 1, y + 1, width - 2, hight - 2, 0);
lcd_line (x, y + ((hight) / 2), x + width, y + ((hight) / 2), 1);
 
}
*/
 
 
//--------------------------------------------------------------
// Home symbol
// draw Homesymbol at <x>/<y>
//--------------------------------------------------------------
void draw_homesymbol (uint8_t x, uint8_t y)
{
x *= 6;
y *= 8;
y += 7;
 
lcd_plot (x,y-4,1);
lcd_line (x+1,y-1,x+1,y-5,1);
lcd_plot (x+2,y-6,1);
lcd_plot (x+3,y-7,1);
lcd_plot (x+4,y-6,1);
lcd_line (x+5,y-1,x+5,y-5,1);
lcd_plot (x+6,y-4,1);
lcd_plot (x+3,y-1,1);
lcd_plot (x+3,y-2,1);
lcd_line (x+1,y,x+5,y,1);
 
}
 
 
//--------------------------------------------------------------
// Target symbol
// draw Targetsymbol at <x>/<y>
//--------------------------------------------------------------
void draw_targetsymbol (uint8_t x, uint8_t y)
{
x *= 6;
y *= 8;
y += 7;
 
lcd_circle (x+3, y-3, 4, 1);
lcd_line (x,y-3,x+6,y-3,1);
lcd_line (x+3,y,x+3,y-6,1);
lcd_circle (x+3, y-3, 2, 1);
}
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void writex_altimeter( uint8_t x, uint8_t y, s32 Altimeter, uint8_t mode, int8_t xoffs, int8_t yoffs )
{
if (Altimeter > (300 / AltimeterAdjust) || Altimeter < (-300 / AltimeterAdjust)) // above 10m only write full meters
writex_ndigit_number_s ( x, y, (Altimeter / (30 / AltimeterAdjust)), 4, 0, mode, xoffs,yoffs);
else // up to 10m write meters.dm
writex_ndigit_number_s_10th( x, y, (Altimeter / (3 / AltimeterAdjust)), 3, 0, mode, xoffs,yoffs);
}
 
 
 
//-----------------------------------------------------------
//--------------------------------------------------------------
void lcd_o_circle (uint16_t x, uint16_t y, int16_t breite, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
breite *= 6;
int16_t radius = breite / 2;
x += 2;
x *= 6;
x += 2;
y += 1;
y *= 8;
y += 3;
 
// 04.03.2012 OG: chg: x-radius von -3 auf -2 (runder auf dem display)
//lcd_ellipse (x, y, radius - 3, radius - 5, mode);
lcd_ellipse( x+xoffs, y+yoffs, radius - 2, radius - 5, mode);
}
 
 
//-----------------------------------------------------------
// lcd_o_circ_line( x, y, breite, deg, rOffset, mode)
//
// x, y : in Chars
// breite : in Chars
// deg : in Pixel
// rOffset: Beeinflusst den Schluss der Linie zum Huellkreis
// 0 = Standard
// >0 naeher zum Huellkreis
// <0 entfernter vom Huellkreis
// mode : siehe: lcd_ellipse_line()
//-----------------------------------------------------------
void lcd_o_circ_line( uint16_t x, uint16_t y, uint8_t breite, uint16_t deg, int8_t rOffset, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
breite *= 6;
int16_t radius = breite / 3;
x += 2;
x *= 6;
x += 2;
y += 1;
y *= 8;
y += 3;
 
// 04.03.2013 OG: der Radius kann mit rOffset >0 vergroessert werden um zum Kreis aufzuschliessen
lcd_ellipse_line( x+xoffs, y+yoffs, radius+rOffset, radius+rOffset, deg, mode);
}
 
 
 
 
 
 
 
 
 
 
 
//-----------------------------------------------------------
//--------------------------------------------------------------
void lcdx_o_circle( uint8_t x, uint8_t y, int8_t width, uint8_t mode)
{
int8_t radius = width / 2;
 
// 04.03.2012 OG: chg: x-radius von -3 auf -2 (runder auf dem display)
//lcd_ellipse (x, y, radius - 3, radius - 5, mode);
lcd_ellipse( x, y, radius - 2, radius - 5, mode);
}
 
 
 
//-----------------------------------------------------------
// lcd_o_circ_line( x, y, breite, deg, rOffset, mode)
//
// x, y : in Chars
// breite : in Chars
// deg : in Pixel
// rOffset: Beeinflusst den Schluss der Linie zum Huellkreis
// 0 = Standard
// >0 naeher zum Huellkreis
// <0 entfernter vom Huellkreis
// mode : siehe: lcd_ellipse_line()
//-----------------------------------------------------------
void lcdx_o_circ_line( uint16_t x, uint16_t y, uint8_t breite, uint16_t deg, int8_t rOffset, uint8_t mode, int8_t xoffs, int8_t yoffs)
{
breite *= 6;
int16_t radius = breite / 3;
x += 2;
x *= 6;
x += 2;
y += 1;
y *= 8;
y += 3;
 
// 04.03.2013 OG: der Radius kann mit rOffset >0 vergroessert werden um zum Kreis aufzuschliessen
lcd_ellipse_line( x+xoffs, y+yoffs, radius+rOffset, radius+rOffset, deg, mode);
}
 
 
 
//--------------------------------------------------------------
// PARAMETER:
// x,y : in Pixel
//--------------------------------------------------------------
void draw_icon_mk( uint8_t x, uint8_t y)
{
//lcd_plot( x+0, y+0, 1); // Referenz 0,0
 
lcd_line( x+5, y+0, x+0, y+5, 1); // Dach oben Links
lcd_line( x+5, y+0, x+10, y+5, 1); // Dach oben Rechts
 
lcd_line( x+5, y+10, x+0, y+5, 1); // Dach unten Links
lcd_line( x+5, y+10, x+10, y+5, 1); // Dach unten Rechts
 
lcd_line( x+4, y+5, x+6, y+5, 1); // Innenkreuz Horizontal
lcd_line( x+5, y+4, x+5, y+6, 1); // Innenkreuz Vertikal
}
 
 
 
//--------------------------------------------------------------
// Variante: rund
//
// PARAMETER:
// x,y : in Pixel
//--------------------------------------------------------------
void draw_icon_target_round( uint8_t x, uint8_t y)
{
//lcd_plot( x+0, y+0, 1); // Referenz 0,0
 
lcd_ellipse( x+5, y+5, 5+1, 5, 1); // Aussenkreis
 
//lcd_line( x+2, y+5, x+8, y+5, 1); // Innenkreuz Horizontal (laenger)
lcd_line( x+3, y+5, x+7, y+5, 1); // Innenkreuz Horizontal (kuerzer)
 
lcd_line( x+5, y+3, x+5, y+7, 1); // Innenkreuz Vertikal
}
 
 
 
//--------------------------------------------------------------
// Variante: eckig
//
// PARAMETER:
// x,y : in Pixel
//--------------------------------------------------------------
void draw_icon_target_diamond( uint8_t x, uint8_t y)
{
//lcd_plot( x+0, y+0, 1); // Referenz 0,0
 
lcd_line( x+5, y+0, x+0, y+5, 1); // Dach oben Links
lcd_line( x+5, y+0, x+10, y+5, 1); // Dach oben Rechts
 
lcd_line( x+5, y+10, x+0, y+5, 1); // Dach unten Links
lcd_line( x+5, y+10, x+10, y+5, 1); // Dach unten Rechts
 
lcd_line( x+4, y+5, x+6, y+5, 1); // Innenkreuz Horizontal
lcd_line( x+5, y+4, x+5, y+6, 1); // Innenkreuz Vertikal
}
 
 
 
//--------------------------------------------------------------
// PARAMETER:
// x,y : in Pixel
//--------------------------------------------------------------
void draw_icon_home( uint8_t x, uint8_t y)
{
//lcd_plot( x+0, y+0, 1); // Referenz 0,0
lcd_rect( x+0, y+5, 10, 8, 1); // Mitte
lcd_line( x+5, y+0, x+0, y+5, 1); // Dach Links
lcd_line( x+5, y+0, x+10, y+5, 1); // Dach Rechts
lcd_rect( x+4, y+10, 2, 3, 1); // Tuere
 
}
 
 
 
//--------------------------------------------------------------
// PARAMETER:
// x,y : in Pixel
//--------------------------------------------------------------
void draw_icon_sat( uint8_t x, uint8_t y)
{
//lcd_plot( x+0, y+0, 1); // Referenz 0,0
lcd_rect( x+0, y+2, 4, 2, 1); // linker Fluegel
lcd_rect( x+8, y+2, 4, 2, 1); // rechter Fluegel
lcd_rect( x+4, y+0, 4, 6, 1); // Mitte, oben
lcd_line( x+6, y+7, x+2, y+11, 1); // Strahl Links
lcd_line( x+6, y+7, x+10, y+11, 1); // Strahl Rechts
lcd_line( x+1, y+12, x+11, y+12, 1); // Strahl Unten
}
 
 
 
//--------------------------------------------------------------
// PARAMETER:
// x,y : in Pixel
//--------------------------------------------------------------
void draw_icon_satmini( uint8_t x, uint8_t y)
{
//lcd_plot( x+0, y+0, 1); // Referenz 0,0
 
//lcd_line( x+3, y+3, x+0, y+6, 1); // Strahl Links
 
lcd_line( x+2, y+0, x+4, y+0, 1); //
lcd_line( x+0, y+1, x+6, y+1, 1); //
lcd_line( x+2, y+2, x+4, y+2, 1); //
lcd_plot( x+3, y+1, 0); //
 
lcd_line( x+3, y+3, x+1, y+5, 1); // Strahl Links
lcd_line( x+3, y+3, x+5, y+5, 1); // Strahl Rechts
lcd_line( x+0, y+6, x+6, y+6, 1); // Strahl Unten
}
 
 
 
//--------------------------------------------------------------
// PARAMETER:
// x,y : in Pixel
//--------------------------------------------------------------
void draw_icon_satmini2( uint8_t x, uint8_t y)
{
//lcd_plot( x+0, y+0, 1); // Referenz 0,0
 
//lcd_line( x+3, y+3, x+0, y+6, 1); // Strahl Links
 
lcd_line( x+2, y-1, x+4, y-1, 1); //
//lcd_line( x+2, y+0, x+4, y+0, 1); //
lcd_line( x+0, y+0, x+6, y+0, 1); //
lcd_line( x+0, y+1, x+6, y+1, 1); //
lcd_line( x+2, y+2, x+4, y+2, 1); //
lcd_plot( x+3, y+0, 0); //
lcd_plot( x+3, y+1, 0); //
 
lcd_line( x+3, y+3, x+1, y+5, 1); // Strahl Links
lcd_line( x+3, y+3, x+5, y+5, 1); // Strahl Rechts
lcd_line( x+0, y+6, x+6, y+6, 1); // Strahl Unten
}
 
 
//--------------------------------------------------------------
// PARAMETER:
// x,y : in Pixel
//--------------------------------------------------------------
void draw_icon_battery( uint8_t x, uint8_t y)
{
//lcd_plot( x+0, y+0, 1); // Referenz 0,0
lcd_rect( x+2, y+0, 2, 2, 1); // der kleine Knubbel oben
lcd_rect( x+0, y+2, 6, 15, 1); // body
}
 
 
 
//--------------------------------------------------------------
// RC symbol
// alternatives Symbol fuer RC-Quality
//--------------------------------------------------------------
void draw_symbol_rc( uint8_t x, uint8_t y)
{
x *= 6;
y *= 8;
y += 1;
x += 1;
 
lcd_plot( x+3, y+4, 1);
lcd_line( x+2, y+2, x+4, y+2, 1);
lcd_line( x+1, y+0, x+5, y+0, 1);
}
 
 
 
 
//##############################################################
//# spezielle Beeps
//##############################################################
 
//--------------------------------------------------------------
// Beep_Waypoint()
//
// Beep bei Waypoint Wechsel und wenn die WP-Liste abgearbeitet
// ist
//--------------------------------------------------------------
void Beep_Waypoint( void )
{
//-----------------
// BEEP: WP erreicht
//-----------------
if( naviData->WaypointIndex > WP_old )
{
set_beep( 30, 0xffff, BeepNormal ); // kurzer Bestaetigungs-Beep
}
 
if( (naviData->WaypointIndex == naviData->WaypointNumber)
&& (naviData->NCFlags & NC_FLAG_TARGET_REACHED)
&& (!WP_last)
)
{
set_beep( 400, 0xffff, BeepNormal ); // langer Bestaetigungs-Beep
WP_last = true;
}
 
if( naviData->WaypointIndex != WP_old )
{
WP_old = naviData->WaypointIndex;
}
 
if( (naviData->WaypointIndex != naviData->WaypointNumber) // wenn aktueller WP != WP-Anzahl -> WP_last abschalten
|| !(naviData->NCFlags & NC_FLAG_TARGET_REACHED) // wenn kein TR mehr an ist -> WP_last abschalten
)
{
WP_last = false;
}
 
 
// alter Code zur Orientierung
//if( OldWP != naviData->WaypointIndex )
//{
// OldWP = naviData->WaypointIndex;
// NextWP = true;
//}
//
//if( (NextWP==true) && (naviData->NCFlags & NC_FLAG_TARGET_REACHED) )
//{
// set_beep( 25, 0xffff, BeepNormal ); // kurzer Bestaetigungs-Beep
// NextWP = false;
//}
}
 
 
 
//##############################################################
//# OSD-ELEMENTS
//##############################################################
 
//--------------------------------------------------------------
// OSD_Element_Flag_Label( xC, yC, item, lOn, xoffs, yoffs)
//
// xC, yC : x,y in Characters
// item : OSD_FLAG_AH, OSD_FLAG_PH, usw.
// lOn : true / false
// xoffs,yoffs : x,y Pixelverschiebung
//--------------------------------------------------------------
void OSD_Element_Flag_Label( uint8_t xC, uint8_t yC, uint8_t item, uint8_t lOn, int8_t xoffs, int8_t yoffs)
{
int8_t x = (xC*6)-2;
int8_t y = (yC*8)-1;
uint8_t w = 14;
uint8_t h = 8;
 
const char *labels[OSD_FLAG_COUNT] =
{
PSTR("AH"), // OSD_FLAG_AH Altitue Hold
PSTR("PH"), // OSD_FLAG_PH Position Hold
PSTR("CF"), // OSD_FLAG_CF Care Free
PSTR("CH"), // OSD_FLAG_CH Coming Home
PSTR("o1"), // OSD_FLAG_O1 Out1
PSTR("o2"), // OSD_FLAG_O2 Out2
PSTR("BA"), // OSD_FLAG_BA LowBat warning (MK)
PSTR("CA"), // OSD_FLAG_CA Calibrate
PSTR("ST"), // OSD_FLAG_ST Start
PSTR("MR"), // OSD_FLAG_MR Motor Run
PSTR("FY"), // OSD_FLAG_FY Fly
PSTR("EL"), // OSD_FLAG_EL Emergency Landing
PSTR("FS"), // OSD_FLAG_FS RX Failsave Active
PSTR("GP"), // OSD_FLAG_GP GPS Ok
PSTR("S!"), // OSD_FLAG_S0 GPS-Sat not ok (GPS NOT ok)
PSTR("TU"), // OSD_FLAG_TU Vario Trim Up
PSTR("TD"), // OSD_FLAG_TD Vario Trim Down
PSTR("FR"), // OSD_FLAG_FR Free
PSTR("RL"), // OSD_FLAG_RL Range Limit
PSTR("SL"), // OSD_FLAG_SL No Serial Link
PSTR("TR"), // OSD_FLAG_TR Target Reached
PSTR("MC") // OSD_FLAG_MC Manual Control
};
 
//lcd_plot( x-2, y-2, 1); // Referenz
 
if( yC==0 && yoffs<=0 ) { y = 0; h = 7; }
if( xC==0 && xoffs<=0 ) { x = 0; w = 12; }
 
if( lOn )
{
lcd_frect( x+xoffs, y+yoffs, w, h, 1); // Filler
lcdx_printp_at( xC, yC, labels[item], MINVERS, xoffs,yoffs); // Label
}
else
{
lcd_frect( x+xoffs, y+yoffs, w, h, 0); // clear
}
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void OSD_Element_Flag( uint8_t xC, uint8_t yC, uint8_t item, int8_t xoffs, int8_t yoffs)
{
uint8_t lOn = 0;
 
// FC_StatusFlags 0.88
switch( item )
{
// Altitue Hold
case OSD_FLAG_AH : lOn = (naviData->FCStatusFlags2 & FC_STATUS2_ALTITUDE_CONTROL);
break;
 
// Position Hold
case OSD_FLAG_PH : lOn = (naviData->NCFlags & NC_FLAG_PH);
break;
 
// Coming Home
case OSD_FLAG_CH : lOn = (naviData->NCFlags & NC_FLAG_CH);
break;
 
// Care Free
case OSD_FLAG_CF : lOn = (naviData->FCStatusFlags2 & FC_STATUS2_CAREFREE);
break;
 
// Out1
case OSD_FLAG_O1 : lOn = (naviData->FCStatusFlags2 & FC_STATUS2_OUT1_ACTIVE);
break;
 
// Out2
case OSD_FLAG_O2 : lOn = (naviData->FCStatusFlags2 & FC_STATUS2_OUT2_ACTIVE);
break;
 
// LowBat warning (MK)
case OSD_FLAG_BA : lOn = (naviData->FCStatusFlags & FC_STATUS_LOWBAT);
break;
 
// Calibrate
case OSD_FLAG_CA : lOn = (naviData->FCStatusFlags & FC_STATUS_CALIBRATE);
break;
 
// Start
case OSD_FLAG_ST : lOn = (naviData->FCStatusFlags & FC_STATUS_START);
break;
 
// Motor Run
case OSD_FLAG_MR : lOn = (naviData->FCStatusFlags & FC_STATUS_MOTOR_RUN);
break;
 
// Fly
case OSD_FLAG_FY : lOn = (naviData->FCStatusFlags & FC_STATUS_FLY);
break;
 
// Emergency Landing
case OSD_FLAG_EL : lOn = (naviData->FCStatusFlags & FC_STATUS_EMERGENCY_LANDING);
break;
 
// RC Failsave Active
case OSD_FLAG_FS : lOn = (naviData->FCStatusFlags2 & FC_STATUS2_RC_FAILSAVE_ACTIVE);
break;
 
// GPS ok
case OSD_FLAG_GP : lOn = (naviData->NCFlags & NC_FLAG_GPS_OK);
break;
 
// GPS-Sat not ok (GPS NOT ok)
case OSD_FLAG_S0 : lOn = !(naviData->NCFlags & NC_FLAG_GPS_OK);
break;
 
// Vario Trim Up
case OSD_FLAG_TU : lOn = (naviData->FCStatusFlags & FC_STATUS_VARIO_TRIM_UP);
break;
 
// Vario Trim Down
case OSD_FLAG_TD : lOn = (naviData->FCStatusFlags & FC_STATUS_VARIO_TRIM_DOWN);
break;
 
// Free
case OSD_FLAG_FR : lOn = (naviData->NCFlags & NC_FLAG_FREE);
break;
 
// Range Limit
case OSD_FLAG_RL : lOn = (naviData->NCFlags & NC_FLAG_RANGE_LIMIT);
break;
 
// No Serial Link
case OSD_FLAG_SL : lOn = (naviData->NCFlags & NC_FLAG_NOSERIALLINK);
break;
 
// Target Reached
case OSD_FLAG_TR : lOn = (naviData->NCFlags & NC_FLAG_TARGET_REACHED);
break;
 
// Manual Control
case OSD_FLAG_MC : lOn = (naviData->NCFlags & NC_FLAG_MANUAL_CONTROL);
break;
 
}
 
OSD_Element_Flag_Label( xC, yC, item, lOn, xoffs,yoffs);
}
 
 
//--------------------------------------------------------------
// Anzeige von Steigen / Sinken
//--------------------------------------------------------------
void OSD_Element_UpDown( uint8_t x, uint8_t y, int8_t xoffs, int8_t yoffs)
{
x = (x*6) + xoffs;
y = (y*8) + yoffs;
 
lcd_frect( x, y, 6, 7, 0); // clear
 
if( naviData->Variometer > 2 ) // steigen mehr als 0.2 m/sec (ein guter Wert muss noch in der Praxis ermittelt werden)
{
lcd_line( x+2, y+0, x+0, y+2, 1);
lcd_line( x+2, y+0, x+4, y+2, 1);
}
else if( naviData->Variometer < -2 ) // sinken mehr als 0.2 m/sec
{
lcd_line( x+2, y+6, x+0, y+4, 1);
lcd_line( x+2, y+6, x+4, y+4, 1);
}
 
}
 
 
//--------------------------------------------------------------
// OSD_Element_Altitude( x, y, nStyle)
// nStyle entspricht dem ehemaligen 'Mode'
//--------------------------------------------------------------
void OSD_Element_Altitude( uint8_t x, uint8_t y, uint8_t nStyle )
{
 
#ifdef USE_FONT_BIG
 
switch( nStyle )
{
case 0 :
case 1 : //note:lephisto:according to several sources it's /30
if (naviData->Altimeter > (300 / AltimeterAdjust) || naviData->Altimeter < (-300 / AltimeterAdjust)) // above 10m only write full meters
write_ndigit_number_s (x, y, naviData->Altimeter / (30 / AltimeterAdjust), 4, 0,MNORMAL);
else // up to 10m write meters.dm
write_ndigit_number_s_10th (x, y, naviData->Altimeter / (3 / AltimeterAdjust), 3, 0,MNORMAL);
 
lcd_printp_at (x+4, y, PSTR("m"), MNORMAL);
lcd_putc (x+5, y, 0x09, 0); // Hoehensymbol
break;
 
case 2 : //note:lephisto:according to several sources it's /30
if (naviData->Altimeter > (300 / AltimeterAdjust) || naviData->Altimeter < (-300 / AltimeterAdjust)) // above 10m only write full meters
write_ndigit_number_s (x+4, y, naviData->Altimeter / (30 / AltimeterAdjust), 4, 0,MBIG);
else // up to 10m write meters.dm
write_ndigit_number_s_10th (x+4, y, naviData->Altimeter / (3 / AltimeterAdjust), 3, 0,MBIG);
lcd_putc( x+8, y, 'm', MBIG);
lcd_printp_at (x, y, PSTR("Höhe"), MNORMAL);
break;
}
 
#else
 
if( nStyle == 2 )
{
lcd_printp_at (x, y, PSTR("Höhe"), MNORMAL);
x += 4;
}
else
{
lcd_putc (x+5, y, 0x09, 0); // Hoehensymbol
}
 
if (naviData->Altimeter > (300 / AltimeterAdjust) || naviData->Altimeter < (-300 / AltimeterAdjust)) // above 10m only write full meters
write_ndigit_number_s (x, y, naviData->Altimeter / (30 / AltimeterAdjust), 4, 0,MNORMAL);
else // up to 10m write meters.dm
write_ndigit_number_s_10th (x, y, naviData->Altimeter / (3 / AltimeterAdjust), 3, 0,MNORMAL);
 
lcd_printp_at (x+4, y, PSTR("m"), MNORMAL);
 
#endif
 
}
 
 
//--------------------------------------------------------------
// fuer: Config.OSD_LipoBar==1
//--------------------------------------------------------------
void OSD_Element_BatteryLevel_Bar( uint8_t x, uint8_t y )
{
uint16_t Balken = 0;
 
drawmode = (naviData->UBat < BattLowVoltageWarning ? 2 : 0);
 
if( cells > 0 ) // LipobargraphAnzeige nur wenn Anzahl der Lipozellen bekannt sind
{
write_ndigit_number_u (x+6, y, cells, 1, 0, drawmode);
lcd_printp_at (x+7, y, PSTR("S"), drawmode);
 
if( cells==3 )
{
lcd_rect(x*6, y*8, 28, 7, 1); // Rahmen
Balken = ((naviData->UBat-(cells*MIN_CELL_VOLTAGE))*10)/12;
if((Balken > 0) && (Balken <28)) lcd_frect((x*6)+1, (y*8)+1, Balken, 5, 1); // Fuellung
if(Balken <= 26) lcd_frect(Balken+(x*6)+1, (y*8)+1, 26-Balken, 5, 0); // loeschen
}
 
if( cells==4 ||cells==5 )
{
lcd_rect(x*6, y*8, 30, 7, 1); // Rahmen
if (cells == 4) Balken = ((naviData->UBat-(cells*MIN_CELL_VOLTAGE))*10)/15;
if (cells == 5) Balken = ((naviData->UBat-(cells*MIN_CELL_VOLTAGE))*10)/19;
if ((Balken > 0) && (Balken <=29)) lcd_frect((x*6)+1, (y*8)+1, Balken, 5, 1); // Fuellung
if (Balken <= 27) lcd_frect(Balken+(x*6)+1, (y*8)+1, 28-Balken, 5, 0); // loeschen
}
 
} // end if: cells > 0 (TODO: Anzeige fuer cells==0 implementieren)
}
 
 
 
//--------------------------------------------------------------
// fuer die neuen OSD-Screens
//--------------------------------------------------------------
void OSD_Element_BattLevel2( uint8_t x, uint8_t y, int8_t xoffs, int8_t yoffs )
{
drawmode = (naviData->UBat < BattLowVoltageWarning ? MINVERS : MNORMAL);
 
if( Config.OSD_ShowCellU )
{
// kalk. Einzelzellen Spannungsanzeige
writex_ndigit_number_u_100th( x, y, (uint16_t)((naviData->UBat*10)/cells), 3, 0, drawmode, xoffs,yoffs);
lcdx_printp_at( x+4, y, PSTR("v"), drawmode, xoffs+1,yoffs); // Einheit (Einzelzellenanzeige ca., berechnet)
}
else
{
// Gesamtspannungsanzeige
writex_ndigit_number_u_10th( x, y, naviData->UBat, 3, 0, drawmode, xoffs,yoffs);
lcdx_printp_at( x+4, y, PSTR("V"), drawmode, xoffs+1,yoffs); // Einheit (Gesamtspannung)
}
 
lcd_line( (x+4)*6, y*8, (x+4)*6, y*8+7, (drawmode==MINVERS ? 1 : 0) ); // filler zwischen Spannung und "V"
 
}
 
 
//--------------------------------------------------------------
// fuer: Config.OSD_LipoBar==0
// nStyle entspricht dem ehemaligen 'Mode'
//--------------------------------------------------------------
void OSD_Element_BatteryLevel_Text( uint8_t x, uint8_t y, uint8_t nStyle )
{
#ifdef USE_FONT_BIG
if( nStyle <= 1)
drawmode = (naviData->UBat < BattLowVoltageWarning ? 2 : 0); // Normal-Schrift
else
drawmode = (naviData->UBat < BattLowVoltageWarning ? 4 : 3); // Fett-Schrift
 
if( nStyle <= 1)
{
write_ndigit_number_u_10th (x, y, naviData->UBat, 3, 0, drawmode);
lcd_printp_at (x+4, y, PSTR("V"), drawmode);
}
else
{
write_ndigit_number_u_10th (x-2, y, naviData->UBat, 3, 0, drawmode);
lcd_printp_at (x+2, y, PSTR("V"), drawmode);
}
#else
drawmode = (naviData->UBat < BattLowVoltageWarning ? 2 : 0); // Normal-Schrift
 
if( nStyle == 2)
x += 3;
write_ndigit_number_u_10th (x, y, naviData->UBat, 3, 0, drawmode);
lcd_printp_at (x+4, y, PSTR("V"), drawmode);
#endif
}
 
 
//--------------------------------------------------------------
// OSD_Element_Battery_Bar( x, y, length, width, orientation)
//
// neue Variante (OG 06/2013)
//
// Parameter:
// length : Gesamtlaenge des Bar's
// width : Breite in Pixel (fest)
// orientation: ORIENTATION_V - Vertikal (x,y oberer,linker Punkt)
// ORIENTATION_H
//--------------------------------------------------------------
void OSD_Element_Battery_Bar( uint8_t x, uint8_t y, uint8_t length, uint8_t width, uint8_t orientation)
{
uint8_t bat_umax;
uint8_t bat_umin;
uint8_t bat_uact;
int8_t bat_p;
 
// die Min/Max Spannungswerte sind jetzt erstmal fest vorgegeben bzw. berechnet, eine individuelle
// Anpassung waere moeglich aber wenn besser ist es, wenn der User das nicht machen muesste...
bat_umax = cells * 42;
//bat_umin = cells * 32;
bat_umin = cells * 34; // 3.4 Volt pro Zelle Minimum
 
bat_uact = naviData->UBat;
 
bat_p = length * (bat_uact-bat_umin) / (bat_umax-bat_umin);
 
if( bat_p < 0 ) bat_p = 0;
if( bat_p > length ) bat_p = length;
 
if( width == 1 ) width = 0; // eine kleine Eigenart von frect um es zu ueberreden eine Linie zu zeichnen
 
if( orientation == ORIENTATION_V )
{
lcd_frect( x, y , width, length-bat_p, 0); // clear: vertical
lcd_frect( x, y+length-bat_p, width, bat_p, 1); // draw: vertical
}
else
{
lcd_frect( x+bat_p, y, length-bat_p, width, 0); // clear:
lcd_frect( x , y, bat_p , width, 1); // draw:
}
}
 
 
//--------------------------------------------------------------
// nStyle entspricht dem ehemaligen 'Mode'
//--------------------------------------------------------------
void OSD_Element_BatteryLevel( uint8_t x, uint8_t y, uint8_t nStyle )
{
if( Config.OSD_LipoBar )
OSD_Element_BatteryLevel_Bar( x, y);
else
OSD_Element_BatteryLevel_Text( x, y, nStyle);
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void OSD_Element_Capacity( uint8_t x, uint8_t y )
{
drawmode = (naviData->UsedCapacity > Config.OSD_mAh_Warning ? 2 : 0);
 
write_ndigit_number_u (x, y, naviData->UsedCapacity, 5, 0, drawmode);
lcd_printp_at (x+5, y, PSTR("mAh"), drawmode);
// BeepTime = 3000;
// BeepMuster = 0x0020;
}
 
 
 
//--------------------------------------------------------------
// OSD_Element_CompassDegree( x, y, nStyle)
// nStyle entspricht dem ehemaligen 'Mode'
//--------------------------------------------------------------
void OSD_Element_CompassDegree( uint8_t x, uint8_t y, uint8_t nStyle )
{
switch( nStyle )
{
case 0 :
case 1 : write_ndigit_number_u (x, y, (naviData->CompassHeading)%360, 3, 0,MNORMAL);
x += 3;
break;
 
case 2 :
#ifdef USE_FONT_BIG
write_ndigit_number_u (x, y, (naviData->CompassHeading)%360, 3, 0,MBIG);
#else
write_ndigit_number_u (x+5, y, (naviData->CompassHeading)%360, 3, 0,MNORMAL);
#endif
 
x += 8;
break;
}
lcd_putc( x, y, 0x1E, MNORMAL); // degree symbol
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void OSD_Element_CompassDirection( uint8_t x, uint8_t y, int8_t xoffs, int8_t yoffs )
{
lcdx_printp_at (x, y, (const char *) (pgm_read_word ( &(directions_p[heading_conv((naviData->CompassHeading)%360)]))), MNORMAL, xoffs,yoffs);
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void OSD_Element_CompassRose( uint8_t x, uint8_t y )
{
draw_compass (x, y, (naviData->CompassHeading)%360, 0,0);
}
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void OSD_Element_Current( uint8_t x, uint8_t y )
{
write_ndigit_number_u_10th (x, y, naviData->Current, 3, 0,0);
lcd_printp_at (x+4, y, PSTR("A"), 0);
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void OSD_Element_FlyingTime( uint8_t x, uint8_t y )
{
write_time (x, y, naviData->FlyingTime);
lcd_printp_at (x+5, y, PSTR("m"), 0);
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void OSD_Element_GroundSpeed( uint8_t x, uint8_t y )
{
write_ndigit_number_u (x, y, (uint16_t) (((uint32_t) naviData->GroundSpeed * (uint32_t) 9) / (uint32_t) 250), 3, 0,0);
lcd_printp_at (x+3, y, PSTR("Kmh"), 0);
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void OSD_Element_HomeCircle( uint8_t x, uint8_t y, uint8_t breite, int8_t rOffset, int8_t xoffs, int8_t yoffs )
{
calc_heading_home();
 
lcd_o_circle( x, y, breite, 1, xoffs,yoffs);
lcd_o_circ_line( x, y, breite, (old_hh + 180), rOffset, 0, xoffs,yoffs);
lcd_o_circ_line( x, y, breite, (heading_home + 180), rOffset, 1, xoffs,yoffs);
 
old_hh = heading_home;
}
 
 
 
//--------------------------------------------------------------
// NEU! 22.04.2014 OG
// soll das alte OSD_Element_HomeCircle() komplett ersetzen wenn
// die alten OSD-Screens endgueltig rausfliegen
//--------------------------------------------------------------
void OSD_Element_HomeCircleX( uint8_t px, uint8_t py, uint8_t rx, int8_t ry )
{
calc_heading_home();
lcd_ellipse_line( px, py, rx, ry, (old_hh + 180), 0);
lcd_ellipse_line( px, py, rx, ry, (heading_home + 180), 1);
lcd_ellipse( px, py, rx, ry, 1);
old_hh = heading_home;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void OSD_Element_HomeDegree( uint8_t x, uint8_t y )
{
write_ndigit_number_u (x, y, heading_home, 3, 0,0);
lcd_putc (x+3, y, 0x1e, 0); // degree symbol
}
 
 
//--------------------------------------------------------------
// OSD_Element_HomeDistance( x, y, nStyle)
//--------------------------------------------------------------
void OSD_Element_HomeDistance( uint8_t x, uint8_t y, uint8_t nStyle )
{
switch( nStyle )
{
case 0 :
case 1 : write_ndigit_number_u (x, y, naviData->HomePositionDeviation.Distance / 10, 3, 0,0);
lcd_putc (x+3, y, 'm', 0);
draw_homesymbol(x+4, y);
break;
 
case 2 : lcd_printp_at (x, y, PSTR("Home"), 0);
write_ndigit_number_u (x+5, y, naviData->HomePositionDeviation.Distance / 10, 3, 0,0);
lcd_printp_at (x+8, y, PSTR("m -"), 0);
break;
}
}
 
 
//--------------------------------------------------------------
// OSD_Element_LEDOutput( x, y, bitmask)
//
// bitmask: LED1 = FC_STATUS2_OUT1_ACTIVE
// LED2 = FC_STATUS2_OUT2_ACTIVE
//--------------------------------------------------------------
void OSD_Element_LEDOutput( uint8_t x, uint8_t y, uint8_t bitmask )
{
uint8_t lOn;
 
lOn = (naviData->FCStatusFlags2 & bitmask ? 1 : 0); // Bit gesetzt?
lOn = (Config.OSD_InvertOut ? !lOn : lOn); // Invertieren?
lOn = (lOn ? 1 : 0); // auf 0 oder 1 setzen
 
lcd_fcircle (x * 6 + 5, y * 8 + 3, Config.OSD_LEDform, lOn);
lcd_circle (x * 6 + 5, y * 8 + 3, 3, 1);
}
 
 
//--------------------------------------------------------------
// OSD_Element_LED1Output( x, y)
//--------------------------------------------------------------
void OSD_Element_LED1Output( uint8_t x, uint8_t y )
{
OSD_Element_LEDOutput( x, y, FC_STATUS2_OUT1_ACTIVE );
}
 
 
//--------------------------------------------------------------
// OSD_Element_LED2Output( x, y)
//--------------------------------------------------------------
void OSD_Element_LED2Output( uint8_t x, uint8_t y )
{
OSD_Element_LEDOutput( x, y, FC_STATUS2_OUT2_ACTIVE );
}
 
 
//--------------------------------------------------------------
// OSD_Element_Manuell( x, y)
//--------------------------------------------------------------
void OSD_Element_Manuell( uint8_t x, uint8_t y )
{
if (naviData->NCFlags & NC_FLAG_MANUAL_CONTROL)
lcd_putc (x, y, 'M', 0); // rc transmitter
else
lcd_putc (x, y, 'X', 0); // clear
}
 
 
 
//--------------------------------------------------------------
// OSD_Element_RCIntensity( x, y)
//--------------------------------------------------------------
void OSD_Element_RCIntensity( uint8_t x, uint8_t y )
{
write_ndigit_number_u (x, y, naviData->RC_Quality, 3, 0,0);
//lcd_printp_at (x+3, y, PSTR("\x1F"), 0); // RC-transmitter
if (naviData->NCFlags & NC_FLAG_NOSERIALLINK)
{
lcd_printpns_at(x+3, y, PSTR(" "), 0); // Clear
}
else
{
lcd_printpns_at(x+3, y, PSTR("PC"), 0);
}
}
 
 
//--------------------------------------------------------------
// OSD_Element_SatsInUse( x, y, nStyle)
//
// nStyle == 0: "00s"
// nStyle == 1: wie 0
// nStyle == 2: "00 Sat"
//
// nStyle entspricht dem ehemaligen 'Mode'
//--------------------------------------------------------------
void OSD_Element_SatsInUse( uint8_t x, uint8_t y, uint8_t nStyle )
{
drawmode = (naviData->NCFlags & NC_FLAG_GPS_OK ? 0 : 2);
 
switch( nStyle )
{
case 0 :
case 1 : write_ndigit_number_u (x, y, naviData->SatsInUse, 2, 0, drawmode);
lcd_putc (x+2, y, 0x08, drawmode);
break;
 
case 2 : write_ndigit_number_u (x, y, naviData->SatsInUse, 2, 0, drawmode);
lcd_printp_at (x+2, y, PSTR(" Sat"), drawmode);
break;
}
}
 
 
 
//--------------------------------------------------------------
// OSD_Element_Variometer( x, y)
//--------------------------------------------------------------
void OSD_Element_Variometer( uint8_t x, uint8_t y )
{
x *= 6;
y *= 8;
y += 7;
 
draw_variometer (x, y, 10, 14, naviData->Variometer);
}
 
 
//--------------------------------------------------------------
// OSD_Element_Target( x, y, nStyle)
//
// nStyle entspricht dem ehemaligen 'Mode'
// nStyle = 0,1: "000m"
// nStyle = 2,3: "Ziel 000m -"
//--------------------------------------------------------------
void OSD_Element_Target( uint8_t x, uint8_t y, uint8_t nStyle )
{
if( nStyle <= 1 )
{
write_ndigit_number_u (x, y, naviData->TargetPositionDeviation.Distance / 10, 3, 0,0);
lcd_putc (x+3, y, 'm', 0);
draw_targetsymbol(x+4,y);
}
else
{
lcd_printp_at (x, y, PSTR("Ziel"), 0);
write_ndigit_number_u (x+5, y, naviData->TargetPositionDeviation.Distance / 10, 3, 0,0);
lcd_printp_at (x+8, y, PSTR("m -"), 0);
}
}
 
 
//--------------------------------------------------------------
// TODO:
// - pruefen ob beep hier an richtiger Stelle ist
//--------------------------------------------------------------
void OSD_Element_VarioWert( uint8_t x, uint8_t y )
{
uint8_t FC_Fallspeed;
 
FC_Fallspeed = (unsigned int)naviData->Variometer;
FC_Fallspeed = 255-FC_Fallspeed;
 
drawmode = ( (naviData->Variometer < 0) && (FC_Fallspeed > Config.OSD_Fallspeed) ? 2 : 0);
 
 
if( Config.OSD_VarioBeep )
Beep_Vario(); // Beep ???
 
if( drawmode == 2 )
{
if( !Config.HWSound )
set_beep ( 1000, 0x0060, BeepNormal); // muss ein Beep hier hin????
else
variobeep(naviData->Variometer); // muss ein Beep hier hin????
}
 
write_ndigit_number_s_10th (x, y, naviData->Variometer, 3,0, drawmode);
lcd_printpns_at(x+4, y, PSTR("ms"), drawmode);
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void OSD_Element_WayPoint( uint8_t x, uint8_t y )
{
if (!OldWP == naviData->WaypointIndex)
{
// BeepTime = 500;
// BeepMuster = 0x0080;
OldWP = naviData->WaypointIndex;
NextWP = true;
}
 
if ((NextWP==true)&& naviData->NCFlags & NC_FLAG_TARGET_REACHED)
{
set_beep ( 500, 0x0080, BeepNormal);
NextWP = false;
}
 
write_ndigit_number_u (x+2, y, naviData->WaypointIndex , 2, 0,0);
 
lcd_printp_at (x, y, PSTR("WP"), 0);
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void OSD_Element_TargetDegree( uint8_t x, uint8_t y )
{
write_ndigit_number_u (x, y, naviData->TargetPositionDeviation.Bearing/ 10, 3, 0,0);
lcd_putc (x+3, y, 0x1e, 0); // degree symbol
}
 
 
 
//##############################################################
//# OSD-SCREENS
//##############################################################
 
//--------------------------------------------------------------
// OSD-Screen "General"
//
// OSDScreenRefresh: 0 = update values
// 1 = redraw labels and update values
//--------------------------------------------------------------
void OSD_Screen_General( void )
{
//-----------------------------------------
// REDRAW
// statische Screen Elemente die nicht
// jedesmal neu gezeichnet werden muessen
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// Display: 128 x 64 with 6x8 Font => 21 x 8
 
// Linien: Horizontal
lcd_line (0, 28, 127, 28, 1); // mitte
lcd_line (0, 51, 127, 51, 1); // unten
 
// Linien: Vertikal
lcd_line (65, 0, 65, 50, 1); // mitte
 
//-----------------------------------------
// Block: Oben - Links
//-----------------------------------------
draw_icon_battery(0,4);
lcdx_printp_at( 7, 2, PSTR(" mA"), MNORMAL, 0,2);
 
//-----------------------------------------
// Block: Oben - Rechts
//-----------------------------------------
lcdx_printp_at( 12, 0, PSTR("Alt:") , MNORMAL, 0,0);
lcdx_printp_at( 12, 1, PSTR("Dir:") , MNORMAL, 0,1);
lcdx_putc( 20, 1, SYMBOL_SMALLDEGREE, MNORMAL, 1,1);
lcdx_printp_at( 12, 2, PSTR(" I:") , MNORMAL, 0,2);
lcdx_putc( 20, 2, 'A', MNORMAL, 2,2);
 
//-----------------------------------------
// Block: Unten - Links
//-----------------------------------------
draw_icon_sat(0,33);
lcdx_printp_at( 6, 5, PSTR(" kmh"), MNORMAL, 0,1);
 
//-----------------------------------------
// Block: Unten - Rechts
//-----------------------------------------
draw_icon_home( 70, 32);
lcdx_putc( 20, 4, 'm', MNORMAL, 2,0);
lcdx_putc( 20, 5, SYMBOL_SMALLDEGREE, MNORMAL, 1,1);
 
//-----------------------------------------
// unterste Zeile
//-----------------------------------------
draw_symbol_rc( 20, 7); // RC-transmitter
//lcdx_putc( 20, 7, SYMBOL_RCQUALITY, MNORMAL, 2,0);
}
 
//-----------------
// Batt Level (Graph)
//-----------------
OSD_Element_Battery_Bar( 2, 8, 11, 2, ORIENTATION_V);
 
//-----------------
// Batt Level (Volt)
//-----------------
OSD_Element_BattLevel2( 2, 0, 0,0 );
 
//-----------------
// LowBat Warnung MK
//-----------------
OSD_Element_Flag( 8, 0, OSD_FLAG_BA, 0,0 );
 
//-----------------
// Flugzeit
//-----------------
writex_time(2, 1, naviData->FlyingTime, MNORMAL, 0,1);
 
//-----------------
// entnommene Kapazitaet (mAh)
//-----------------
drawmode = (naviData->UsedCapacity > Config.OSD_mAh_Warning ? MINVERS : MNORMAL);
writex_ndigit_number_u( 2, 2, naviData->UsedCapacity, 5, 0, drawmode, 0,2);
 
//-----------------
// Höhe
//-----------------
writex_altimeter( 16, 0, naviData->Altimeter, MNORMAL, 0,0 );
/*
if (naviData->Altimeter > (300 / AltimeterAdjust) || naviData->Altimeter < (-300 / AltimeterAdjust)) // above 10m only write full meters
write_ndigit_number_s ( 16, 0, naviData->Altimeter / (30 / AltimeterAdjust), 4, 0, MNORMAL);
else // up to 10m write meters.dm
write_ndigit_number_s_10th( 16, 0, naviData->Altimeter / (3 / AltimeterAdjust), 3, 0, MNORMAL);
*/
 
//-----------------
// steigen / sinken
//-----------------
OSD_Element_UpDown( 20, 0, 2,0);
 
//-----------------
// Compass Degree
//-----------------
writex_ndigit_number_u (17, 1, (naviData->CompassHeading)%360, 3, 0,MNORMAL, 0,1);
 
//-----------------
// Strom
//-----------------
//write_ndigit_number_u_10th( 16, 2, naviData->Current, 3, 0,0); // alternativ mit Nachkomma
writex_ndigit_number_u( 17, 2, naviData->Current/10, 3, 0,MNORMAL, 0,2);
 
//-----------------
// Sat Anzahl
//-----------------
write_ndigit_number_u (4, 4, naviData->SatsInUse, 2, 0,MNORMAL);
 
//-----------------
// Sat Warnung "!"
//-----------------
/*
if( naviData->NCFlags & NC_FLAG_GPS_OK )
lcd_printp_at( 9, 4, PSTR(" "), MNORMAL);
else
lcd_printp_at( 9, 4, PSTR("!"), MNORMAL);
*/
OSD_Element_Flag( 8, 4, OSD_FLAG_S0, -1,0 ); // Sat Warnung (GPS not ok)
 
//-----------------
// Geschwindigkeit
//-----------------
writex_ndigit_number_u( 3, 5, (uint16_t) (((uint32_t) naviData->GroundSpeed * (uint32_t) 9) / (uint32_t) 250), 3, 0,MNORMAL, 0,1);
 
//-----------------
// Home Distance
//-----------------
write_ndigit_number_u( 17, 4, naviData->HomePositionDeviation.Distance / 10, 3, 0,MNORMAL);
 
//-----------------
// Home Winkel
//-----------------
writex_ndigit_number_u( 16, 5, heading_home, 4, 0,MNORMAL, 0,1);
 
//-----------------
// Flags
//-----------------
OSD_Element_Flag( 1, 7, OSD_FLAG_CF, 0,0 ); // Care Free
OSD_Element_Flag( 4, 7, OSD_FLAG_AH, 0,0 ); // Altitude Hold
OSD_Element_Flag( 7, 7, OSD_FLAG_PH, 0,0 ); // Position Hold
OSD_Element_Flag( 10, 7, OSD_FLAG_CH, 0,0 ); // Coming Home
OSD_Element_Flag( 13, 7, OSD_FLAG_EL, 0,0 ); // Emergency Landing
 
//-----------------
// RC-Quality (MK)
//-----------------
write_ndigit_number_u( 17, 7, naviData->RC_Quality, 3, 0,MNORMAL);
 
#ifdef USE_OSD_DEMO
//-----------------
// Flags
//-----------------
OSD_Element_Flag_Label( 8, 0, OSD_FLAG_BA, true, 0,0 ); // DEMO: Batterie Warnung
OSD_Element_Flag_Label( 8, 4, OSD_FLAG_S0, true, -1,0 ); // DEMO: Sat Warnung (GPS not ok)
 
OSD_Element_Flag_Label( 1, 7, OSD_FLAG_CF, true, 0,0 ); // DEMO
OSD_Element_Flag_Label( 4, 7, OSD_FLAG_AH, true, 0,0 ); // DEMO
OSD_Element_Flag_Label( 7, 7, OSD_FLAG_PH, true, 0,0 ); // DEMO
OSD_Element_Flag_Label( 10, 7, OSD_FLAG_CH, true, 0,0 ); // DEMO
OSD_Element_Flag_Label( 13, 7, OSD_FLAG_EL, true, 0,0 ); // DEMO
#endif
}
 
 
 
//--------------------------------------------------------------
// OSD-Screen "Navigation"
//
// OSDScreenRefresh: 0 = update values
// 1 = redraw labels and update values
//--------------------------------------------------------------
#ifdef USE_OSD_SCREEN_NAVIGATION
void OSD_Screen_Navigation( void )
{
int8_t xoffs, yoffs;
int16_t degree;
uint8_t minus;
 
//-----------------------------------------
// REDRAW
// statische Screen Elemente die nicht
// jedesmal neu gezeichnet werden muessen
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// do things here for static screen elements like labels and so....
 
lcd_line( (6*6-3), 0, (6*6-3), 11, 1); // Linie Vertikal links
lcd_line( (15*6+5), 0, (15*6+5), 11, 1); // Linie Vertikal rechts
lcd_line( 0, 12, 127, 12, 1); // Linie Horizontal
 
lcdx_printp_at( 0, 2, PSTR("Alt:"), MNORMAL, 0,2); // Hoehe
lcdx_printp_at( 0, 5, PSTR("Home:"), MNORMAL, 0,3); // Home Distance
}
 
 
//-----------------
// Oben: Batt Level (Volt)
//-----------------
OSD_Element_BattLevel2( 0, 0, 0,0 );
 
//-----------------
// Oben: Batt Level Bar
//-----------------
//OSD_Element_Battery_Bar( x, y, length, width, orientation)
OSD_Element_Battery_Bar( 0, 9, 30, 1, ORIENTATION_H);
 
//-----------------
// Oben: Kompass Rose
//-----------------
draw_compass( 6, 0, (naviData->CompassHeading)%360, 2,0);
 
//-----------------
// Oben: Flugzeit
//-----------------
writex_time(16, 0, naviData->FlyingTime, MNORMAL, 2,0);
 
//-----------------
// Hoehe
//-----------------
xoffs = 0;
yoffs = 3;
writex_altimeter( 0, 3, naviData->Altimeter, MNORMAL, xoffs,yoffs );
 
//-----------------
// Steigen / Sinken
//-----------------
OSD_Element_UpDown( 4, 3, 1,yoffs);
 
//-----------------
// Home Distance
//-----------------
yoffs = 3;
writex_ndigit_number_u( 0, 6, naviData->HomePositionDeviation.Distance / 10, 4, 0,MNORMAL, 0,yoffs+1);
lcdx_printp_at( 4, 6, PSTR("m"), MNORMAL, 2,yoffs+1); // Home
 
//-----------------
// Home Circle
//-----------------
 
//void OSD_Element_HomeCircleX( uint8_t px, uint8_t py, uint8_t rx, int8_t ry )
 
xoffs = 2;
yoffs = 3;
 
//OSD_Element_HomeCircleX( 64, 38, 25, 22 ); // entspricht dem ehemaligem Huellkreis
OSD_Element_HomeCircleX( 64, 38, 26, 22 ); // leicht erweiterter Huellkreis
 
lcd_frect( (9*6)-3+xoffs, (4*8)-2+yoffs, (3*6)+4, (1*8)+2, 0); // inner clear
lcd_rect ( (9*6)-4+xoffs, (4*8)-3+yoffs, (3*6)+6, (1*8)+4, 1); // inner rect
lcd_frect( 61+xoffs, 57+yoffs, 2, 2, 1); // bottom mini rect
 
degree = (int16_t)heading_home;
minus = false;
if( degree >= 180 ) degree = 360 - degree;
else minus = true;
 
writex_ndigit_number_u( 9, 4, degree, 3, 0,MNORMAL, xoffs+1,yoffs); // Degree (Winkel)
 
if( minus && degree != 0 )
lcd_line( (9*6)-2+xoffs, (4*8)+3+yoffs, (9*6)-1+xoffs, (4*8)+3+yoffs, 1);
 
 
//-----------------
// Variometer
//-----------------
// OG: Variometer wird erstmal nicht angezeigt weil es den Screen zu voll macht
// wenn doch muessen erst grafische Anpassungen an den Variometer-Code gemacht
// werden
//void draw_variometer (uint8_t x, uint8_t y, uint8_t width, uint8_t hight, int16_t variometer)
//draw_variometer( 95, 38, 7, 30, naviData->Variometer);
//draw_variometer( 94, 38, 7, 21, naviData->Variometer);
//draw_variometer2( 94, 28, 7, 21, naviData->Variometer);
 
//-----------------
// Flags
//-----------------
OSD_Element_Flag( 16, 2, OSD_FLAG_BA, -3, 0); // MK Batt Warning
OSD_Element_Flag( 19, 2, OSD_FLAG_CF, 0, 0); // Carefree
OSD_Element_Flag( 19, 4, OSD_FLAG_AH, 0,-3); // Altitude Hold
OSD_Element_Flag( 19, 6, OSD_FLAG_PH, 0,-6); // Position Hold
OSD_Element_Flag( 19, 7, OSD_FLAG_CH, 0,-1); // Coming Home
OSD_Element_Flag( 16, 7, OSD_FLAG_S0, -3,-1); // GPS-Sat not ok (GPS NOT ok)
 
 
#ifdef USE_OSD_DEMO
//-----------------
// Flags
//-----------------
OSD_Element_Flag_Label( 16, 2, OSD_FLAG_BA, true, -3,0); // DEMO
 
OSD_Element_Flag_Label( 19, 2, OSD_FLAG_CF, true, 0,0); // DEMO
OSD_Element_Flag_Label( 19, 4, OSD_FLAG_AH, true, 0,-3); // DEMO
OSD_Element_Flag_Label( 19, 6, OSD_FLAG_PH, true, 0,-6); // DEMO
OSD_Element_Flag_Label( 19, 7, OSD_FLAG_CH, true, 0,-1); // DEMO
 
OSD_Element_Flag_Label( 16, 7, OSD_FLAG_S0, true, -3,-1); // DEMO
#endif
}
#endif // USE_OSD_SCREEN_NAVIGATION
 
 
 
 
//--------------------------------------------------------------
// OSD-Screen "OSD_Screen_Waypoints_OLD"
//
// alte, alternative Variante - wenn sich die neue Variante
// durchsetzt kann das hier geloescht werden
//--------------------------------------------------------------
#ifdef USE_OSD_SCREEN_WAYPOINTS
/*
void OSD_Screen_Waypoints_OLD( void )
{
int8_t xoffs, yoffs;
 
//-----------------------------------------
// REDRAW
// statische Screen Elemente die nicht
// jedesmal neu gezeichnet werden muessen
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// do things here for static screen elements like labels and so....
 
lcd_line( (6*6-3), 0, (6*6-3), 11, 1); // Linie Vertikal links
lcd_line( (15*6+5), 0, (15*6+5), 11, 1); // Linie Vertikal rechts
//lcd_line( 0, 12, 127, 12, 1); // Linie Horizontal
 
lcd_rect_round( 0, 12, 127, 63-19+7, 1, R2); // Rahmen
 
lcd_line( 0, 12+25, 127, 12+25, 1); // Trennlinie in der Mitte
 
draw_icon_home( 7, 18);
draw_icon_target_round( 7, 45);
//draw_icon_target_diamond( 7, 45); // Alternative fuer draw_icon_target_round()
}
 
 
//-----------------
// Oben: Batt Level (Volt)
//-----------------
OSD_Element_BattLevel2( 0, 0, 0,0 );
 
//-----------------
// Oben: Batt Level Bar
//-----------------
//OSD_Element_Battery_Bar( x, y, length, width, orientation)
OSD_Element_Battery_Bar( 0, 9, 30, 1, ORIENTATION_H);
 
//-----------------
// Oben: Kompass Rose
//-----------------
//draw_compass( 6, 0, (naviData->CompassHeading)%360, 2,0);
 
//-----------------
// Oben: Flugzeit
//-----------------
writex_time(16, 0, naviData->FlyingTime, MNORMAL, 2,0);
 
//-----------------
// Home: Hoehe
//-----------------
xoffs = 6;
yoffs = 0;
writex_altimeter( 7, 2, naviData->Altimeter, MNORMAL, xoffs,yoffs );
lcdx_printp_at( 3, 2, PSTR("Al:"), MNORMAL, xoffs+2,yoffs);
 
//-----------------
// Home: Steigen / Sinken
//-----------------
OSD_Element_UpDown( 13, 2, -2,yoffs);
 
//-----------------
// Home: Distance
//-----------------
yoffs = 2;
lcdx_printp_at( 3, 3, PSTR("Ho:"), MNORMAL, xoffs+2,yoffs);
writex_ndigit_number_u( 7, 3, naviData->HomePositionDeviation.Distance / 10, 4, 0,MNORMAL, xoffs,yoffs);
lcdx_printp_at(11, 3, PSTR("m"), MNORMAL, xoffs+4,yoffs); // Home
 
//-----------------
// Home: Circle
//-----------------
xoffs = 2;
yoffs = 3;
 
//OSD_Element_HomeCircleX( px, py, rx, ry )
//OSD_Element_HomeCircleX( 64, 38, 26, 22 ); // leicht erweiterter Huellkreis
OSD_Element_HomeCircleX( 112, 24, 10, 8 ); // leicht erweiterter Huellkreis
 
//lcd_frect( 112-1, 33, 2, 1, 1); // bottom mini rect
lcd_frect( 112-1, 33, 2, 0, 1); // bottom mini rect
lcd_frect( 112-0, 33, 0, 1, 1); // bottom mini rect
 
 
//-----------------
// WP: Waypoint-Index und Anzahl der Waypoint's
//-----------------
xoffs = 6;
yoffs = 2;
lcdx_printp_at( 3, 5, PSTR("WP:"), MNORMAL, xoffs+2,yoffs);
 
uint8_t wpindex = naviData->WaypointIndex;
if( naviData->WaypointNumber==0 ) wpindex = 0;
 
lcdx_printf_at_P( 7, 5, MNORMAL, xoffs,yoffs, PSTR("%2d/%2d"), wpindex, naviData->WaypointNumber );
 
 
//-----------------
// Sat Anzahl
//-----------------
writex_ndigit_number_u( 17, 5, naviData->SatsInUse, 2, 0,MNORMAL, 0,2);
draw_icon_satmini( 117, 42);
 
 
//-----------------
// WP: Distance
//-----------------
yoffs = 4;
lcdx_printp_at( 3, 6, PSTR("Di:"), MNORMAL, xoffs+2,yoffs);
writex_ndigit_number_u( 7, 6, naviData->TargetPositionDeviation.Distance / 10, 4, 0,MNORMAL, xoffs,yoffs);
lcdx_printp_at( 11, 6, PSTR("m"), MNORMAL, xoffs+4,yoffs); //
 
//-----------------
// WP: Hoehe
// Anmerkung OG: macht nicht so wirklich Sinn denke ich
//-----------------
//writex_ndigit_number_u( 14, 6, naviData->TargetPosition.Altitude / 1000, 4, 0,MNORMAL, xoffs,yoffs);
//lcdx_printp_at( 18, 6, PSTR("m"), MNORMAL, xoffs+4,yoffs); //
 
 
//-----------------
// Oben: Flags
//-----------------
// Variante 1: PH, CH, CF
//OSD_Element_Flag( 7, 0, OSD_FLAG_PH, -2,1); // Position Hold
//OSD_Element_Flag( 9, 0, OSD_FLAG_CH, 5,1); // Coming Home
//OSD_Element_Flag( 12, 0, OSD_FLAG_CF, 6,1); // Carefree
 
// Variante 2: CF, CH, TR
OSD_Element_Flag( 7, 0, OSD_FLAG_CF, -2,1); // Carefree
OSD_Element_Flag( 9, 0, OSD_FLAG_CH, 5,1); // Coming Home
OSD_Element_Flag( 12, 0, OSD_FLAG_TR, 6,1); // Target Reached
 
 
// Variante: TR neben Waypoint-Anzahl
//OSD_Element_Flag( 13, 5, OSD_FLAG_TR, 6,2); // Target Reached
 
 
//-----------------
// ggf. BEEP wenn WP erreicht
//-----------------
Beep_Waypoint();
}
*/
#endif // USE_OSD_SCREEN_WAYPOINTS
 
 
 
//--------------------------------------------------------------
// OSD-Screen "Waypoints"
//
// aktuelle Variante!
//--------------------------------------------------------------
#ifdef USE_OSD_SCREEN_WAYPOINTS
void OSD_Screen_Waypoints( void )
{
int8_t xoffs, yoffs;
uint8_t v;
 
//-----------------------------------------
// REDRAW
// statische Screen Elemente die nicht
// jedesmal neu gezeichnet werden muessen
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// do things here for static screen elements like labels and so....
 
lcd_line( (6*6-3), 0, (6*6-3), 11, 1); // Linie Vertikal links
lcd_line( (15*6+5), 0, (15*6+5), 11, 1); // Linie Vertikal rechts
//lcd_line( 0, 12, 127, 12, 1); // Linie Horizontal
 
lcd_rect_round( 0, 12, 127, 63-19+7, 1, R2); // Rahmen
 
lcd_line( 0, 12+25, (15*6+5), 12+25, 1); // Trennlinie in der Mitte
lcd_line( (15*6+5), 12+25, (15*6+5), 63, 1); // Linie Vertikal rechts, unten
lcd_plot ((15*6+5), 12+25, 0);
 
draw_icon_home( 7, 18);
draw_icon_target_round( 7, 45);
//draw_icon_target_diamond( 7, 45); // Alternative fuer draw_icon_target_round()
}
 
 
//-----------------
// Oben,Links: Batt Level (Volt)
//-----------------
OSD_Element_BattLevel2( 0, 0, 0,0 );
 
//-----------------
// Oben,Links: Batt Level Bar
//-----------------
//OSD_Element_Battery_Bar( x, y, length, width, orientation)
OSD_Element_Battery_Bar( 0, 9, 30, 1, ORIENTATION_H);
 
//-----------------
// Oben,Rechts: Flugzeit
//-----------------
writex_time(16, 0, naviData->FlyingTime, MNORMAL, 2,0);
 
//-----------------
// Oben,Mitte: Flags
//-----------------
// Variante 1: PH, CH, CF
//OSD_Element_Flag( 7, 0, OSD_FLAG_PH, -2,1); // Position Hold
//OSD_Element_Flag( 9, 0, OSD_FLAG_CH, 5,1); // Coming Home
//OSD_Element_Flag( 12, 0, OSD_FLAG_CF, 6,1); // Carefree
 
// Variante 2: CF, CH, TR
OSD_Element_Flag( 7, 0, OSD_FLAG_CF, -2,1); // Carefree
OSD_Element_Flag( 9, 0, OSD_FLAG_CH, 5,1); // Coming Home
OSD_Element_Flag( 12, 0, OSD_FLAG_TR, 6,1); // Target Reached
 
 
 
//-----------------
// Home: Hoehe
//-----------------
xoffs = 5;
yoffs = 0;
writex_altimeter( 7, 2, naviData->Altimeter, MNORMAL, xoffs,yoffs );
lcdx_printp_at( 3, 2, PSTR("Al:"), MNORMAL, xoffs+3,yoffs);
 
//-----------------
// Home: Steigen / Sinken
//-----------------
OSD_Element_UpDown( 13, 2, -3,yoffs);
 
//-----------------
// Home: Distance
//-----------------
yoffs = 2;
lcdx_printp_at( 3, 3, PSTR("Ho:"), MNORMAL, xoffs+3,yoffs);
writex_ndigit_number_u( 7, 3, naviData->HomePositionDeviation.Distance / 10, 4, 0,MNORMAL, xoffs,yoffs);
lcdx_printp_at(11, 3, PSTR("m"), MNORMAL, xoffs+4,yoffs); // Home
 
//-----------------
// Home: Circle
//-----------------
// orginal
//OSD_Element_HomeCircleX( 110, 25, 11, 9 ); // leicht erweiterter Huellkreis
//lcd_frect( 112-3, 35, 2, 1, 1); // bottom mini rect
 
// 1 pixel weiter links
OSD_Element_HomeCircleX( 109, 25, 11, 9 ); // leicht erweiterter Huellkreis
lcd_frect( 112-4, 35, 2, 1, 1); // bottom mini rect
 
// etwas groesser
//OSD_Element_HomeCircleX( 109, 26, 12, 10 ); // leicht erweiterter Huellkreis
//lcd_frect( 112-4, 37, 2, 1, 1); // bottom mini rect
 
//-----------------
// Home: Sat Anzahl
//-----------------
//yoffs = -2; // alternativ
yoffs = 0;
//naviData->SatsInUse = 10;
writex_ndigit_number_u( 17, 5, naviData->SatsInUse, 2, 0,MNORMAL, -1,2+yoffs);
draw_icon_satmini( 115, 42+yoffs);
 
 
 
//-----------------
// WP: Waypoint-Index und Anzahl der Waypoint's
//-----------------
xoffs = 5;
yoffs = 2;
lcdx_printp_at( 3, 5, PSTR("WP:"), MNORMAL, xoffs+3,yoffs);
 
v = naviData->WaypointIndex;
if( naviData->WaypointNumber==0 ) v = 0;
 
lcdx_printf_at_P( 7, 5, MNORMAL, xoffs,yoffs, PSTR("%2d/%2d"), v, naviData->WaypointNumber );
 
 
//-----------------
// WP: Countdown Target-Holdtime
//-----------------
xoffs = 6;
yoffs = 2;
 
v = naviData->TargetHoldTime;
if( v > 0 )
{
lcdx_printf_at_P( 12, 5, MINVERS, xoffs+2,yoffs, PSTR("%2d"), v );
lcd_line( (12*6)+xoffs+2, (5*8)+yoffs-1, (12*6)+xoffs+2+11, (5*8)+yoffs-1, 1);
lcd_line( (12*6)+xoffs+1, (5*8)+yoffs-1, (12*6)+xoffs+1, (5*8)+yoffs+7, 1);
}
else
{
lcd_frect( (12*6)+xoffs+1, (5*8)+yoffs-1, (2*8)-3, 8, 0);
}
 
 
//-----------------
// WP: Distance
//-----------------
xoffs = 5;
yoffs = 4;
lcdx_printp_at( 3, 6, PSTR("Di:"), MNORMAL, xoffs+3,yoffs);
writex_ndigit_number_u( 7, 6, naviData->TargetPositionDeviation.Distance / 10, 4, 0,MNORMAL, xoffs,yoffs);
lcdx_printp_at( 11, 6, PSTR("m"), MNORMAL, xoffs+4,yoffs); //
 
//-----------------
// WP: Hoehe
// Anmerkung OG: macht nicht so wirklich Sinn denke ich
//-----------------
//writex_ndigit_number_u( 14, 6, naviData->TargetPosition.Altitude / 1000, 4, 0,MNORMAL, xoffs,yoffs);
//lcdx_printp_at( 18, 6, PSTR("m"), MNORMAL, xoffs+4,yoffs); //
 
 
 
 
//-----------------
// ggf. BEEP wenn WP erreicht
//-----------------
Beep_Waypoint();
}
#endif // USE_OSD_SCREEN_WAYPOINTS
 
 
 
//--------------------------------------------------------------
// OSD-Screen "User GPS"
//
// OSDScreenRefresh: OSD_SCREEN_REFESH = update values
// OSD_SCREEN_REDRAW = redraw labels and update values
//--------------------------------------------------------------
#ifdef USE_OSD_SCREEN_USERGPS
void OSD_Screen_UserGPS( void )
{
uint8_t y, i;
int8_t yoffs;
uint8_t show_gps_altitude = 0; // 1=GPS-Höhe anzeigen; 0=barymetrische Höhe anzeigen
 
 
//-----------------------------------------
// REDRAW
// statische Screen Elemente die nicht
// jedesmal neu gezeichnet werden muessen
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// do things here for static screen elements like labels and so....
lcd_line( (6*6-3), 0, (6*6-3), 9, 1); // Linie vertikal oben, links
lcd_line( (15*6+3), 0, (15*6+3), 9, 1); // Linie vertikal oben, rechts
lcd_rect_round( 0, 9, 127, 63-9, 1, R2); // Rahmen
lcdx_printp_at( 6, 0, PSTR("UGPS"), MNORMAL, 2,0);
}
 
 
//-----------------
// Oben: Batt Level (Volt)
//-----------------
OSD_Element_BattLevel2( 0, 0, 0,0 );
 
//-----------------
// Oben: Sat Ok
//-----------------
OSD_Element_Flag( 12, 0, OSD_FLAG_S0, 5,0); // GPS-Sat not ok (GPS NOT ok)
 
//-----------------
// Oben: Flugzeit
//-----------------
writex_time( 16, 0, naviData->FlyingTime, MNORMAL, 2,0);
 
//-----------------
// die letzen 3 User-GPS Daten anzeigen
//-----------------
yoffs = -4;
for(i=0; i<3; i++)
{
y = (i*2)+2;
lcd_frect( 0, (y*8)+yoffs-1, 127, 7, 1); // inverser Hintergrund
 
writex_ndigit_number_u( 0, y+0, (i+1), 1, 0 , MINVERS, 4,yoffs); // Index
writex_datetime_time( 4, y+0, Config.GPS_User[i].timestamp, MINVERS, 0,yoffs);
 
//writex_time( 3, y+0, GPS_User[i].time_pkt, MINVERS, 0,yoffs);
//lcdx_printp_at( 12, y+0, PSTR("Alt:") , MINVERS, 0,yoffs);
lcdx_printp_at( 20, y+0, PSTR("m") , MINVERS, 0,yoffs);
 
if( show_gps_altitude ) // GPS-Hoehe oder barymetrische Hoehe?
{
// GPS Hoehe
//lcdx_printp_at( 10, y+0, PSTR("G"), MINVERS, 2,yoffs);
//lcd_frect( (12*6)-4, (y*8)+3+yoffs, 1, 1, 0);
writex_ndigit_number_s( 16, y+0, Config.GPS_User[i].GPSData.Altitude/1000, 4, 0, MINVERS, 0,yoffs); // GPS Hoehe in Meter
}
else
{
// barymetrische Hoehe
//lcdx_printp_at( 10, y+0, PSTR("B"), MINVERS, 2,yoffs);
//lcd_frect( (12*6)-4, (y*8)+3+yoffs, 1, 1, 0);
writex_altimeter( 16, y+0, Config.GPS_User[i].Altimeter, MINVERS, 0,yoffs );
}
 
lcd_line( 1, (y*8)+yoffs+7, 125, (y*8)+yoffs+7, 0); // clear: Invers unterste Linie
 
writex_gpspos( 1, y+1, Config.GPS_User[i].GPSData.Latitude , MNORMAL, 0,yoffs); // GPS Lat
writex_gpspos( 12, y+1, Config.GPS_User[i].GPSData.Longitude, MNORMAL, 0,yoffs); // GPS Long
//writex_gpspos( 1, y+1, GPS_User[i].GPSData.Latitude + 12867000, MNORMAL, 0,yoffs); // DUMMY DATEN! DEMO!
//writex_gpspos( 12, y+1, GPS_User[i].GPSData.Longitude+ 8568000, MNORMAL, 0,yoffs); // DUMMY DATEN! DEMO!
 
yoffs++;
}
}
#endif // USE_OSD_SCREEN_USERGPS
 
 
 
//--------------------------------------------------------------
// OSD-Screen "Status"
//
// OSDScreenRefresh: 0 = update values
// 1 = redraw labels and update values
//--------------------------------------------------------------
#ifdef USE_OSD_SCREEN_MKSTATUS
void OSD_Screen_MKStatus( void )
{
int8_t xoffs, yoffs;
 
//-----------------------------------------
// REDRAW
// statische Screen Elemente die nicht
// jedesmal neu gezeichnet werden muessen
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// do things here for static screen elements like labels and so....
 
lcd_line( (6*6-3), 0, (6*6-3), 9, 1); // Linie vertikal oben, links
lcd_line( (15*6+3), 0, (15*6+3), 9, 1); // Linie vertikal oben, rechts
lcd_rect_round( 0, 10, 127, 63-10, 1, R2); // Rahmen
 
lcdx_printp_at( 12,0 , PSTR("mAh"), MNORMAL, -1,0); // "mAh" (entnommene Kapazität)
}
 
 
//-----------------
// Oben: Batt Level (Volt)
//-----------------
OSD_Element_BattLevel2( 0, 0, 0,0 );
 
//-----------------
// Strom
//-----------------
//writex_ndigit_number_u_10th( 7, 0, naviData->Current, 4, 0,MNORMAL, 1,0); // Strom mit Nachkomma
 
//-----------------
// entnommene Kapazitaet (mAh)
//-----------------
drawmode = (naviData->UsedCapacity > Config.OSD_mAh_Warning ? MINVERS : MNORMAL);
//writex_ndigit_number_u( 7, 0, naviData->UsedCapacity * 10, 5, 0, drawmode, -3,0); // DEBUG
writex_ndigit_number_u( 7, 0, naviData->UsedCapacity, 5, 0, drawmode, -3,0);
 
//-----------------
// Oben: Flugzeit
//-----------------
writex_time( 16, 0, naviData->FlyingTime, MNORMAL, 2,0);
 
//-----------------
// Flags
//-----------------
yoffs = -2;
xoffs = -7;
OSD_Element_Flag( 19, 2, OSD_FLAG_CF, 0+xoffs, 0+yoffs); // Carefree
OSD_Element_Flag( 19, 4, OSD_FLAG_AH, 0+xoffs,-3+yoffs); // Altitude Hold
OSD_Element_Flag( 19, 6, OSD_FLAG_PH, 0+xoffs,-6+yoffs); // Position Hold
OSD_Element_Flag( 19, 7, OSD_FLAG_CH, 0+xoffs,-1+yoffs); // Coming Home
 
xoffs -= 4;
OSD_Element_Flag( 16, 2, OSD_FLAG_BA, -3+xoffs, 0+yoffs); // MK Batt Warning
OSD_Element_Flag( 16, 4, OSD_FLAG_EL, -3+xoffs,-3+yoffs); // Emergency Landing
OSD_Element_Flag( 16, 6, OSD_FLAG_RL, -3+xoffs,-6+yoffs); // Range Limit
OSD_Element_Flag( 16, 7, OSD_FLAG_S0, -3+xoffs,-1+yoffs); // GPS-Sat not ok (GPS NOT ok)
 
xoffs -= 4;
OSD_Element_Flag( 12, 2, OSD_FLAG_CA, 0+xoffs, 0+yoffs); // Calibrate
OSD_Element_Flag( 12, 4, OSD_FLAG_ST, 0+xoffs,-3+yoffs); // Start
OSD_Element_Flag( 12, 6, OSD_FLAG_MR, 0+xoffs,-6+yoffs); // Motor Run
OSD_Element_Flag( 12, 7, OSD_FLAG_FY, 0+xoffs,-1+yoffs); // Fly
 
xoffs -= 4;
OSD_Element_Flag( 9, 2, OSD_FLAG_O1, -2+xoffs, 0+yoffs); // Out1
OSD_Element_Flag( 9, 4, OSD_FLAG_O2, -2+xoffs,-3+yoffs); // Out2
OSD_Element_Flag( 9, 6, OSD_FLAG_TR, -2+xoffs,-6+yoffs); // Target Reached
OSD_Element_Flag( 9, 7, OSD_FLAG_MC, -2+xoffs,-1+yoffs); // Manual Control
 
xoffs -= 4;
OSD_Element_Flag( 6, 2, OSD_FLAG_TU, -4+xoffs, 0+yoffs); // Vario Trim Up
OSD_Element_Flag( 6, 4, OSD_FLAG_TD, -4+xoffs,-3+yoffs); // Vario Trim Down
OSD_Element_Flag( 6, 6, OSD_FLAG_FR, -4+xoffs,-6+yoffs); // Free
OSD_Element_Flag( 6, 7, OSD_FLAG_SL, -4+xoffs,-1+yoffs); // No Serial Link
 
 
#ifdef USE_OSD_DEMO
//-----------------
// Flags
//-----------------
/*
PSTR("AH"), // OSD_FLAG_AH Altitue Hold
PSTR("PH"), // OSD_FLAG_PH Position Hold
PSTR("CF"), // OSD_FLAG_CF Care Free
PSTR("CH"), // OSD_FLAG_CH Coming Home
PSTR("o1"), // OSD_FLAG_O1 Out1
PSTR("o2"), // OSD_FLAG_O2 Out2
PSTR("BA"), // OSD_FLAG_BA LowBat warning (MK)
PSTR("CA"), // OSD_FLAG_CA Calibrate
PSTR("ST"), // OSD_FLAG_ST Start
PSTR("MR"), // OSD_FLAG_MR Motor Run
PSTR("FY"), // OSD_FLAG_FY Fly
PSTR("EL"), // OSD_FLAG_EL Emergency Landing
PSTR("FS"), // OSD_FLAG_FS RX Failsave Active
PSTR("GP"), // OSD_FLAG_GP GPS Ok
PSTR("S!") // OSD_FLAG_S0 GPS-Sat not ok (GPS NOT ok)
PSTR("TU"), // OSD_FLAG_TU Vario Trim Up
PSTR("TD"), // OSD_FLAG_TD Vario Trim Down
PSTR("FR"), // OSD_FLAG_FR Free
PSTR("RL"), // OSD_FLAG_RL Range Limit
PSTR("SL"), // OSD_FLAG_SL No Serial Link
PSTR("TR"), // OSD_FLAG_TR Target Reached
PSTR("MC") // OSD_FLAG_MC Manual Control
*/
yoffs = -2;
xoffs = -7;
OSD_Element_Flag_Label( 19, 2, OSD_FLAG_CF, true, 0+xoffs, 0+yoffs); // DEMO: Carefree
OSD_Element_Flag_Label( 19, 4, OSD_FLAG_AH, true, 0+xoffs,-3+yoffs); // DEMO: Altitude Hold
OSD_Element_Flag_Label( 19, 6, OSD_FLAG_PH, true, 0+xoffs,-6+yoffs); // DEMO: Position Hold
OSD_Element_Flag_Label( 19, 7, OSD_FLAG_CH, true, 0+xoffs,-1+yoffs); // DEMO: Coming Home
 
xoffs -= 4;
OSD_Element_Flag_Label( 16, 2, OSD_FLAG_BA, true, -3+xoffs, 0+yoffs); // DEMO: MK Batt Warning
OSD_Element_Flag_Label( 16, 4, OSD_FLAG_EL, true, -3+xoffs,-3+yoffs); // DEMO: Emergency Landing
OSD_Element_Flag_Label( 16, 6, OSD_FLAG_RL, true, -3+xoffs,-6+yoffs); // DEMO: Range Limit
OSD_Element_Flag_Label( 16, 7, OSD_FLAG_S0, true, -3+xoffs,-1+yoffs); // DEMO: GPS-Sat not ok (GPS NOT ok)
 
xoffs -= 4;
OSD_Element_Flag_Label( 12, 2, OSD_FLAG_CA, true, 0+xoffs, 0+yoffs); // DEMO: Calibrate
OSD_Element_Flag_Label( 12, 4, OSD_FLAG_ST, true, 0+xoffs,-3+yoffs); // DEMO: Start
OSD_Element_Flag_Label( 12, 6, OSD_FLAG_MR, true, 0+xoffs,-6+yoffs); // DEMO: Motor Run
OSD_Element_Flag_Label( 12, 7, OSD_FLAG_FY, true, 0+xoffs,-1+yoffs); // DEMO: Fly
 
xoffs -= 4;
OSD_Element_Flag_Label( 9, 2, OSD_FLAG_O1, true, -2+xoffs, 0+yoffs); // DEMO: Out1
OSD_Element_Flag_Label( 9, 4, OSD_FLAG_O2, true, -2+xoffs,-3+yoffs); // DEMO: Out2
OSD_Element_Flag_Label( 9, 6, OSD_FLAG_TR, true, -2+xoffs,-6+yoffs); // DEMO: Target Reached
OSD_Element_Flag_Label( 9, 7, OSD_FLAG_MC, true, -2+xoffs,-1+yoffs); // DEMO: Manual Control
 
xoffs -= 4;
OSD_Element_Flag_Label( 6, 2, OSD_FLAG_TU, true, -4+xoffs, 0+yoffs); // DEMO: Vario Trim Up
OSD_Element_Flag_Label( 6, 4, OSD_FLAG_TD, true, -4+xoffs,-3+yoffs); // DEMO: Vario Trim Down
OSD_Element_Flag_Label( 6, 6, OSD_FLAG_FR, true, -4+xoffs,-6+yoffs); // DEMO: Free
OSD_Element_Flag_Label( 6, 7, OSD_FLAG_SL, true, -4+xoffs,-1+yoffs); // DEMO: No Serial Link
 
#endif
}
#endif // USE_OSD_SCREEN_MKSTATUS
 
 
 
//--------------------------------------------------------------
// OSD_Screen_Electric()
//
// Anzeige BL-Temperaturen und Stroeme
//--------------------------------------------------------------
#ifdef USE_OSD_SCREEN_ELECTRIC
void OSD_Screen_Electric( void )
{
uint8_t x, y, x0, y0;
int8_t yoffs;
 
//-----------------------------------------
// REDRAW
// statische Screen Elemente die nicht
// jedesmal neu gezeichnet werden muessen
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// do things here for static screen elements like labels and so....
lcd_line (33, 0, 33, 19, 1); // Linie vertikal oben, links
lcd_line (93, 0, 93, 19, 1); // Linie vertikal oben, rechts
 
lcd_rect_round( 0, 19, 127, 63-19, 1, R2); // Rahmen
lcd_line (0, 41, 127, 41, 1); // Linie horizontal mitte
 
lcdx_printp_at( 12,0 , PSTR("mAh"), MNORMAL, -1,0); // entnommene Kapazität
lcdx_printp_at( 12,1 , PSTR("A") , MNORMAL, -1,2); // aktueller Strom
 
writex_ndigit_number_u( 19, 1, cells, 1, 0, MNORMAL, 2,2); // LiPO Cells Wert
lcdx_printp_at( 20,1 , PSTR("s") , MNORMAL, 2,2); // LiPO Cells "s"
 
} // end: if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
//-----------------------------------------
 
 
//-----------------
// Oben: Batt Level (Volt)
//-----------------
OSD_Element_BattLevel2( 0, 0, 0,0 );
 
//-----------------
// Oben: Batt Level Bar
//-----------------
//OSD_Element_Battery_Bar( x, y, length, width, orientation)
OSD_Element_Battery_Bar( 0, 9, 30, 1, ORIENTATION_H);
 
//-----------------
// Oben: entnommene Kapazitaet (mAh)
//-----------------
drawmode = (naviData->UsedCapacity > Config.OSD_mAh_Warning ? MINVERS : MNORMAL);
writex_ndigit_number_u( 7, 0, naviData->UsedCapacity, 5, 0, drawmode, -3,0);
 
//-----------------
// Oben: Flugzeit
//-----------------
//writex_time(16, 0, naviData->FlyingTime+900, MNORMAL, 2,0); // DEBUG
writex_time( 16, 0, naviData->FlyingTime, MNORMAL, 2,0);
 
//-----------------
// Strom
//-----------------
writex_ndigit_number_u_10th( 7, 1, naviData->Current, 4, 0,MNORMAL, -3,2); // Strom mit Nachkomma
 
//-----------------
// BL 1-8 Temp & Strom
//-----------------
x0 = 1;
y0 = 4;
for( y=0; y<2; y++) // 2 Zeilen (mit je 4 BL's/Motoren)
{
if( y==0 ) yoffs = -9;
else yoffs = -3;
 
for( x=0; x<4; x++) // und 4 BL's/Motoren pro Zeile
{
if( blData[y*4+x].Status & 0xf0 ) // BL/Motor vorhanden?
{
if( blData[y*4+x].Temperature != 0 ) // Anzeige nur wenn Temp != 0 wegen BL-Ctrl v1 die keine Temperatur senden
{
writex_ndigit_number_u( (x*5)+x0, (y*2)+y0+0, ( blData[y*4+x].Temperature ), 3, 0,MNORMAL, 0,yoffs); // Temperatur
lcdx_putc ( (x*5)+3+x0, (y*2)+y0+0, SYMBOL_SMALLDEGREE ,MNORMAL, 1,yoffs);
}
 
// Variante: mit Nachkommastellen
writex_ndigit_number_u_10th ( (x*5)+x0, (y*2)+y0+1, ( blData[y*4+x].Current), 3, 0, MNORMAL, 0,yoffs); // Strom
}
}
}
 
#ifdef USE_OSD_DEMO
OSD_Element_Flag_Label( 19, 1, OSD_FLAG_BA, true, 0,1); // DEMO
#endif
}
#endif // USE_OSD_SCREEN_ELECTRIC_N
 
 
 
 
//--------------------------------------------------------------
// OSD_Screen_Statistics()
//--------------------------------------------------------------
#ifdef USE_OSD_SCREEN_STATISTIC
void OSD_Screen_Statistics( void )
{
osd_BLmax_t blmax;
uint8_t line = 0;
 
 
// max. der BL's ermitteln
calc_BLmax( &blmax );
 
 
//---------------------------
// max Altitude
lcd_printp_at (0, line, strGet(STATS_ITEM_0), MNORMAL);
write_ndigit_number_s (14, line, Config.OSD_Statistic.max_Altimeter / (30 / AltimeterAdjust), 4, 0,MNORMAL);
lcdx_putc (18, line, 'm', MNORMAL, 2,0);
 
//---------------------------
// max Speed
// max_GroundSpeed = 1;
lcd_printp_at (0, ++line, strGet(STATS_ITEM_1), MNORMAL);
write_ndigit_number_u (15, line, (uint16_t) (((uint32_t) Config.OSD_Statistic.max_GroundSpeed * (uint32_t) 9) / (uint32_t) 250), 3, 0,MNORMAL);
lcdx_printp_at(18, line, PSTR("kmh"), MNORMAL, 2,0);
 
//---------------------------
// max Distance
// max_Distance = 64512;
lcd_printp_at (0, ++line, strGet(STATS_ITEM_2), MNORMAL);
write_ndigit_number_u (14, line, Config.OSD_Statistic.max_Distance / 10, 4, 0,MNORMAL);
lcdx_putc (18, line, 'm', MNORMAL, 2,0);
 
//---------------------------
// min voltage
lcd_printp_at (0, ++line, strGet(STATS_ITEM_3), MNORMAL);
if( Config.OSD_Statistic.min_UBat==255 )
lcd_printp_at(14, line, PSTR(" 0"), MNORMAL);
else
write_ndigit_number_u_10th (14, line, Config.OSD_Statistic.min_UBat, 3, 0,MNORMAL);
lcdx_putc (18, line, 'V', MNORMAL, 2,0);
 
//---------------------------
// Used Capacity
lcd_printp_at (0, ++line, strGet(STATS_ITEM_6), MNORMAL);
write_ndigit_number_u (14, line, Config.OSD_Statistic.max_Capacity, 4, 0,MNORMAL);
lcdx_printp_at(18, line, PSTR("mAh"), MNORMAL, 2,0);
 
 
//---------------------------
// max Current
// max_Current = 1000;
lcd_printp_at (0, ++line, strGet(STATS_ITEM_5), MNORMAL);
write_ndigit_number_u_10th (13, line, Config.OSD_Statistic.max_Current, 4, 0,MNORMAL);
lcdx_putc (18, line, 'A', MNORMAL, 2,0);
 
 
//---------------------------
// max BL-Current
line++;
lcd_printp_at( 0, line, PSTR("max BL Curr:"), MNORMAL);
write_ndigit_number_u( 6, line, blmax.max_BL_Current_Index+1, 1, 0,MNORMAL);
write_ndigit_number_u_10th (14, line, blmax.max_BL_Current, 3, 0,MNORMAL);
lcdx_putc (18, line, 'A', MNORMAL, 2,0);
 
//---------------------------
// max BL-Temp
line++;
lcd_printp_at( 0, line, PSTR("max BL Temp:"), MNORMAL);
write_ndigit_number_u( 6, line, blmax.max_BL_Temp_Index+1, 1, 0,MNORMAL);
write_ndigit_number_u (14, line, blmax.max_BL_Temp, 4, 0,MNORMAL);
lcdx_printp_at( 18, line, PSTR("\013C"), MNORMAL, 2,0);
}
#endif // USE_OSD_SCREEN_STATISTIC
 
 
 
//--------------------------------------------------------------
// OSD_Screen_3DLage()
//--------------------------------------------------------------
#ifdef USE_OSD_SCREEN_3DLAGE
void OSD_Screen_3DLage( void )
{
uint16_t head_home;
uint8_t Nick;
uint8_t Roll;
 
//-----------------------------------------
// REDRAW
// statische Screen Elemente die nicht
// jedesmal neu gezeichnet werden muessen
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// do things here for static screen elements like labels and so....
lcd_rect_round( 0, 0, 127, 63-0, 1, R2); // Rahmen
}
 
 
head_home = (naviData->HomePositionDeviation.Bearing + 360 - naviData->CompassHeading) % 360;
 
lcd_line(26,32,100,32,1); // horizontal //
lcd_line(63,0,63,63,1); // vertical //
 
// 45' Angel
lcd_line(61,11,65,11,1); // -- //
lcd_line(40,30,40,34,1); // | //
lcd_line(86,30,86,34,1); // | //
lcd_line(61,53,65,53,1); // -- //
 
lcdx_printp_at( 9, 0, strGet(OSD_3D_V), MNORMAL, 0,4); // V
lcdx_printp_at( 3, 3, strGet(OSD_3D_L), MNORMAL, 0,0); // L
lcdx_printp_at(17, 3, strGet(OSD_3D_R), MNORMAL, 0,0); // R
lcdx_printp_at( 9, 7, strGet(OSD_3D_H), MNORMAL, 0,-3); // H
 
// Oben, Links: Ni
lcdx_printp_at(0, 0, strGet(OSD_3D_NICK), MNORMAL, 5,4); // Ni
writex_ndigit_number_s (2, 0, naviData->AngleNick, 3, 0, MNORMAL, 7,4);
lcdx_putc (5, 0, SYMBOL_SMALLDEGREE, MNORMAL, 7,4);
 
// Unten, Links: Ro
lcdx_printp_at(0, 7, strGet(OSD_3D_ROLL), MNORMAL, 5,-3); // Ro
writex_ndigit_number_s (2, 7, naviData->AngleRoll, 3, 0, MNORMAL, 7,-3);
lcdx_putc (5, 7, SYMBOL_SMALLDEGREE, MNORMAL, 7,-3);
 
// Oben, Rechts: Ko
//lcdx_printp_at(13, 0, strGet(OSD_3D_COMPASS), MNORMAL, -4,3); // Ko
writex_ndigit_number_u (15, 0, (naviData->CompassHeading)%360, 3, 0, MNORMAL, -4,4);
lcdx_putc (18, 0, SYMBOL_SMALLDEGREE, MNORMAL, -4,4);
OSD_Element_CompassDirection( 19, 0, -2,4 );
 
Roll = ((-naviData->AngleRoll/2)+63);
Nick = ((-naviData->AngleNick/2)+32);
 
if( Roll < (9+1) ) Roll = (9+1); // nicht ausserhalb des Screens zeichnen!
if( Roll > 127-(9+1) ) Roll = 127-(9+1); // nicht ausserhalb des Screens zeichnen!
 
if( Nick < (8+1) ) Nick = (8+1); // nicht ausserhalb des Screens zeichnen!
if( Nick > 63-(8+1) ) Nick = 63-(8+1); // nicht ausserhalb des Screens zeichnen!
 
if( old_AngleRoll != 0 ) // nicht ausserhalb des Screens zeichnen!
{
lcd_ellipse ( old_AngleRoll, old_AngleNick, 9, 8, 0);
lcd_ellipse_line( old_AngleRoll, old_AngleNick, 8, 7, old_hh, 0);
}
 
lcd_ellipse ( Roll, Nick, 9, 8, 1);
lcd_ellipse_line( Roll, Nick, 8, 7, head_home, 1);
 
// remember last values (3DL)
old_hh = head_home;
old_AngleNick = Nick;
old_AngleRoll = Roll;
}
#endif // USE_OSD_SCREEN_3DLAGE
 
 
 
 
//--------------------------------------------------------------
// OSD_Screen_MKDisplay()
//
// das ist ein Spezialscreen der ausserhalb der regulaeren
// OSD-Screens aufgerufen und bedient wird!
//--------------------------------------------------------------
//#ifdef USE_OSD_SCREEN_MKDISPLAY
void OSD_Screen_MKDisplay( void )
{
uint8_t wpindex;
 
//-----------------------------------------
// REDRAW
// statische Screen Elemente die nicht
// jedesmal neu gezeichnet werden muessen
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// do things here for static screen elements like labels and so....
lcd_line( (6*6-3), 0, (6*6-3), 11, 1); // Linie Vertikal Oben: links
lcd_line( (15*6+5), 0, (15*6+5), 11, 1); // Linie Vertikal Oben: rechts
lcd_rect_round( 0, 2*7-2, 127, 5*7+3+3, 1, R2); // Rahmen unten fuer Inhalt Display
 
//lcd_frect_round( 6*6+0, 0, 9*6+2, 9, 1, R1); // Umrahmung fuer "OSD-Displ"
//lcdx_printp_at( 7, 0, PSTR("OSD-Disp"), MINVERS, -3,1); // "OSD-Displ"
//lcdx_printp_at(15, 0, PSTR("l"), MINVERS, -4,1); // das "l" von "OSD-Displ" (1 Pixel nach links)
 
lcdx_printp_at( 2, 7, PSTR("\x18 \x19"), MNORMAL, 0,0); // Keyline: Links / Rechts
PKT_KeylineUpDown( 18, 13, 0,0); // Keyline: Down / Up
 
} // end: if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
//-----------------------------------------
 
 
//-----------------
// Oben: Waypoint-Index und Anzahl der Waypoint's
//-----------------
wpindex = naviData->WaypointIndex;
if( naviData->WaypointNumber==0 ) wpindex = 0;
 
lcdx_printf_at_P( 7, 0, MNORMAL, -1,0, PSTR("WP:%2d/%2d"), wpindex, naviData->WaypointNumber );
 
 
//lcdx_printf_at_P(13, 0, MNORMAL, -3,1, PSTR("R:%d"), (naviData->NCFlags & NC_FLAG_TARGET_REACHED) );
//if ((NextWP==true)&& naviData->NCFlags & NC_FLAG_TARGET_REACHED)
//lcd_printf_at_P( 0, 2, MNORMAL, PSTR("WP:%d"), naviData->WaypointIndex);
//write_ndigit_number_u (x+2, y, naviData->WaypointIndex , 2, 0,0);
//lcd_printp_at (x, y, PSTR("WP"), 0);
//if ((NextWP==true)&& naviData->NCFlags & NC_FLAG_TARGET_REACHED)
 
 
 
//-----------------
// Oben: Batt Level (Volt)
//-----------------
OSD_Element_BattLevel2( 0, 0, 0,0 );
 
//-----------------
// Oben: Batt Level Bar
//-----------------
//OSD_Element_Battery_Bar( x, y, length, width, orientation)
OSD_Element_Battery_Bar( 0, 9, 30, 1, ORIENTATION_H);
 
//-----------------
// Oben: Navi-Kreis
//-----------------
//OSD_Element_HomeCircleX( 64, 5, 6, 5, true );
 
 
//-----------------
// Oben: Flugzeit
//-----------------
writex_time(16, 0, naviData->FlyingTime, MNORMAL, 2,0);
 
 
//------------------------------------------
// Ausgabe auf PKT-Anzeige
// 4 Zeilen a 20 Zeichen
//------------------------------------------
mkdisplayData[80] = 0;
lcdx_print_at( 0,5, (uint8_t *) &mkdisplayData[60], MNORMAL, 5,3);
 
mkdisplayData[60] = 0;
lcdx_print_at( 0,4, (uint8_t *) &mkdisplayData[40], MNORMAL, 5,2);
 
mkdisplayData[40] = 0;
lcdx_print_at( 0,3, (uint8_t *) &mkdisplayData[20], MNORMAL, 5,1);
 
mkdisplayData[20] = 0;
lcdx_print_at( 0,2, (uint8_t *) &mkdisplayData[0], MNORMAL, 5,0);
 
Beep_Waypoint();
}
//#endif // USE_OSD_SCREEN_MKDISPLAY
 
 
 
//##############################################################
#ifdef USE_OSD_SCREEN_DEBUG
//##############################################################
 
//**************************************************************
//* OSD_DEBUG_SCREEN - Experimental-Code usw.
//* - nicht fuer die Oeffentlichkeit bestimmt
//* - gesteuert ueber define OSD_DEBUG_SCREEN
//**************************************************************
 
//--------------------------------------------------------------
// OSD_Screen_Debug()
//--------------------------------------------------------------
void OSD_Screen_Debug( void )
{
//char buffer[80];
static uint16_t debug_count = 0;
//char buffer[30];
//uint8_t y, i;
 
 
//-----------------------------------------
// REDRAW
// statische Screen Elemente die nicht
// jedesmal neu gezeichnet werden muessen
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// do things here for static screen elements like labels and so....
lcd_printp_at( 0, 0, PSTR("Debug"), 0);
//timer_pkt_uptime = 0;
}
 
debug_count++;
write_ndigit_number_u( 17, 0, (debug_count), 4, 0,MNORMAL); //
 
 
// act. Current
lcd_printf_at_P( 0, 2, MNORMAL, PSTR("act Current%3.1u A"), naviData->Current);
 
// max. Current
lcd_printf_at_P( 0, 3, MNORMAL, PSTR("max Current%3.1u A"), Config.OSD_Statistic.max_Current);
 
// avg. Current
lcd_printf_at_P( 0, 4, MNORMAL, PSTR("avg Current%3.1u A"), (uint8_t)(Config.OSD_Statistic.avg_Current/100));
 
// avg. Current DEBUG
//lcd_printf_at_P( 0, 5, MNORMAL, PSTR("avgD Current%3.1u A"), (uint8_t)(Config.OSD_Statistic.avg_Altimeter/100));
 
// stat. Packages
lcd_printf_at_P( 0, 6, MNORMAL, PSTR("stat Pkg's%7u"), Config.OSD_Statistic.count_osd);
 
 
/*
// DEBUG: Heading
lcd_printf_at_P( 0, 1, MNORMAL, PSTR("NC-Errorcode:%3u"), naviData->Errorcode);
 
//heading_home = (naviData->HomePositionDeviation.Bearing + 360 - naviData->CompassHeading) % 360;
 
lcd_printf_at_P( 0, 3, MNORMAL, PSTR("CH:%6d%6d"), naviData->CompassHeading, naviData->CompassHeading%360);
lcd_printf_at_P( 0, 4, MNORMAL, PSTR("HD:%6d%6d"), naviData->HomePositionDeviation.Bearing, naviData->HomePositionDeviation.Bearing%360);
 
//heading_home = (naviData->HomePositionDeviation.Bearing + 360 - naviData->CompassHeading) % 360;
 
//heading_home = ((naviData->CompassHeading % 360) - (naviData->HomePositionDeviation.Bearing % 360)) + 180;
//heading_home = ((naviData->CompassHeading % 360) - (naviData->HomePositionDeviation.Bearing % 360));
 
calc_heading_home();
 
lcd_printf_at_P( 0, 6, MNORMAL, PSTR("xx:%6d"), heading_home);
*/
 
/*
lcd_putc( 0, 3, 0x08, MNORMAL); // ASCII - 8 08 SAT Symbol
lcd_putc( 2, 3, 0x09, MNORMAL); // ASCII - 9 09 Altitude Symbol
lcd_putc( 4, 3, 0x0C, MNORMAL); // ASCII - 12 0C Enter Symbol
lcd_putc( 6, 3, 0x1F, MNORMAL); // ASCII - 31 1F Antenne
lcd_putc( 8, 3, 10, MNORMAL); // 'o'
lcd_putc(10, 3, 13, MNORMAL); // 'o'
//lcd_putc(10, 3, 0x06, MNORMAL);
//lcd_putc(12, 3, 0x07, MNORMAL);
 
lcd_putc( 0, 5, 0x1E, MNORMAL);
lcd_putc( 4, 5, 0x7e, MNORMAL);
lcd_putc( 6, 5, 0x7f, MNORMAL);
lcd_putc( 8, 5, 0x18, MNORMAL);
lcd_putc(10, 5, 0x19, MNORMAL);
*/
 
//lcd_printp_at( 0, 1, PSTR("Free RAM:"), 0);
//writex_ndigit_number_u ( 9, 1, get_freeRam(), 9, 0,MNORMAL, 0,0); //
}
 
 
//--------------------------------------------------------------
// OSD_Screen_Debug_RX()
//
// Anzeige gelesener Datenpakete (fuer Feinabstimmung) und weitere
// Werte wie Zeit/Datum (mit/ohne Abgleich zur NC)
//
// Anzeige oben 1. Zeile:
// Screenname : "Debug-RX"
// PKT-Uptime : Minuten, Sekunden die das PKT aktuell eingeschaltet ist
// Screen-Count: Anzahl der Aufrufe des Screens (abhaengig von der Refreshtime)
//
// Anzeige Zeit:
// "N" oder "O": neuer(N) oder alter(O) Zeit-Algo fuer die NC (OSD_MK_UTCTime())
// 00:00:00 : Stunde, Minute, Sekunde (korrigiert mittels PKT-Einstellung bzgl. Zeitzone/Sommerzeit)
// dd.mm.yyyy : Tag, Monat, Jahr (korrigiert mittels PKT-Einstellung bzgl. Zeitzone/Sommerzeit)
// Solange keine richtige Zeit von der NC gemeldet wird, wird die PKT-Uptime
// seit einschalten des PKT angezeigt.
//
// Anzeige unten:
// OSD: Anzahl gelesener OSD-Pakete der NC
// Time: Anzahl gelesener Time-Pakete der NC (Aktualisierung ca. jede Minute)
//
// BL: es werden die gelesenen Datenpakete der BL's angezeigt
// von BL1 (links oben) bis BL8 (rechts unten)
//--------------------------------------------------------------
void OSD_Screen_Debug_RX( void )
{
static uint16_t debug_count = 0;
uint8_t y;
int8_t yoffs;
 
//uint8_t status; // FC Kommunikation
 
//-----------------------------------------
// REDRAW
// statische Screen Elemente die nicht
// jedesmal neu gezeichnet werden muessen
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// do things here for static screen elements like labels and so....
lcd_frect( 0, 0, 1, 8, 1); // title spacer
lcdx_printp_at( 0, 0, PSTR("Debug-RX"), MINVERS, 1,0); // title
lcd_line (0, 9, 127, 9, 1); // Linie horizontal
lcd_line (0, 22, 127, 22, 1); // Linie horizontal
//lcd_line (0, 31, 127, 31, 1); // Linie horizontal
}
 
//-----------------------
// Zeile 0
//-----------------------
writex_time( 11, 0, timer_pkt_uptime/100, MNORMAL, 0,0);
debug_count++;
write_ndigit_number_u ( 17, 0, (debug_count), 4, 0,MNORMAL); //
 
 
//-----------------------
// Anzeige Zeit / Datum
//-----------------------
yoffs = 5;
writex_datetime_time( 1, 1, UTCTime, MNORMAL, 5,yoffs); // Zeit
writex_datetime_date( 11, 1, UTCTime, MNORMAL, 0,yoffs); // Datum
 
//-----------------------
// gelesene Pakete: OSD und Zeit
//-----------------------
y = 4;
yoffs = -5;
 
lcdx_printp_at( 0, y+0, PSTR("OSD:"), MNORMAL, 0,yoffs);
writex_ndigit_number_u ( 4, y+0, ( readCounterOSD), 5, 0,MNORMAL, 0,yoffs); //
 
lcdx_printp_at( 13, y+0, PSTR("Time:"), MNORMAL, 0,yoffs);
writex_ndigit_number_u ( 18, y+0, ( readCounterTIME), 3, 0,MNORMAL, 0,yoffs); //
 
 
//----
lcdx_printp_at( 0, y+1, PSTR("Dis:"), MNORMAL, 0,yoffs);
writex_ndigit_number_u ( 4, y+1, ( readCounterDISPLAY), 5, 0,MNORMAL, 0,yoffs); //
 
 
//-----------------------
// gelesene Pakete: BL
//-----------------------
y = 6;
lcd_frect( 0, y*8-1, 8, 17, 1); // Box
 
lcdx_printp_at( 0, y+0, PSTR("B"), MINVERS, 2,0);
lcdx_printp_at( 0, y+1, PSTR("L"), MINVERS, 2,0);
write_ndigit_number_u ( 2, y+0, ( readCounterBL[0]), 4, 0,MNORMAL); //
write_ndigit_number_u ( 7, y+0, ( readCounterBL[1]), 4, 0,MNORMAL); //
write_ndigit_number_u ( 12, y+0, ( readCounterBL[2]), 4, 0,MNORMAL); //
write_ndigit_number_u ( 17, y+0, ( readCounterBL[3]), 4, 0,MNORMAL); //
 
write_ndigit_number_u ( 2, y+1, ( readCounterBL[4]), 4, 0,MNORMAL); //
write_ndigit_number_u ( 7, y+1, ( readCounterBL[5]), 4, 0,MNORMAL); //
write_ndigit_number_u ( 12, y+1, ( readCounterBL[6]), 4, 0,MNORMAL); //
write_ndigit_number_u ( 17, y+1, ( readCounterBL[7]), 4, 0,MNORMAL); //
}
 
//##############################################################
#endif // USE_OSD_SCREEN_DEBUG
//##############################################################
 
 
 
//-----------------------------------------------------------
// ok = OSD_Popup_MKSetting()
//
// zeigt das aktuelle FC-Setting beim Start vom OSD an
//
// RUECKGABE:
// true = Setting konnte gelesen werden
// false = Fehler
//-----------------------------------------------------------
uint8_t OSD_Popup_MKSetting( void )
{
Popup_Draw( 3 ); // 3 Zeilen von unten nach oben fuer's Popup
lcdx_printp_center( 2, PSTR("PKT OSD") , MNORMAL, 0, 0);
lcdx_printp_center( 6, PSTR("MK Setting"), MINVERS, 0,-8);
 
MK_Setting_load( 0xff, 9 ); // 0xff == aktuelles Parameterset holen; 9 == timeout
 
MKVersion_Setting_print( 7, MINVERS, 0,-4); // aus: mkbase.c
 
if( MKVersion.mksetting == 0 )
set_beep( 500, 0xffff, BeepNormal ); // kein Setting - langer Beep ERROR
 
 
clear_key_all();
timer = 300; // ca. 3 Sekunden zeigen; Abbruch mit einer Taste moeglich
while( timer > 0 && !get_key_press(0xff) );
 
clear_key_all();
lcd_cls();
 
return (MKVersion.mksetting != 0);
}
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void OSD_Popup_MKError( u8 mkerrorcode )
{
Popup_Draw( 3 ); // 3 Zeilen von unten nach oben fuer's Popup
 
lcdx_printf_center_P( 6, MINVERS, 0,-8, PSTR("** MK-%S %02d **"), strGet(STR_ERROR), mkerrorcode ); // "MK-FEHLER" und Fehlernummer
 
lcdx_printp_center( 7, (const char*) pgm_read_word(&mkerrortext[mkerrorcode]), MINVERS, 0,-4); // MK-Fehlertext
}
 
 
 
//-----------------------------------------------------------
//-----------------------------------------------------------
void OSD_Popup_Info( uint8_t ScreenNum, const char *ScreenName)
{
Popup_Draw( 5 ); // 5 Zeilen von unten nach oben fuer's Popup
 
lcd_line( 3, 53-21, 124, 53-21, 0); // Linie: oben
lcd_line( 3, 53, 124, 53, 0); // Linie: unten
 
//-----------------------
// ScreenNummer: ScreenName
//-----------------------
lcdx_printf_at_P( 0, 3, MINVERS, 5,-2, PSTR("%02d: %S"), ScreenNum, ScreenName );
 
//-----------------------
// longpress Key's
//-----------------------
lcdx_printp_at( 0, 4, strGet(STR_LONGPRESS), MINVERS, 6,3); // "langer Tastendruck:"
lcdx_printp_at(12, 5, PSTR("Disp"), MINVERS, 0,4);
lcdx_printp_at(17, 5, PSTR("UGps"), MINVERS, 0,4);
 
//-----------------------
// shortpress Key's
//-----------------------
lcd_printp_at( 0, 7, strGet(KEYLINE3), MINVERS);
lcd_printp_at(17, 7, PSTR("Info") , MINVERS);
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void GPS_Pos_Save( pkt_gpspos_t *pGPS )
{
pGPS->Altimeter = naviData->Altimeter; // barymetrische Hoehe
pGPS->HomeDistance = naviData->HomePositionDeviation.Distance; // Entfernung Home
 
memcpy( &pGPS->GPSData, &naviData->CurrentPosition, sizeof(GPS_Pos_t) ); // sichern...
memcpy( &pGPS->timestamp, (char *)&UTCTime, sizeof(PKTdatetime_t) ); // sichern...
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
 
//--------------------------------------------------------------
// GPS_User_Init()
//
// initialisiert die GPS Positionen neu
//--------------------------------------------------------------
 
void GPS_User_Init( void )
{
memset( Config.GPS_User, 0, sizeof(pkt_gpspos_t)*MAX_GPS_USER );
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void GPS_User_Save( void )
{
uint8_t i;
 
if( naviData->NCFlags & NC_FLAG_GPS_OK ) // nur wenn MK-GPS ok ist
{
for( i=MAX_GPS_USER-1; i>0; i--)
{
Config.GPS_User[i] = Config.GPS_User[i-1];
}
GPS_Pos_Save( &Config.GPS_User[0] );
 
set_beep( 160, 0xffff, BeepNormal ); // Beep Ok
}
else
{
set_beep( 600, 0x000f, BeepNormal ); // Beep Error (keine gueeltigen GPS-Daten)
}
}
 
 
 
//##############################################################
//##############################################################
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void MKLiPoCells_Init( void )
{
CellIsChecked = 0;
cells = 0;
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void MKLiPoCells_Check( void )
{
if( cells == 0 ) // Zellenzahl noch nicht ermittelt?
{
// up to 6s LiPo, less than 2s is technical impossible
for( cells = 2; cells < 7; cells++)
{
if( naviData->UBat < cells * MAX_CELL_VOLTAGE ) break;
}
Config.OSD_Statistic.LiPoCells = cells;
}
}
 
 
 
//##############################################################
//# OSD MAIN LOOP
//##############################################################
 
//--------------------------------------------------------------
// OSD MAIN LOOP
//--------------------------------------------------------------
void osd( void )
{
uint8_t osdexit = false;
uint8_t mktimeout = false;
uint8_t flying = false;
uint8_t popup_state = OSD_POPUP_NONE;
 
 
lcd_cls();
 
#ifdef DEBUG_OSD_TIME
// Fake-Zeit/Datum setzen wenn der NC-Simulator verwendet wird
if( UTCTime.year < 2000 )
{
UTCTime.seconds = ((uint32_t)13*3600)+(15*60)+42; // 13:15:42
UTCTime.day = 01;
UTCTime.month = 05;
UTCTime.year = 2013;
}
#endif
 
 
//----------------------------------------
// Anzeige: aktuelles MK-Setting
//----------------------------------------
if( (Config.OSD_ShowMKSetting) )
{
if( !OSD_Popup_MKSetting() )
return;
}
 
 
/*
//-----------------------------------------------------------------------------------------------
// 07.03.2013 OG: del
// Dieser Teil hat immer wieder Probleme bereitet bei der Verbindung des PKT-OSD zum MK da
// MK_TIMEOUTs zustande kamen. Eine Recherche im Code ergab, dass die Nutzdaten die
// hierueber bezogen werden sich lediglich auf Flags_ExtraConfig beschraenkten (CFG2_HEIGHT_LIMIT).
// Siehe dazu untere Kommentare.
//
// Der negative Effekt moeglicher MK_TIMEOUTs und Verzoegerungen sind es aktuell nicht Wert
// CFG2_HEIGHT_LIMIT zu unterstuetzen. Dieses Feature ist erstmal raus.
//
// Falls gewuenscht wird, dass CFG2_HEIGHT_LIMIT wieder in das PKT-OSD kommt muss
// es zuverlaessig an anderer Stelle implementiert werden - und zwar nicht in osd.c
// weil es eine statische FC-Information ist (ggf. beim Verbindungsaufbau PKT <-> MK).
//
// Hat auch aktuell Auswirkung auf den Code OSD_Element_AltitudeControl()
//-----------------------------------------------------------------------------------------------
//lcd_printp_at( 0, 3, PSTR("connecting MK..."), 0);
//
//SwitchToFC();
//
//status = load_setting(0xff);
//
//if( status == 255 )
//{
// lcd_printp_at(0, 0, PSTR("Keine Settings !!"), 0); // Keine Settings
// _delay_ms(2000);
//}
//Flags_ExtraConfig = mk_param_struct->ExtraConfig; // OG: wird in osd.c nur verwendet von: OSD_Element_AltitudeControl()
//Flags_GlobalConfig = mk_param_struct->GlobalConfig; // OG: wird nicht in osd.c verwendet
//Flags_GlobalConfig3 = mk_param_struct->GlobalConfig3; // OG: wird nicht in osd.c verwendet
*/
 
 
 
//-------------------------
// MK-Display initialisieren
//-------------------------
memset( mkdisplayData, 0, 81 );
mkdisplayMode = false;
mkdisplayCmd = 0xff;
 
 
//-------------------------
// BL-DATA initialisieren
//-------------------------
memset( blData, 0, sizeof(BLData_t)*OSD_MAX_MOTORS );
 
 
//-------------------------
// Debug initialisieren
//-------------------------
#ifdef USE_OSD_SCREEN_DEBUG
readCounterOSD = 0;
readCounterTIME = 0;
readCounterDISPLAY = 0;
memset( readCounterBL, 0, sizeof(uint16_t)*OSD_MAX_MOTORS );
#endif // USE_OSD_SCREEN_DEBUG
 
 
 
//-------------------------
// NC Datenkommunikation starten
//-------------------------
OSD_MK_Connect( MK_CONNECT );
 
OSD_active = true; // benoetigt fuer Navidata Ausgabe an SV2
 
 
//-------------------------
// Clear statistics
//-------------------------
//STAT_Init();
 
CellIsChecked = 0;
cells = 0;
AkkuWarnThreshold = 0;
OldWP = 0;
NextWP = false;
old_PKTErrorcode = 0;
old_MKErrorcode = 0;
 
 
 
//-------------------------
// Init: OSD-Screens
//-------------------------
ScreenCtrl_Init();
ScreenCtrl_Push( OSDSCREEN_GENERAL , strGet(STR_OSDSCREEN_GENERAL) , &OSD_Screen_General );
 
#ifdef USE_OSD_SCREEN_NAVIGATION
ScreenCtrl_Push( OSDSCREEN_NAVIGATION , strGet(STR_OSDSCREEN_NAVIGATION), &OSD_Screen_Navigation );
#endif
 
#ifdef USE_OSD_SCREEN_WAYPOINTS
ScreenCtrl_Push( OSDSCREEN_WAYPOINTS , strGet(STR_OSDSCREEN_WAYPOINTS) , &OSD_Screen_Waypoints );
#endif
 
// *ALTERNATIVE*
//#ifdef USE_OSD_SCREEN_WAYPOINTS
//ScreenCtrl_Push( OSDSCREEN_WAYPOINTS , strGet(STR_OSDSCREEN_WAYPOINTS) , &OSD_Screen_Waypoints0 );
//#endif
 
#ifdef USE_OSD_SCREEN_ELECTRIC
ScreenCtrl_Push( OSDSCREEN_ELECTRIC , strGet(STR_OSDSCREEN_ELECTRIC) , &OSD_Screen_Electric );
#endif
 
#ifdef USE_OSD_SCREEN_MKSTATUS
ScreenCtrl_Push( OSDSCREEN_MKSTATUS , strGet(STR_OSDSCREEN_MKSTATUS) , &OSD_Screen_MKStatus );
#endif
 
#ifdef USE_OSD_SCREEN_USERGPS
ScreenCtrl_Push( OSDSCREEN_USERGPS , strGet(STR_OSDSCREEN_USERGPS) , &OSD_Screen_UserGPS );
#endif
 
#ifdef USE_OSD_SCREEN_3DLAGE
ScreenCtrl_Push( OSDSCREEN_3DLAGE , strGet(STR_OSDSCREEN_3DLAGE) , &OSD_Screen_3DLage );
#endif
 
#ifdef USE_OSD_SCREEN_STATISTIC
ScreenCtrl_Push( OSDSCREEN_STATISTICS , strGet(STR_OSDSCREEN_STATISTIC) , &OSD_Screen_Statistics );
#endif
 
#ifdef USE_OSD_SCREEN_OLD
ScreenCtrl_Push( OSDSCREEN_OSD0 , strGet(STR_OSDSCREEN_OSD0) , &OSD_Screen_OSD0 );
ScreenCtrl_Push( OSDSCREEN_OSD1 , strGet(STR_OSDSCREEN_OSD1) , &OSD_Screen_OSD1 );
ScreenCtrl_Push( OSDSCREEN_OSD2 , strGet(STR_OSDSCREEN_OSD2) , &OSD_Screen_OSD2 );
#endif
 
#ifdef USE_OSD_SCREEN_DEBUG
ScreenCtrl_Push( 0 , PSTR("Debug") , &OSD_Screen_Debug );
ScreenCtrl_Push( 0 , PSTR("Debug-RX") , &OSD_Screen_Debug_RX );
#endif
 
ScreenCtrl_Set( Config.OSD_ScreenMode );
 
 
//-------------------------
// Init: Timer & Flags
//-------------------------
OSDScreenRefresh = OSD_SCREEN_REDRAW;
timer_mk_timeout = MK_TIMEOUT;
timer_osd_refresh = TIME_OSD_REFRESH;
timer_get_bldata = 0;
timer_get_tidata = 0;
timer_get_displaydata = 0;
 
 
//--------------------------------
// OSD Main-Loop
//--------------------------------
while( !osdexit )
{
//################################
//# Empfange/verarbeite: OSD-Daten
//################################
if( rxd_buffer_locked ) // naviData Ok?
{
Decode64();
memcpy( &osdData, (const void *)pRxData, sizeof(NaviData_t) ); // sichern in: osdData
naviData = &osdData;
 
#ifdef USE_OSD_SCREEN_DEBUG
readCounterOSD++; // gelesene Datenpakete
#endif
 
mktimeout = false;
 
 
//----------------------------------
// LiPo Cell Check
//----------------------------------
if( cells == 0 ) // Zellenzahl noch nicht ermittelt?
{
// up to 6s LiPo, less than 2s is technical impossible
for( cells = 2; cells < 7; cells++)
{
if( naviData->UBat < cells * MAX_CELL_VOLTAGE ) break;
}
Config.OSD_Statistic.LiPoCells = cells;
}
 
 
//----------------------------------
// Winkel zu Home
//----------------------------------
calc_heading_home();
 
 
//----------------------------------
// speichere letzte GPS-Positionen
//----------------------------------
GPS_Pos_Save( &GPS_Current );
Config.LastLatitude = GPS_Current.GPSData.Latitude; // speichere letzte Position in Config
Config.LastLongitude = GPS_Current.GPSData.Longitude; // speichere letzte Position in Config
 
 
//----------------------------------
// PKT Fehler reset
//----------------------------------
if( old_PKTErrorcode == 40 ) // 40 = PKT Empfangsausfall ("PKT RX lost")
{
// PKT-Verbindungsfehler zuruecksetzen
// da an dieser Stelle ja bereits wieder ein gueltiges Datenpaket
// von der NaviCtrl empfangen wurde
old_PKTErrorcode = 0;
clear_key_all();
}
 
 
//----------------------------------
// remember statistics (only when engines running)
//----------------------------------
#ifdef DEBUG_OSD_STAT_MOTORRUN
if( true )
#else
if( naviData->FCStatusFlags & FC_STATUS_MOTOR_RUN ) // AM FLIEGEN -> Statistik aufzeichnen
#endif
{
flying = true;
 
// --- gueltige Zeit von der NC vorhanden und noch keine Start-Zeit gesetzt?
if( UTCTime.year != 0 && Config.OSD_Statistic.begin_StatTime.year == 0 )
{
memcpy( &Config.OSD_Statistic.begin_StatTime, (char *)&UTCTime, sizeof(PKTdatetime_t) ); // Start Zeit/Datum sichern...
}
 
Config.OSD_Statistic.last_FlyTime = naviData->FlyingTime;
 
Config.OSD_Statistic.count_osd++; // Anzahl OSD-Statistik Pakete
 
// int32_t calc_avg( int32_t avg, int32_t value, int32_t count, int32_t factor)
Config.OSD_Statistic.avg_Current = (uint16_t)calc_avg( (int32_t)Config.OSD_Statistic.avg_Current,
(int32_t)naviData->Current,
(int32_t)Config.OSD_Statistic.count_osd,
(int32_t)100 );
 
if( naviData->Altimeter > Config.OSD_Statistic.max_Altimeter ) Config.OSD_Statistic.max_Altimeter = naviData->Altimeter;
if( naviData->GroundSpeed > Config.OSD_Statistic.max_GroundSpeed ) Config.OSD_Statistic.max_GroundSpeed = naviData->GroundSpeed;
if( naviData->HomePositionDeviation.Distance > Config.OSD_Statistic.max_Distance ) Config.OSD_Statistic.max_Distance = naviData->HomePositionDeviation.Distance;
if( naviData->Current > Config.OSD_Statistic.max_Current ) Config.OSD_Statistic.max_Current = naviData->Current;
if( naviData->UsedCapacity > Config.OSD_Statistic.max_Capacity ) Config.OSD_Statistic.max_Capacity = naviData->UsedCapacity;
if( naviData->UBat < Config.OSD_Statistic.min_UBat ) Config.OSD_Statistic.min_UBat = naviData->UBat;
 
if( naviData->TopSpeed > Config.OSD_Statistic.max_TopSpeed ) Config.OSD_Statistic.max_TopSpeed = naviData->TopSpeed;
if( naviData->RC_Quality > Config.OSD_Statistic.max_RCQuality ) Config.OSD_Statistic.max_RCQuality = naviData->RC_Quality;
if( naviData->RC_Quality < Config.OSD_Statistic.min_RCQuality ) Config.OSD_Statistic.min_RCQuality = naviData->RC_Quality;
 
if( naviData->AngleNick < Config.OSD_Statistic.min_AngleNick ) Config.OSD_Statistic.min_AngleNick = naviData->AngleNick;
if( naviData->AngleNick > Config.OSD_Statistic.max_AngleNick ) Config.OSD_Statistic.max_AngleNick = naviData->AngleNick;
 
if( naviData->AngleRoll < Config.OSD_Statistic.min_AngleRoll ) Config.OSD_Statistic.min_AngleRoll = naviData->AngleRoll;
if( naviData->AngleRoll > Config.OSD_Statistic.max_AngleRoll ) Config.OSD_Statistic.max_AngleRoll = naviData->AngleRoll;
}
else if( flying && UTCTime.year != 0 ) // GELANDET -> Statistik beenden
{
// --- Ende Zeit/Datum Statistik sichern
memcpy( &Config.OSD_Statistic.end_StatTime, (char *)&UTCTime, sizeof(PKTdatetime_t) ); // Ende Zeit/Datum sichern...
flying = false;
}
 
 
//-----------------------
// Check: Akku Warnung
//-----------------------
CheckMKLipo();
 
 
//----------------------------------
// Show: OSD-Screens
//----------------------------------
if( popup_state == OSD_POPUP_NONE && (timer_osd_refresh == 0 || OSDScreenRefresh == OSD_SCREEN_REDRAW) )
{
if( OSDScreenRefresh == OSD_SCREEN_REDRAW ) lcd_cls();
 
if( !mkdisplayMode )
ScreenCtrl_Show();
else
OSD_Screen_MKDisplay();
 
timer_osd_refresh = TIME_OSD_REFRESH;
}
OSDScreenRefresh = OSD_SCREEN_REFRESH;
 
 
//----------------------------------
// Check: MK-Error
//----------------------------------
if( naviData->Errorcode != old_MKErrorcode && naviData->Errorcode <= MAX_MKERROR_NUM )
{
if( naviData->Errorcode > 0 ) // raise Error
{
// Fehler aufzeichnen
MkError_Save( naviData->Errorcode );
 
// Fehler Anzeigen
OSD_Popup_MKError( naviData->Errorcode );
set_beep( 1000, 0x000f, BeepNormal); // Beep Error (MK-Error vorhanden)
timer2 = TIME_POPUP_MKERROR;
popup_state = OSD_POPUP_MKERROR;
}
else // reset Error
{
popup_state = OSD_POPUP_NONE;
OSDScreenRefresh = OSD_SCREEN_REDRAW;
}
old_MKErrorcode = naviData->Errorcode;
}
 
rxd_buffer_locked = FALSE; // ready to receive new data
 
 
//-------------------------------------------
// hole weitere Daten vom MK (BL, Time, ...)
//
// muss am Schluss stehen da naviData-Buffer
// dabei ueberschrieben wird!
//-------------------------------------------
OSD_MK_GetData(); // holt BL-Daten und NC-Zeit
 
 
timer_mk_timeout = MK_TIMEOUT;
 
} //end: if( rxd_buffer_locked ) // OSD-Daten
 
 
 
//################################
//# der Rest...
//################################
 
//--------------------------------
// TASTEN: MK-Timeout
//--------------------------------
if( mktimeout )
{
if( get_key_short(1 << KEY_ESC) ) // PKT OSD EXIT
{
osdexit = true;
}
}
 
 
//--------------------------------
// Popup beenden
// wenn irgendeine Taste gedrückt oder Popup-Timeout
//--------------------------------
if( !mktimeout && (popup_state != OSD_POPUP_NONE) && (get_key_press(255) || !timer2) ) // get_key_press(255) == alles an Tasten abfangen was moeglich ist
{
popup_state = OSD_POPUP_NONE;
OSDScreenRefresh = OSD_SCREEN_REDRAW;
clear_key_all();
}
 
 
//--------------------------------
// TASTEN: KEIN mkdisplay (OSD Modus)
//--------------------------------
if( !osdexit && !mktimeout && !mkdisplayMode )
{
if( get_key_short(1 << KEY_ESC) ) // PKT OSD EXIT
{
osdexit = true;
}
 
if( get_key_long(1 << KEY_ESC) ) // ÊINSCHALTEN: mkdisplayMode
{
set_beep( 25, 0xffff, BeepNormal ); // kurzer Bestaetigungs-Beep
OSDScreenRefresh = OSD_SCREEN_REDRAW;
mkdisplayMode = true;
mkdisplayCmd = 0; // lesen display-Daten erzwingen
}
 
if( get_key_long (1 << KEY_ENTER) ) // User GPS-Position sichern
{
GPS_User_Save();
}
 
if( get_key_short (1 << KEY_ENTER) ) // Popup: Info
{
if( popup_state == OSD_POPUP_NONE )
{
popup_state = OSD_POPUP_INFO;
OSD_Popup_Info( ScreenCtrl_GetNum(), ScreenCtrl_GetName() );
timer2 = TIME_POPUP_INFO;
}
}
 
if( get_key_press (1 << KEY_MINUS)) // previous screen
{
ScreenCtrl_Previous();
}
 
if( get_key_press (1 << KEY_PLUS)) // next Screen
{
ScreenCtrl_Next();
}
 
}
 
 
 
//--------------------------------
// TASTEN: mkdisplay AKTIV
//--------------------------------
if( !osdexit && !mktimeout && mkdisplayMode )
{
/*
if( get_key_long(1 << KEY_ENTER) // ABSCHALTEN mkdisplayMode: longpress ENTER, ESC, MINUS, PLUS schaltet mkdisplay aus
|| get_key_long(1 << KEY_ESC)
|| get_key_long(1 << KEY_MINUS)
|| get_key_long(1 << KEY_PLUS) )
{
*/
 
if( get_key_long(1 << KEY_ESC) ) // ABSCHALTEN mkdisplayMode: longpress ESC (Taste 3 von links)
{
set_beep( 25, 0xffff, BeepNormal ); // kurzer Bestaetigungs-Beep beim Modus-Wechsel
OSDScreenRefresh = OSD_SCREEN_REDRAW;
mkdisplayMode = false;
clear_key_all();
}
 
if( get_key_short (1 << KEY_MINUS) ) mkdisplayCmd = 0xfe; // MK-Key: rechts (next page)
if( get_key_short (1 << KEY_PLUS) ) mkdisplayCmd = 0xfd; // MK-Key: links (previous page)
if( get_key_short (1 << KEY_ESC) ) mkdisplayCmd = 0xfb; // MK-Key: runter
if( get_key_short (1 << KEY_ENTER) ) mkdisplayCmd = 0xf7; // MK-Key: hoch
 
if( mkdisplayCmd != 0xff ) // wenn eine MK-Display Taste gedrueckt worde sofort Daten
{ // holen und darstellen um Anzeigereaktion fuer Benutzer zu verbessern
timer_get_displaydata = 0; // lesen erzwingen
OSD_MK_GetData(); // Daten holen
OSD_Screen_MKDisplay(); // MK-Display Anzeigen
}
}
 
 
 
//-----------------------
// abo_timer
//-----------------------
if( abo_timer == 0 )
{
OSD_MK_Connect( MK_ABORENEW );
}
 
 
//--------------------------
// Daten Timeout vom MK?
//--------------------------
if( timer_mk_timeout == 0 )
{
if( !mktimeout ) OSD_MK_ShowTimeout(); // nur anzeigen wenn noch nicht im mktimeout-Modus
set_beep ( 200, 0x0080, BeepNormal); // Beep
mktimeout = true;
timer_mk_timeout = MK_TIMEOUT;
OSDScreenRefresh = OSD_SCREEN_REDRAW;
OSD_MK_Connect( MK_CONNECT ); // 21.06.2014 OG: wieder aktviert wegen Umschaltung auf NC
}
 
 
 
//--------------------------
// Pruefe auf PKT-Update und
// andere interne PKT-Aktionen
//--------------------------
#ifdef USE_OSD_PKTHOOK
if( PKT_CtrlHook() ) OSDScreenRefresh = OSD_SCREEN_REDRAW; // Update vom Updatetool angefordert?
#endif
 
} // END: while( !osdexit )
 
 
 
//------------------------------------------
// PKT-OSD beenden
//------------------------------------------
Config.OSD_ScreenMode = ScreenCtrl_GetNum(); // merken letzter Screen
 
 
//------------------------------------------
// ggf. Statistik Ende Zeit/Datum sichern
//------------------------------------------
if( flying && UTCTime.year != 0 ) // wenn noch am fliegen
{
// --- Ende Zeit/Datum Statistik sichern
memcpy( &Config.OSD_Statistic.end_StatTime, (char *)&UTCTime, sizeof(PKTdatetime_t) ); // Ende Zeit/Datum sichern...
}
 
 
OSD_active = false;
}
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/osd/osd.h
0,0 → 1,309
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY osd.h
//#
//# 21.06.2014 OG
//# - add: writex_altimeter()
//# - add: draw_icon_mk()
//#
//# 18.06.2014 OG
//# - add: weitere Exporte von Funktionen draw_icon...()
//# - add: MKLiPoCells_Init(), MKLiPoCells_Check()
//# - add: OSD_Element_Battery_Bar()
//# - chg: define ORIENTATION_H, ORIENTATION_V verschoben nach osd.h
//#
//# 01.06.2014 OG
//# Beginn von Auslagerungen von Code alter OSD-Screens nach osdold_screens.c/h
//#
//# 26.05.2014 OG
//# - add: #define OSDSCREEN_WAYPOINTS
//#
//# 24.05.2014 OG
//# - chg: OSD_Element_CompassDirection() - erweitert um xoffs,yoffs
//#
//# 28.04.2014 OG
//# - del: OSD_Timeout()
//#
//# 07.07.2013 OG
//# - add: defines fuer Screen-ID's (verwendet in setup.c, osd.c)
//#
//# 30.06.2013 OG
//# - chg: Benamung Statistik-Var's von mid_* auf avg_* geaendert
//#
//# 31.05.2013 OG
//# Achtung! Aenderung eeprom-Kompatibilitaet wegen typedef Erweiterung!
//# - chg: typedef: osd_statistic_BL_t fuer Mittelwerte
//# - chg: typedef: osd_statistic_t fuer Mittelwerte
//#
//# 15.05.2013 OG
//# - add: calc_BLmax()
//# - add: struct osd_BLmax_t
//#
//# 04.05.2013 OG
//# - chg: aktualisiert Kommentare in 'osd_statistic_t'
//# - del: OSD_Debug_XX()
//#
//# 02.05.2013 OG
//# - fix: struct osd_statistic_t: max_Distance von int16_t nach uint16_t
//#
//# 28.04.2013 OG
//# - chg: osd(OSDMode) -> osd(void)
//# - del: OSDDATA_Statistics()
//#
//# vorheriges: siehe osd.c
//############################################################################
 
 
#ifndef _OSD_H
#define _OSD_H
 
#include "../mk-data-structs.h"
#include "../timer/timer.h"
 
#define OSD_MAX_MOTORS 8 // max. Anzahl vom PKT unterstuetzer Motoren (absolut MAX ist 12 da der MK nicht mehr unterstuetzt)
#define MAX_GPS_USER 10 // max. Anzahl der GPS-Positionen durch Benutzer gespeichert
#define MAX_MKERR_LOG 20 // max. Anzahl Eintraege im MK-Error-Log
 
#define OSD_SCREEN_REFRESH 0 // Screen: Werte anzeigen
#define OSD_SCREEN_REDRAW 1 // Screen: Labels und statischer Elemente neu zeichen, Werte anzeigen
 
 
#define ORIENTATION_V 1 // fuer OSD_Element_Battery_Bar()
#define ORIENTATION_H 2
 
 
// OSD-Screen ID's
// maximal: 31 (!) wegen Bitcodierung in Config.OSD_UseScreen
#define OSDSCREEN_GENERAL 0
#define OSDSCREEN_NAVIGATION 1
#define OSDSCREEN_ELECTRIC 2
#define OSDSCREEN_MKSTATUS 3
#define OSDSCREEN_USERGPS 4
#define OSDSCREEN_3DLAGE 5
#define OSDSCREEN_STATISTICS 6
#define OSDSCREEN_OSD0 7
#define OSDSCREEN_OSD1 8
#define OSDSCREEN_OSD2 9
#define OSDSCREEN_WAYPOINTS 10
 
 
// Flags
#define OSD_FLAG_AH 0 // Altitue Hold
#define OSD_FLAG_PH 1 // Position Hold
#define OSD_FLAG_CF 2 // Care Free
#define OSD_FLAG_CH 3 // Coming Home
#define OSD_FLAG_O1 4 // Out1 (LED 1)
#define OSD_FLAG_O2 5 // Out2 (LED 2)
#define OSD_FLAG_BA 6 // LowBat warning (MK)
#define OSD_FLAG_CA 7 // Calibrate
#define OSD_FLAG_ST 8 // Start
#define OSD_FLAG_MR 9 // Motor Run
#define OSD_FLAG_FY 10 // Fly
#define OSD_FLAG_EL 11 // Emergency Landing
#define OSD_FLAG_FS 12 // RS Failsave Active
#define OSD_FLAG_GP 13 // GPS ok
#define OSD_FLAG_S0 14 // GPS-Sat not ok (GPS NOT ok)
#define OSD_FLAG_TU 15 // Vario Trim Up
#define OSD_FLAG_TD 16 // Vario Trim Down
#define OSD_FLAG_FR 17 // Free
#define OSD_FLAG_RL 18 // Range Limit
#define OSD_FLAG_SL 19 // No Serial Link
#define OSD_FLAG_TR 20 // Target Reached
#define OSD_FLAG_MC 21 // Manual Control
 
#define OSD_FLAG_COUNT 22
 
 
// Hier Höhenanzeigefehler Korrigieren
#define AltimeterAdjust 1.5
 
 
//-----------------------------------------------------------
// typedef: Statistiken
//-----------------------------------------------------------
typedef struct
{
uint16_t count; // Anzahl Werte BL-Daten (fuer Mittelwertberechnung)
uint8_t max_Current; // in 0.1 A steps
uint16_t avg_Current; // Mittelwert Current (*100 fuer Rechengenauigkeit)
uint8_t max_Temp; // old BL-Ctrl will return a 255 here, the new version (>= V2.0) the temp. in °C
} osd_statistic_BL_t;
 
 
typedef struct
{
PKTdatetime_t begin_StatTime; // Datum/Zeit
PKTdatetime_t end_StatTime; // Datum/Zeit
uint16_t total_FlyTime; // gesamt Flugzeit seit Stat-Init
uint16_t last_FlyTime; // letzte Flugzeit
uint16_t count_osd; // TODO: Anzahl Werte OSD-Daten (fuer Mittelwertberechnung)
uint16_t count_Errorcode; // TODO: Anzahl gemeldeter MK-Errors
int16_t max_Altimeter; // max. Hoehe
int16_t avg_Altimeter; // TODO: Mittelwert Hoehe ()
s16 max_Variometer; // TODO: ...
uint16_t max_GroundSpeed; // max. Geschwindigkeit
uint16_t avg_GroundSpeed; // TODO: Mittelwert Geschwindigkeit ()
s16 max_TopSpeed; // max. velocity in vertical direction in cm/s
uint16_t max_Distance; // max. Entfernung
uint16_t avg_Distance; // TODO: Mittelwert Entfernung ()
uint16_t max_Current; // max. Strom
uint16_t avg_Current; // Mittelwert Strom ()
u8 max_RCQuality; // max. Empfangsqualitaet
u8 min_RCQuality; // min. Empfangsqualitaet
uint16_t avg_RCQuality; // TODO: Mittelwert Empfangsqualitaet ()
uint16_t max_Capacity; // max. entnommene Kapazitaet
s8 max_AngleNick; // max. Nick
s8 min_AngleNick; // min. Nick
s8 max_AngleRoll; // max. Roll
s8 min_AngleRoll; // min. Roll
uint8_t min_UBat; // min. Spannung (V)
uint8_t LiPoCells; // Anzahl der LiPo Zellen
uint8_t BL_Count; // Anzahl erkannter BL's (Motoren)
osd_statistic_BL_t BL[OSD_MAX_MOTORS]; // Werte der einzelnen BL's
} osd_statistic_t;
 
 
typedef struct
{
uint8_t max_BL_Current_Index; // BL-Nummer
unsigned char max_BL_Current; // in 0.1 A steps
uint8_t max_BL_Temp_Index; // BL-Nummer
unsigned char max_BL_Temp; // old BL-Ctrl will return a 255 here, the new version (>= V2.0) the temp. in °C
} osd_BLmax_t;
 
 
//-----------------------------------------------------------
// typedef: Aufzeichnung von MK-Errors
//-----------------------------------------------------------
typedef struct
{
u8 Errorcode; // 0 --> okay
PKTdatetime_t set_Time; // Datum/Zeit
PKTdatetime_t clear_Time; // Datum/Zeit
} mkerror_t;
 
 
 
//-----------------------------------------------------------
// typedef: PKT GPS-Positionen
//-----------------------------------------------------------
typedef struct
{
PKTdatetime_t timestamp; // Zeitstempel: UTC
s16 Altimeter; // barymetrische Hoehe (entspricht: naviData->Altimeter)
u16 HomeDistance; // distance to home in cm (entspricht: naviData->HomePositionDeviation.Distance)
GPS_Pos_t GPSData; // GPS-Position (mk-data-structs.h)
} pkt_gpspos_t;
 
 
 
//-----------------------------------------------------------
// global var's
//-----------------------------------------------------------
extern volatile uint8_t OSD_active;
extern volatile uint8_t error;
 
//-----------------------------------------------------------
// strings
//-----------------------------------------------------------
extern const char * const mkerrortext[];
 
 
//-----------------------------------------------------------
// Funktionen
//-----------------------------------------------------------
void osd( void );
void vario_beep_output (void);
void CheckMKLipo(void);
void STAT_Init(void);
void GPS_User_Init(void);
void MKErr_Log_Init(void);
void calc_BLmax( osd_BLmax_t *blmax );
 
 
void OSD_Element_Flag_Label( uint8_t xC, uint8_t yC, uint8_t item, uint8_t lOn, int8_t xoffs, int8_t yoffs);
void OSD_Element_Flag( uint8_t xC, uint8_t yC, uint8_t item, int8_t xoffs, int8_t yoffs);
void OSD_Element_Altitude( uint8_t x, uint8_t y, uint8_t nStyle );
void OSD_Element_BattLevel2( uint8_t x, uint8_t y, int8_t xoffs, int8_t yoffs );
void OSD_Element_BatteryLevel_Bar( uint8_t x, uint8_t y );
void OSD_Element_BatteryLevel_Text( uint8_t x, uint8_t y, uint8_t nStyle );
void OSD_Element_BatteryLevel( uint8_t x, uint8_t y, uint8_t nStyle );
void OSD_Element_Capacity( uint8_t x, uint8_t y );
void OSD_Element_CompassDegree( uint8_t x, uint8_t y, uint8_t nStyle );
void OSD_Element_CompassDirection( uint8_t x, uint8_t y, int8_t xoffs, int8_t yoffs );
void OSD_Element_CompassRose( uint8_t x, uint8_t y );
void OSD_Element_Current( uint8_t x, uint8_t y );
void OSD_Element_FlyingTime( uint8_t x, uint8_t y );
void OSD_Element_GroundSpeed( uint8_t x, uint8_t y );
void OSD_Element_HomeCircle( uint8_t x, uint8_t y, uint8_t breite, int8_t rOffset, int8_t xoffs, int8_t yoffs );
void OSD_Element_HomeDegree( uint8_t x, uint8_t y );
void OSD_Element_HomeDistance( uint8_t x, uint8_t y, uint8_t nStyle );
void OSD_Element_LEDOutput( uint8_t x, uint8_t y, uint8_t bitmask );
void OSD_Element_LED1Output( uint8_t x, uint8_t y );
void OSD_Element_LED2Output( uint8_t x, uint8_t y );
void OSD_Element_Manuell( uint8_t x, uint8_t y );
void OSD_Element_RCIntensity( uint8_t x, uint8_t y );
void OSD_Element_SatsInUse( uint8_t x, uint8_t y, uint8_t nStyle );
void OSD_Element_Variometer( uint8_t x, uint8_t y );
void OSD_Element_Target( uint8_t x, uint8_t y, uint8_t nStyle );
void OSD_Element_VarioWert( uint8_t x, uint8_t y );
void OSD_Element_WayPoint( uint8_t x, uint8_t y );
void OSD_Element_TargetDegree( uint8_t x, uint8_t y );
void OSD_Element_UpDown( uint8_t x, uint8_t y, int8_t xoffs, int8_t yoffs);
void OSD_Element_Battery_Bar( uint8_t x, uint8_t y, uint8_t length, uint8_t width, uint8_t orientation);
 
void writex_altimeter( uint8_t x, uint8_t y, s32 Altimeter, uint8_t mode, int8_t xoffs, int8_t yoffs );
 
void MKLiPoCells_Init( void );
void MKLiPoCells_Check( void );
 
void draw_icon_satmini( uint8_t x, uint8_t y);
void draw_icon_satmini2( uint8_t x, uint8_t y);
void draw_icon_home( uint8_t x, uint8_t y);
void draw_icon_target_diamond( uint8_t x, uint8_t y);
void draw_icon_target_round( uint8_t x, uint8_t y);
void draw_icon_mk( uint8_t x, uint8_t y);
 
void OSD_MK_ShowTimeout( void );
 
 
//-----------------------------------------------------------
// EXPORTS NUR FUER osdold_screens.c
//-----------------------------------------------------------
extern NaviData_t *naviData;
extern uint8_t OSDScreenRefresh;
 
 
#endif // _OSD_H
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/osd/osddata.c
0,0 → 1,838
/*****************************************************************************
* Copyright (C) 2013 Oliver Gemesi *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
*****************************************************************************/
 
//############################################################################
//# HISTORY osddata.c
//#
//# 14.06.2014 OG
//# - chg: Menu_OSDData() - Bezeichnung von "OSD Daten" und "BL Daten" geaendert
//# zu "OSD Statistik" und "BL Statistik"
//#
//# 11.05.2014 OG
//# - chg: Text von SHOWMKERROR_de, SHOWMKERROR_en etwas gekuerzt
//# - chg: Titel von Scrollbox-Listen angepasst
//# - chg: Menu_OSDData() umgestellt auf MenuCtrl_SetTitleFromParentItem()
//# -> die Menues 'erben' damit ihren Titel vom aufrufenden Menuepunkt
//#
//# 30.03.2014 OG
//# - chg: Sprache Hollaendisch vollstaendig entfernt
//# - chg: MenuCtrl_PushML_P() umgestellt auf MenuCtrl_PushML2_P()
//#
//# 29.03.2014 OG
//# - chg: Menu_OSDData() del: MenuCtrl_SetShowBatt() wegen Aenderung Default auf true
//# - chg: ask_delete_data() - Layout und Optimierung
//# - add: OSDDATA_ShowLastGPSPosition()
//# - del: OSDDATA_ShowLastGPS()
//#
//# 12.02.2014 OG
//# - del: die includes zu den alten parameter... entfernt
//#
//# 24.01.2014 OG
//# - fix: OSDDATA_ClearAllData(): Beep wenn Daten geloescht werden
//# (wie bei den anderen Löschungen)
//#
//# 30.06.2013 OG
//# - add: Gesamtstrom-Mittelwert in OSDDATA_Statistics() und OSDDATA_BLStatistics()
//# - chg: Benamung Statistik-Var's von mid_* auf avg_* geaendert
//# - chg: Funktionsnamen geaendert
//#
//# 19.06.2013 OG
//# - add: last Flytime in OSDDATA_Statistics()
//# - chg: Reihenfolge in OSDDATA_Statistics() und zusaetzliche Trennline
//# - add: max Current (Gesamt) in OSDDATA_Statistics()
//#
//# 16.06.2013 OG
//# - fix: "min. Voltage" Anzeige in OSDDATA_Statistics() (war veschoben)
//#
//# 13.06.2013 OG
//# - chg: Uebersetzungen von CB in ask_delete_data() aufgenommen
//# - chg: GPS-Menuetitel geaendert
//# - fix: include pkt.h
//#
//# 11.06.2013 OG
//# - chg: ask_delete_data() erweitert um Info was geloescht wird & Layout (TODO: Uebersetzungen)
//# - add: Mittelwertanzeige fuer BL-Strom
//# - add: Anzahl BL-Statistik-Datenpakete (nur wenn USE_OSD_SCREEN_DEBUG)
//# - add: OSDDATA_BLStatistic() - die BL-Daten wurden in eigene Anzeigefunktion verschoben
//# - add: OSDDATA_ClearAllData() - alle Daten loeschen
//# - add: OSDDATA_ShowLastGPS() - letzte GPS-Position anzeigen
//# - add: Menu_OSDData() - ehemals in menu.c jetzt hier
//# - chg: PKT_CtrlHook() noch an einigen Stellen eingefuegt
//# - fix: ctrl_osddata() clear screen vor ScrollBox_Refresh
//#
//# 15.05.2013 OG
//# - chg: OSDDATA_Statistics() umgestellt auf calc_BLmax() (aus osd.c)
//#
//# 04.05.2013 OG
//# - chg: angepasst auf xutils.c
//# - add: weitere Anzeigen in OSD_Statistics()
//# - add: Content in OSDDATA_UserGPS() und OSDDATA_MkError()
//#
//# 28.04.2013 OG
//# - chg: auf die neuen Features von xprintf angepasst (siehe utils/xstring.c)
//#
//# 21.04.2013 Cebra
//# - chg: Texte "Datenlöschen" in messages.c aufgenommen
//#
//# 20.04.2013 OG - NEU
//############################################################################
 
#include "../cpu.h"
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <string.h>
 
#include "../main.h"
#include "../lcd/lcd.h"
#include "../timer/timer.h"
#include "../uart/usart.h"
#include "../eeprom/eeprom.h"
#include "../messages.h"
#include "../sound/pwmsine8bit.h"
#include "../mk-data-structs.h"
#include "../osd/osd.h"
#include "../utils/scrollbox.h"
#include "../utils/xutils.h"
#include "../utils/menuctrl.h"
#include "../pkt/pkt.h"
#include "../lipo/lipo.h"
#include "../mk/mkbase.h"
 
 
#define INIT_STATISTIC 1
#define INIT_MKERROR 2
#define INIT_USERGPS 3
#define INIT_LASTPOS 4
#define INIT_ALLDATA 5
 
 
//-----------------------
// Menu_OSDDATA
//-----------------------
#define ID_SHOWSTATISTIK 1
#define ID_SHOWBLSTATISTIK 2
#define ID_SHOWMKERROR 3
#define ID_SHOWUSERGPS 4
#define ID_SHOWLASTGPS 5
#define ID_CLEARALLDATA 6
 
 
//static const char SHOWSTATISTIK_de[] PROGMEM = "OSD Daten";
//static const char SHOWSTATISTIK_en[] PROGMEM = "OSD data";
 
//static const char SHOWBLSTATISTIK_de[] PROGMEM = "BL Daten";
//static const char SHOWBLSTATISTIK_en[] PROGMEM = "BL data";
 
static const char SHOWSTATISTIK_de[] PROGMEM = "OSD Statistik";
static const char SHOWSTATISTIK_en[] PROGMEM = "OSD statistics";
 
static const char SHOWBLSTATISTIK_de[] PROGMEM = "BL Statistik";
static const char SHOWBLSTATISTIK_en[] PROGMEM = "BL statistics";
 
static const char SHOWMKERROR_de[] PROGMEM = "MK Fehler";
static const char SHOWMKERROR_en[] PROGMEM = "MK errors";
 
static const char SHOWUSERGPS_de[] PROGMEM = "GPS Userdaten";
static const char SHOWUSERGPS_en[] PROGMEM = "GPS userdata";
 
static const char SHOWLASTGPS_de[] PROGMEM = "GPS letzte Pos.";
static const char SHOWLASTGPS_en[] PROGMEM = "GPS last pos.";
 
static const char CLEARALLDATA_de[] PROGMEM = "LÖSCHE alle Daten";
static const char CLEARALLDATA_en[] PROGMEM = "DELETE all data";
 
 
 
//############################################################################
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t ask_delete_data( uint8_t initcode )
{
uint8_t refresh = true;
 
clear_key_all();
 
set_beep ( 60, 0xffff, BeepNormal);
 
while( true )
{
//--------------------------------------
// screen refresh
//--------------------------------------
if( refresh )
{
lcd_cls();
 
lcd_frect( 0, 0, 127, 7, 1); // Headline: Box fill Black
lcdx_printp_at( 1, 0, strGet(DELETE), MINVERS, 0,0); // Titel
show_Lipo(); // LiPo anzeigen
 
lcd_rect_round( 0, 20, 127, 27, 1, R2); // Rahmen fuer Benutzerfrage
 
switch( initcode )
{
case INIT_STATISTIC: lcdx_printp_center( 2, strGet(STAT_OSDBL), MNORMAL, 0,9); break;
case INIT_MKERROR : lcdx_printp_center( 2, strGet(STAT_ERROR), MNORMAL, 0,9); break;
case INIT_USERGPS : lcdx_printp_center( 2, strGet(STAT_GPS) , MNORMAL, 0,9); break;
case INIT_LASTPOS : lcdx_printp_center( 2, strGet(STAT_POS) , MNORMAL, 0,9); break;
case INIT_ALLDATA : lcdx_printp_center( 2, strGet(STAT_ALL) , MNORMAL, 0,9); break;
}
 
lcdx_printp_center( 4, strGet(DELETE), MNORMAL, 0,4); // "löschen?"
 
lcd_printp_at( 0, 7, strGet(START_LASTPOS2) , MNORMAL); // Keyline: "löschen Nein"
 
refresh = false;
}
 
//--------------------------------------
// Update vom Updatetool angefordert?
//--------------------------------------
if( PKT_CtrlHook() )
{
refresh = true;
}
 
//--------------------------------------
// loeschen
//--------------------------------------
if( get_key_press(1 << KEY_MINUS) )
{
clear_key_all();
return true; // Rueckgabe: true = loeschen
}
 
 
//--------------------------------------
// Ende
//--------------------------------------
if( get_key_press(1 << KEY_ENTER) )
{
clear_key_all();
return false; // Rueckgabe: false = nicht loeschen
}
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void ctrl_osddata( uint8_t isdata, uint8_t initcode )
{
uint8_t key = 0;
 
if( !isdata ) ScrollBox_Push_P( MNORMAL, PSTR(" no data...") );
 
ScrollBox_SetKey( KEY_ENTER, " Del" );
 
do
{
key = ScrollBox_Show();
 
if( key == KEY_ENTER )
{
if( ask_delete_data(initcode) )
{
switch( initcode )
{
case INIT_STATISTIC: STAT_Init(); break;
case INIT_MKERROR: MKErr_Log_Init(); break;
case INIT_USERGPS: GPS_User_Init(); break;
}
 
set_beep ( 400, 0xffff, BeepNormal);
key = 0; // exit
}
else
{
lcd_cls();
ScrollBox_Refresh();
}
}
 
} while( key );
}
 
 
 
//--------------------------------------------------------------
// add_statistic_head()
//
// fuegt Basisdaten den OSD- und BL-Listen hinzu
//--------------------------------------------------------------
void add_statistic_head( void )
{
PKTdatetime_t dtlocal;
 
//---------------------------
// begin: date/time
//---------------------------
UTCdatetime2local( &dtlocal, &Config.OSD_Statistic.begin_StatTime );
ScrollBox_Push_P( MNORMAL, PSTR("Begin: %02u:%02u %02u.%02u."),
(uint16_t)(dtlocal.seconds/3600), (uint16_t)(dtlocal.seconds/60%60),
//lcd_printp_at( 3, 3, strGet(DELETEDATA), MNORMAL); // "Daten loeschen?"
dtlocal.day, dtlocal.month
);
 
//---------------------------
// end: date/time
//---------------------------
UTCdatetime2local( &dtlocal, &Config.OSD_Statistic.end_StatTime );
ScrollBox_Push_P( MNORMAL, PSTR("End: %02u:%02u %02u.%02u."),
(uint16_t)(dtlocal.seconds/3600), (uint16_t)(dtlocal.seconds/60%60),
dtlocal.day, dtlocal.month
);
 
//+++++++++++++++++++++++++++
// TRENNER
//+++++++++++++++++++++++++++
ScrollBox_PushLine();
}
 
 
 
//--------------------------------------------------------------
// zeigt aufgezeichnete OSD-Daten an
//--------------------------------------------------------------
void OSDDATA_Statistics( void )
{
int16_t v;
osd_BLmax_t blmax;
 
lcd_cls();
 
if( !ScrollBox_Create(25) )
return; // kein RAM mehr
 
//+++++++++++++++++++++++++++
// max. der BL's ermitteln
//+++++++++++++++++++++++++++
calc_BLmax( &blmax );
 
ScrollBox_Push_P( MINVERS, PSTR(" OSD Data") );
 
//---------------------------
// Basisanzeige der Stat-Liste
//---------------------------
add_statistic_head();
 
//---------------------------
// last Flytime
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR(" Last Fly %02u:%02u min"), (Config.OSD_Statistic.last_FlyTime/60), (Config.OSD_Statistic.last_FlyTime%60) );
 
//---------------------------
// max. Altitude
//---------------------------
v = Config.OSD_Statistic.max_Altimeter / (30 / AltimeterAdjust);
ScrollBox_Push_P( MNORMAL, PSTR("%cAltitude%7d m"), SYMBOL_MAX, v );
 
//---------------------------
// max. Distance
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%cDistance%7u m"), SYMBOL_MAX, Config.OSD_Statistic.max_Distance/10 );
 
//---------------------------
// max. Ground-Speed
//---------------------------
v = (uint16_t) (((uint32_t) Config.OSD_Statistic.max_GroundSpeed * (uint32_t) 90) / (uint32_t) 250);
ScrollBox_Push_P( MNORMAL, PSTR("%cGrnd.Speed%3.1d kmh"), SYMBOL_MAX, v );
 
//---------------------------
// max. Vert.-Speed
//---------------------------
v = Config.OSD_Statistic.max_TopSpeed;
v = (v*36/100); // cm/s -> km/h*10
ScrollBox_Push_P( MNORMAL, PSTR("%cVert.Speed%3.1d kmh"), SYMBOL_MAX, v );
 
 
//+++++++++++++++++++++++++++
// TRENNER
//+++++++++++++++++++++++++++
ScrollBox_PushLine();
 
 
//---------------------------
// Used Capacity
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR(" Capacity%7d mAh"), Config.OSD_Statistic.max_Capacity );
 
//---------------------------
// max. Current
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%cCurrent%6.1d A"), SYMBOL_MAX, Config.OSD_Statistic.max_Current );
 
//---------------------------
// avg. Current
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%cCurrent%6.1d A"), SYMBOL_AVG, (uint8_t)(Config.OSD_Statistic.avg_Current/100) );
 
//---------------------------
// BL-Detected
//---------------------------
//ScrollBox_Push_P( MNORMAL, PSTR(" BL Detected%4d"), Config.OSD_Statistic.BL_Count );
 
//---------------------------
// max. BL-Current
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%cBL%1d Curr.%4.1u A"), SYMBOL_MAX, blmax.max_BL_Current_Index+1, blmax.max_BL_Current );
 
//---------------------------
// max. BL-Temp
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%cBL%1d Temp. %5u %cC"), SYMBOL_MAX, blmax.max_BL_Temp_Index+1, blmax.max_BL_Temp, SYMBOL_BIGDEGREE );
 
//---------------------------
// min. Voltage
//---------------------------
v = (Config.OSD_Statistic.min_UBat == 255) ? 0 : Config.OSD_Statistic.min_UBat;
ScrollBox_Push_P( MNORMAL, PSTR("%cVoltage%6.1d V"), SYMBOL_MIN, v );
 
 
//+++++++++++++++++++++++++++
// TRENNER
//+++++++++++++++++++++++++++
ScrollBox_PushLine();
 
 
//---------------------------
// max. RC-Quality
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%cRC-Quality%5d"), SYMBOL_MAX, Config.OSD_Statistic.max_RCQuality );
 
//---------------------------
// min. RC-Quality
//---------------------------
v = (Config.OSD_Statistic.min_RCQuality==255) ? 0 : Config.OSD_Statistic.min_RCQuality;
ScrollBox_Push_P( MNORMAL, PSTR("%cRC-Quality%5d"), SYMBOL_MIN, v );
 
 
//---------------------------
// max. Nick
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%cNick%11d %c"), SYMBOL_MAX, Config.OSD_Statistic.max_AngleNick, SYMBOL_SMALLDEGREE );
 
//---------------------------
// min. Nick
//---------------------------
v = (Config.OSD_Statistic.min_AngleNick==126) ? 0 : Config.OSD_Statistic.min_AngleNick;
ScrollBox_Push_P( MNORMAL, PSTR("%cNick%11d %c"), SYMBOL_MIN, v, SYMBOL_SMALLDEGREE );
 
//---------------------------
// max. Roll
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%cRoll%11d %c"), SYMBOL_MAX, Config.OSD_Statistic.max_AngleRoll, SYMBOL_SMALLDEGREE );
 
//---------------------------
// min. Roll
//---------------------------
v = (Config.OSD_Statistic.min_AngleRoll==126) ? 0 : Config.OSD_Statistic.min_AngleRoll;
ScrollBox_Push_P( MNORMAL, PSTR("%cRoll%11d %c"), SYMBOL_MIN, v, SYMBOL_SMALLDEGREE );
 
 
//+++++++++++++++++++++++++++
// TRENNER
//+++++++++++++++++++++++++++
ScrollBox_PushLine();
 
ctrl_osddata( true, INIT_STATISTIC );
 
ScrollBox_Destroy(); // free memory
}
 
 
 
//--------------------------------------------------------------
// zeigt aufgezeichnete BL-Daten an
//--------------------------------------------------------------
void OSDDATA_StatisticsBL( void )
{
uint8_t i;
osd_BLmax_t blmax;
 
lcd_cls();
 
#ifdef USE_OSD_SCREEN_DEBUG
if( !ScrollBox_Create(10 + (Config.OSD_Statistic.BL_Count*6)) )
return; // kein RAM mehr
#else
if( !ScrollBox_Create(10 + (Config.OSD_Statistic.BL_Count*4)) )
return; // kein RAM mehr
#endif
 
//+++++++++++++++++++++++++++
// max. der BL's ermitteln
//+++++++++++++++++++++++++++
calc_BLmax( &blmax );
 
ScrollBox_Push_P( MINVERS, PSTR(" BL Data") );
 
//---------------------------
// Basisanzeige der Stat-Liste
//---------------------------
add_statistic_head();
 
//---------------------------
// max. Current
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%cCurrent%6.1d A"), SYMBOL_MAX, Config.OSD_Statistic.max_Current );
 
//---------------------------
// avg. Current
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%cCurrent%6.1d A"), SYMBOL_AVG, (uint8_t)(Config.OSD_Statistic.avg_Current/100) );
 
//---------------------------
// BL-Detected
//---------------------------
//ScrollBox_Push_P( MNORMAL, PSTR("BL Detected %4d"), Config.OSD_Statistic.BL_Count );
 
//---------------------------
// max. BL-Current
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%cBL%1d Current%2.1u A"), SYMBOL_MAX, blmax.max_BL_Current_Index+1, blmax.max_BL_Current );
 
//---------------------------
// max. BL-Temp
//---------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%cBL%1d Temp. %5u %cC" ), SYMBOL_MAX, blmax.max_BL_Temp_Index+1, blmax.max_BL_Temp, SYMBOL_BIGDEGREE );
 
 
//+++++++++++++++++++++++++++
// TRENNER
//+++++++++++++++++++++++++++
ScrollBox_PushLine();
 
//---------------------------
// LIST: BL-Data
//---------------------------
if( Config.OSD_Statistic.BL_Count > 0 )
{
ScrollBox_Push_P( MINVERS, PSTR(" BL Data") );
 
for( i=0; i < Config.OSD_Statistic.BL_Count; i++)
{
ScrollBox_Push_P( MNORMAL, PSTR("%1d:%cCurrent%4.1u A"), (i+1), SYMBOL_MAX, (uint8_t)(Config.OSD_Statistic.BL[i].max_Current) );
ScrollBox_Push_P( MNORMAL, PSTR(" %cCurrent%4.1u A" ), SYMBOL_AVG, (uint8_t)(Config.OSD_Statistic.BL[i].avg_Current/100) );
ScrollBox_Push_P( MNORMAL, PSTR(" %cTemp.%8u %cC" ), SYMBOL_MAX, (uint8_t)(Config.OSD_Statistic.BL[i].max_Temp), SYMBOL_BIGDEGREE );
 
#ifdef USE_OSD_SCREEN_DEBUG
ScrollBox_Push_P( MNORMAL, PSTR(" RX-Pkg.%7u"), Config.OSD_Statistic.BL[i].count );
//ScrollBox_Push_P( MNORMAL, PSTR(" MC%12u A" ), Config.OSD_Statistic.BL[i].avg_Current );
#endif
 
//+++++++++++++++++++++++++++
// TRENNER
//+++++++++++++++++++++++++++
ScrollBox_PushLine();
}
}
 
ctrl_osddata( true, INIT_STATISTIC );
 
ScrollBox_Destroy(); // free memory
}
 
 
 
//--------------------------------------------------------------
// zeigt aufgezeichnete Benutzer-GPS-Daten an
//--------------------------------------------------------------
void OSDDATA_UserGPS( void )
{
uint8_t i;
uint8_t isdata = 0;
PKTdatetime_t dtlocal;
 
lcd_cls();
 
if( !ScrollBox_Create( (MAX_GPS_USER*4) + 5 ) ) // Speicher reservieren
return; // kein RAM mehr
 
ScrollBox_Push_P( MINVERS, PSTR(" GPS Userdata") );
 
for( i=0; i<MAX_GPS_USER; i++)
{
if( Config.GPS_User[i].GPSData.Latitude != 0) // nur gueltige GPS-Koordinaten anzeigen
{
isdata = 1;
 
ScrollBox_PushLine();
 
//-----------------------------------
// Zeile 1: Nummer / Datum / Zeit
//-----------------------------------
UTCdatetime2local( &dtlocal, &Config.GPS_User[i].timestamp );
ScrollBox_Push_P( MNORMAL, PSTR("%02u.%02u.%04u %02u:%02u:%02u"),
dtlocal.day, dtlocal.month, dtlocal.year,
(uint16_t)(dtlocal.seconds/3600), (uint16_t)(dtlocal.seconds/60%60), (uint16_t)(dtlocal.seconds%60)
);
 
/*
sec = (uint16_t)(Config.GPS_User[i].timestamp.seconds); // Sekunden
ScrollBox_Push_P( MNORMAL, PSTR("%02u.%02u.%04u %02u:%02u:%02u"),
Config.MKErr_Log[i].set_Time.day, Config.MKErr_Log[i].set_Time.month, Config.MKErr_Log[i].set_Time.year,
(uint16_t)(sec/3600), (uint16_t)(sec/60%60), (uint16_t)(sec%60)
);
 
// Alternative Anzeige von Datum/Zeit:
min = (uint16_t)(Config.GPS_User[i].timestamp.seconds/60); // Minuten
ScrollBox_Push_P( MNORMAL, PSTR("%02u: %02u:%02u %02u.%02u.%02u"), i+1,
(uint16_t)(min/60), (uint16_t)(min%60),
Config.GPS_User[i].timestamp.day, Config.GPS_User[i].timestamp.month, Config.GPS_User[i].timestamp.year%100
);
 
// Alternative Anzeige von Datum/Zeit:
ScrollBox_Push_P( MNORMAL, PSTR("%02u: %02u:%02u %02u.%02u.%04u"), i+1,
(uint16_t)(min/60), (uint16_t)(min%60),
Config.GPS_User[i].timestamp.day, Config.GPS_User[i].timestamp.month, Config.GPS_User[i].timestamp.year
);
 
// Alternative Anzeige von Datum/Zeit:
ScrollBox_Push_P( MNORMAL, PSTR("%02u: %02u.%02u.%04u %02u:%02u"), i+1,
Config.GPS_User[i].timestamp.day, Config.GPS_User[i].timestamp.month, Config.GPS_User[i].timestamp.year,
(uint16_t)(min/60), (uint16_t)(min%60)
);
*/
//-----------------------------------
// Zeile 2: Hoehe (GPS/Barymetrisch)
//-----------------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%7d mG%5.1d mB"),
(Config.GPS_User[i].GPSData.Altitude/1000), // GPS-Hoehe in m
(Config.GPS_User[i].Altimeter / (3 / AltimeterAdjust)) ); // Barymetrische-Hoehe in dm
 
//-----------------------------------
// Zeile 3: Koordinaten (Lat/Long)
//-----------------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%3.6ld%3.6ld"),
Config.GPS_User[i].GPSData.Latitude/10,
Config.GPS_User[i].GPSData.Longitude/10 );
}
}
ScrollBox_PushLine();
 
 
ctrl_osddata( isdata, INIT_USERGPS );
 
ScrollBox_Destroy(); // free memory
}
 
 
 
//--------------------------------------------------------------
// OSDDATA_MkError()
//
// zeigt aufgezeichnete MK-Fehler an
//--------------------------------------------------------------
void OSDDATA_MkError( void )
{
uint8_t i;
uint8_t isdata = 0;
PKTdatetime_t dtlocal;
 
lcd_cls();
 
if( !ScrollBox_Create( (MAX_MKERR_LOG*4) + 3 ) ) // Speicher reservieren
return; // kein RAM mehr
 
ScrollBox_Push_P( MINVERS, PSTR(" MK Errors") );
 
for( i=0; i<MAX_MKERR_LOG; i++)
{
if( Config.MKErr_Log[i].Errorcode != 0) // nur vorhandene Errorcodes anzeigen
{
isdata = 1;
 
ScrollBox_PushLine();
 
//-----------------------------------
// Zeile 1: Zeit / Datum
//-----------------------------------
UTCdatetime2local( &dtlocal, &Config.MKErr_Log[i].set_Time );
ScrollBox_Push_P( MNORMAL, PSTR("%02u:%02u:%02u %02u.%02u.%04u"),
(uint16_t)(dtlocal.seconds/3600), (uint16_t)(dtlocal.seconds/60%60), (uint16_t)(dtlocal.seconds%60),
dtlocal.day, dtlocal.month, dtlocal.year
);
 
//-----------------------------------
// Zeile 2: Error Code
//-----------------------------------
ScrollBox_Push_P( MNORMAL, PSTR(" Code %02u"), Config.MKErr_Log[i].Errorcode );
 
//-----------------------------------
// Zeile 3: Error Text
//-----------------------------------
ScrollBox_Push_P( MNORMAL, PSTR("%20S"), pgm_read_word(&mkerrortext[Config.MKErr_Log[i].Errorcode]) );
}
}
ScrollBox_PushLine();
 
ctrl_osddata( isdata, INIT_MKERROR );
 
ScrollBox_Destroy(); // free memory
}
 
 
 
//--------------------------------------------------------------
// OSDDATA_ShowLastGPSPosition()
//
// zeigt die letzte aufgezeichnete GPS-Position an.
// Möglichkeit zum loeschen der GPS-Pos ist vorhanden.
//--------------------------------------------------------------
void OSDDATA_ShowLastGPSPosition( void )
{
uint8_t redraw = true;
 
clear_key_all();
 
while( true )
{
//------------------------
// Screen neu zeichnen
//------------------------
if( redraw )
{
PKT_TitlePKT(); // Titel mit PKT-Version anzeigen (und clearcsreen)
 
lcdx_printp_at(3, 1, strGet(START_LASTPOS) , MNORMAL, 0,4); // "Letzte Position"
lcdx_printp_at(3, 2, strGet(START_LASTPOS3), MNORMAL, 0,4); // "Google Eingabe"
 
//----
lcd_frect( 0, (4*7)+4, 127, 7, 1); // Rect: Invers
lcdx_printp_at(1, 3, strGet(START_LASTPOS1), MINVERS, 0,8); // "Breitengr Längengr"
 
writex_gpspos( 1, 4, Config.LastLatitude , MNORMAL, 0,10); // Anzeige: Breitengrad
writex_gpspos( 12, 4, Config.LastLongitude, MNORMAL, -1,10); // Anzeige: Laengengrad
 
lcd_rect( 0, (3*8)+7, 127, (2*8)+4, 1); // Rahmen
 
//lcd_printp_at(0, 7, strGet(START_LASTPOS2), MNORMAL); // Keyline
lcd_printp_at(12, 7, strGet(KEYLINE4) , MNORMAL); // Keyline
lcd_printp_at(18, 7, PSTR("Del") , MNORMAL); // Keyline
 
redraw = false;
}
 
 
//------------------------
// LiPo Spannung zeigen
//------------------------
show_Lipo();
 
 
//------------------------
// Tasten abfragen
//------------------------
if( get_key_press (1 << KEY_ESC) ) // Ende
{
break;
}
 
if( (get_key_press (1 << KEY_ENTER)) ) // Del
{
if( ask_delete_data(INIT_LASTPOS) )
{
set_beep ( 400, 0xffff, BeepNormal);
WriteLastPosition( 0x00000000, 0x00000000 ); // letzte GPS Position loeschen
break; // und beenden
}
redraw = true;
}
 
 
//------------------------
// ggf. auf PKT-Update reagieren
//------------------------
if( PKT_CtrlHook() )
{
redraw = true;
}
}
 
clear_key_all();
}
 
 
 
 
//--------------------------------------------------------------
// OSDDATA_ClearAllData()
//
// löscht alle erhobenen Daten
//--------------------------------------------------------------
void OSDDATA_ClearAllData( void )
{
if( ask_delete_data( INIT_ALLDATA ) )
{
STAT_Init();
MKErr_Log_Init();
GPS_User_Init(); // loeschen: User GPS
WriteLastPosition( 0x00000000, 0x00000000 ); // loeschen: letzte GPS Position
 
set_beep ( 400, 0xffff, BeepNormal);
}
}
 
 
 
//--------------------------------------------------------------
// Menue fuer osddata
//--------------------------------------------------------------
#ifdef USE_OSDDATA
void Menu_OSDData( void )
{
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "OSD Daten"
//MenuCtrl_SetTitle_P( PSTR("OSD Daten") );
//MenuCtrl_SetShowBatt( true );
 
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( ID_SHOWSTATISTIK , MENU_ITEM, &OSDDATA_Statistics, SHOWSTATISTIK_de , SHOWSTATISTIK_en );
MenuCtrl_PushML2_P( ID_SHOWBLSTATISTIK, MENU_ITEM, &OSDDATA_StatisticsBL, SHOWBLSTATISTIK_de, SHOWBLSTATISTIK_en );
MenuCtrl_PushML2_P( ID_SHOWMKERROR , MENU_ITEM, &OSDDATA_MkError, SHOWMKERROR_de , SHOWMKERROR_en );
MenuCtrl_PushML2_P( ID_SHOWUSERGPS , MENU_ITEM, &OSDDATA_UserGPS, SHOWUSERGPS_de , SHOWUSERGPS_en );
MenuCtrl_PushML2_P( ID_SHOWLASTGPS , MENU_ITEM, &OSDDATA_ShowLastGPSPosition, SHOWLASTGPS_de , SHOWLASTGPS_en );
MenuCtrl_PushML2_P( ID_CLEARALLDATA , MENU_ITEM, &OSDDATA_ClearAllData, CLEARALLDATA_de , CLEARALLDATA_en );
 
//---------------
// Control
//---------------
MenuCtrl_Control( MENUCTRL_EVENT );
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
#endif
 
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/osd/osddata.h
0,0 → 1,38
/*****************************************************************************
* Copyright (C) 2013 Oliver Gemesi *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
*****************************************************************************/
 
//############################################################################
//# HISTORY osddata.h
//#
//# 29.03.2014 OG
//# - add: OSDDATA_ShowLastGPSPosition()
//#
//# 11.06.2013 OG
//# - add: Menu_OSDData() - ehemals in menu.c jetzt hier
//# - del: verschiedene andere exportierte Funktionen
//#
//# 20.04.2013 OG - NEU
//############################################################################
 
#ifndef _OSDDATA_H
#define _OSDDATA_H
 
void OSDDATA_ShowLastGPSPosition( void );
void Menu_OSDData( void );
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/osd/osdold_messages.c
0,0 → 1,117
 
/*****************************************************************************
* hier wird Code von den alten OSD-Screens ausgelagert um messages.c zu entkernen
*****************************************************************************/
 
//############################################################################
//# HISTORY osdold_messages.c
//#
//# 01.06.2014 OG * NEU *
//# Auslagerung von Texten aus messages.c speziell fuer die alten und nicht mehr
//# unterstuetzten OSD-Screens
//############################################################################
 
 
#include <avr/pgmspace.h>
#include "../main.h"
 
#ifdef USE_OSD_SCREEN_OLD
 
#include "../eeprom/eeprom.h"
#include "osdold_messages.h"
 
 
//---------------------------------------------------------------------------------
 
static const char OSD_ALTI_0_de[] PROGMEM = "Höhe aus ";
static const char OSD_ALTI_0_en[] PROGMEM = "Alti. off ";
 
static const char OSD_ALTI_1_de[] PROGMEM = "Höhe begr.";
static const char OSD_ALTI_1_en[] PROGMEM = "Alti.Limit";
 
static const char OSD_VARIO_0_de[] PROGMEM = "Vario aus ";
static const char OSD_VARIO_0_en[] PROGMEM = "Vario off ";
 
static const char OSD_VARIO_1_de[] PROGMEM = "Vario Höhe";
static const char OSD_VARIO_1_en[] PROGMEM = "Vario Alt.";
 
static const char OSD_CARE_FREE_0_de[] PROGMEM = " ";
#define OSD_CARE_FREE_0_en OSD_CARE_FREE_0_de
 
static const char OSD_CARE_FREE_1_de[] PROGMEM = "Care Free";
#define OSD_CARE_FREE_1_en OSD_CARE_FREE_1_de
 
static const char OSD_NAVI_MODE_0_de[] PROGMEM = "Navi aus ";
static const char OSD_NAVI_MODE_0_en[] PROGMEM = "Navi off ";
 
static const char OSD_NAVI_MODE_1_de[] PROGMEM = "Pos. halten";
static const char OSD_NAVI_MODE_1_en[] PROGMEM = "Pos. Hold ";
 
static const char OSD_NAVI_MODE_2_de[] PROGMEM = "Coming Home";
#define OSD_NAVI_MODE_2_en OSD_NAVI_MODE_2_de
 
static const char OSD_FLAGS_0_de[] PROGMEM = " ";
#define OSD_FLAGS_0_en OSD_FLAGS_0_de
 
static const char OSD_FLAGS_1_de[] PROGMEM = "Justieren";
static const char OSD_FLAGS_1_en[] PROGMEM = "Calibrate";
 
static const char OSD_FLAGS_2_de[] PROGMEM = "Start ";
#define OSD_FLAGS_2_en OSD_FLAGS_2_de
 
static const char OSD_FLAGS_3_de[] PROGMEM = "Betrieb ";
static const char OSD_FLAGS_3_en[] PROGMEM = "Run ";
 
static const char OSD_FLAGS_4_de[] PROGMEM = "Fliegen ";
static const char OSD_FLAGS_4_en[] PROGMEM = "Fly ";
 
static const char OSD_FLAGS_5_de[] PROGMEM = "Landung ";
static const char OSD_FLAGS_5_en[] PROGMEM = "Landing ";
 
static const char OSD_FLAGS_6_de[] PROGMEM = "Akku leer";
static const char OSD_FLAGS_6_en[] PROGMEM = "Low Bat. ";
 
static const char OSD_LED_Form_de[] PROGMEM = "Out1/2 Format";
static const char OSD_LED_Form_en[] PROGMEM = "Out1/2 format";
 
//------------------------------------------------------------------------------
 
 
const char * const strings_osdold[] PROGMEM=
{
OSD_ALTI_0_de, OSD_ALTI_0_en,
OSD_ALTI_1_de, OSD_ALTI_1_en,
OSD_VARIO_0_de, OSD_VARIO_0_en,
OSD_VARIO_1_de, OSD_VARIO_1_en,
OSD_CARE_FREE_0_de, OSD_CARE_FREE_0_en,
OSD_CARE_FREE_1_de, OSD_CARE_FREE_1_en,
OSD_NAVI_MODE_0_de, OSD_NAVI_MODE_0_en,
OSD_NAVI_MODE_1_de, OSD_NAVI_MODE_1_en,
OSD_NAVI_MODE_2_de, OSD_NAVI_MODE_2_en,
OSD_FLAGS_0_de, OSD_FLAGS_0_en,
OSD_FLAGS_1_de, OSD_FLAGS_1_en,
OSD_FLAGS_2_de, OSD_FLAGS_2_en,
OSD_FLAGS_3_de, OSD_FLAGS_3_en,
OSD_FLAGS_4_de, OSD_FLAGS_4_en,
OSD_FLAGS_5_de, OSD_FLAGS_5_en,
OSD_FLAGS_6_de, OSD_FLAGS_6_en,
OSD_LED_Form_de, OSD_LED_Form_en,
 
//******************************************************************
// hier stehen lassen, alle neuen Strings hier drüber einfügen
//LAST_STR_de, LAST_STR_en,
};
 
 
char const * strGetOSDOLD( int str_no )
{
if( Config.DisplayLanguage > 1 ) Config.DisplayLanguage = 1;
 
if( Config.DisplayLanguage == 0 ) return (const char*) pgm_read_word( &strings_osdold[str_no*2] );
if( Config.DisplayLanguage == 1 ) return (const char*) pgm_read_word( &strings_osdold[(str_no*2)+1] );
 
return (const char*) pgm_read_word( &strings_osdold[0] );
}
 
 
#endif // ifdef: USE_OSD_SCREEN_OLD
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/osd/osdold_messages.h
0,0 → 1,40
 
/*****************************************************************************
* hier wird Code von den alten OSD-Screens ausgelagert um messages.c zu entkernen
*****************************************************************************/
 
//############################################################################
//# HISTORY osdold_messages.h
//#
//# 01.06.2014 OG * NEU *
//# Auslagerung von Texten aus messages.c speziell fuer die alten und nicht mehr
//# unterstuetzten OSD-Screens
//############################################################################
 
#ifndef OSDOLD_MESSAGES_H
#define OSDOLD_MESSAGES_H
 
 
#include "../main.h"
 
 
#ifdef USE_OSD_SCREEN_OLD
 
//---------------------------------------------------------------------------------------------------------------------
// Typdefinitionen für alle verwendeten Strings
//LAST_STR muss am Ende stehen bleiben
typedef enum
{
OSD_ALTI_0, OSD_ALTI_1, OSD_VARIO_0, OSD_VARIO_1, OSD_CARE_FREE_0, OSD_CARE_FREE_1,
OSD_NAVI_MODE_0, OSD_NAVI_MODE_1, OSD_NAVI_MODE_2,
OSD_FLAGS_0, OSD_FLAGS_1, OSD_FLAGS_2, OSD_FLAGS_3, OSD_FLAGS_4, OSD_FLAGS_5, OSD_FLAGS_6,
OSD_LED_Form
} OSDOLDSTR;
 
 
char const * strGetOSDOLD( int str_no );
 
 
#endif // USE_OSD_SCREEN_OLD
 
#endif /* OSDOLD_MESSAGES_H_ */
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/osd/osdold_screens.c
0,0 → 1,271
 
/*****************************************************************************
* hier wird Code von den alten OSD-Screens ausgelagert um osd.c zu entkernen
*****************************************************************************/
 
//############################################################################
//# HISTORY osdold_screens.c
//#
//# 01.06.2014 OG * NEU *
//# Auslagerung von Funktionen fuer alte OSD-Screens aus osd.c
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <string.h>
#include <util/atomic.h>
 
#include "../main.h"
#include "../lcd/lcd.h"
#include "../timer/timer.h"
#include "../uart/usart.h"
#include "../eeprom/eeprom.h"
#include "../messages.h"
#include "../sound/pwmsine8bit.h"
#include "../mk-data-structs.h"
#include "../pkt/pkt.h"
#include "../osd/osd.h"
#include "../utils/xutils.h"
#include "../mk/mkbase.h"
#include "../osd/osdold_messages.h"
#include "../osd/osdold_screens.h"
 
 
 
#ifdef USE_OSD_SCREEN_OLD
 
 
//--------------------------------------------------------------
// OSD_Element_AltitudeControl( x, y)
//--------------------------------------------------------------
void OSD_Element_AltitudeControl( uint8_t x, uint8_t y )
{
//---------------------------------------------------------
// 10.03.2013 OG:
// CFG2_HEIGHT_LIMIT im Augenblick nicht unterstuetzt
// Siehe Anmerkungen in osd()
//---------------------------------------------------------
/*
if (Flags_ExtraConfig & CFG2_HEIGHT_LIMIT)
{
if (naviData->FCStatusFlags2 & FC_STATUS2_ALTITUDE_CONTROL)
lcd_printp_at (x, y, strGet(OSD_ALTI_1), 0); // Höhe begr.
else
lcd_printp_at (x, y, strGetOSDOLD(OSD_ALTI_0), 0); // Höhe aus
}
else
{
if (naviData->FCStatusFlags2 & FC_STATUS2_ALTITUDE_CONTROL)
lcd_printp_at (x, y, strGetOSDOLD(OSD_VARIO_1), 0); // Vario Höhe
else
lcd_printp_at (x, y, strGetOSDOLD(OSD_VARIO_0), 0); // Vario aus
}
*/
 
if (naviData->FCStatusFlags2 & FC_STATUS2_ALTITUDE_CONTROL)
lcd_printp_at (x, y, strGetOSDOLD(OSD_VARIO_1), 0); // Vario Höhe
else
lcd_printp_at (x, y, strGetOSDOLD(OSD_VARIO_0), 0); // Vario aus
}
 
 
//--------------------------------------------------------------
// OSD_Element_CareFree( x, y)
//--------------------------------------------------------------
void OSD_Element_CareFree( uint8_t x, uint8_t y )
{
lcd_printp_at (x, y, strGetOSDOLD( naviData->FCStatusFlags2 & FC_STATUS2_CAREFREE ? OSD_CARE_FREE_1 : OSD_CARE_FREE_0 ), 0);
}
 
 
//--------------------------------------------------------------
// OSD_Element_NaviMode( x, y)
//--------------------------------------------------------------
void OSD_Element_NaviMode( uint8_t x, uint8_t y )
{
if (naviData->NCFlags & NC_FLAG_FREE)
lcd_printp_at (x, y, strGetOSDOLD(OSD_NAVI_MODE_0), 0); // Navi aus
else if (naviData->NCFlags & NC_FLAG_PH)
lcd_printp_at (x, y, strGetOSDOLD(OSD_NAVI_MODE_1), 0); // Pos. Hold
else if (naviData->NCFlags & NC_FLAG_CH)
lcd_printp_at (x, y, strGetOSDOLD(OSD_NAVI_MODE_2), 0); // Coming Home
}
 
 
//--------------------------------------------------------------
// OSD_Element_StatusFlags( x, y)
//--------------------------------------------------------------
void OSD_Element_StatusFlags( uint8_t x, uint8_t y )
{
// FC_StatusFlags 0.88
// #define FC_STATUS_MOTOR_RUN 0x01
// #define FC_STATUS_FLY 0x02
// #define FC_STATUS_CALIBRATE 0x04
// #define FC_STATUS_START 0x08
// #define FC_STATUS_EMERGENCY_LANDING 0x10
// #define FC_STATUS_LOWBAT 0x20
// #define FC_STATUS_VARIO_TRIM_UP 0x40
// #define FC_STATUS_VARIO_TRIM_DOWN 0x80
 
if (naviData->FCStatusFlags & FC_STATUS_CALIBRATE)
lcd_printp_at (x, y, strGetOSDOLD(OSD_FLAGS_1), 0); // Calibrate
else if (naviData->FCStatusFlags & FC_STATUS_START)
lcd_printp_at (x, y, strGetOSDOLD(OSD_FLAGS_2), 0); // Start
else if (naviData->FCStatusFlags & FC_STATUS_MOTOR_RUN)
lcd_printp_at (x, y, strGetOSDOLD(OSD_FLAGS_3), 0); // Run
else if (naviData->FCStatusFlags & FC_STATUS_FLY)
lcd_printp_at (x, y, strGetOSDOLD(OSD_FLAGS_4), 0); // Fly
else if (naviData->FCStatusFlags & FC_STATUS_EMERGENCY_LANDING)
lcd_printp_at (x, y, strGetOSDOLD(OSD_FLAGS_5), 0); // Landing
else if (naviData->FCStatusFlags & FC_STATUS_LOWBAT)
lcd_printp_at (x, y, strGetOSDOLD(OSD_FLAGS_6), 0); // LowBat
else
// lcd_printp_at (x, y, PSTR(" "), 0); // Clear
lcd_printp_at (x, y, strGetOSDOLD(OSD_FLAGS_0), 0); // Clear
}
 
 
 
//##############################################################
//# OLD OSD-Screens
//##############################################################
 
//--------------------------------------------------------------
// ehemals: OSD_ALTITUDE,Config.OSD_ScreenMode == 0
//--------------------------------------------------------------
void OSD_Screen_OSD0( void )
{
//uint8_t xoffs;
 
//-----------------------------------------
// REDRAW static screen elements
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// do things here for static screen elements like labels and so....
}
 
OSD_Element_AltitudeControl ( 0, 3);
OSD_Element_Altitude ( 11, 3, 0);
OSD_Element_BatteryLevel ( 0, 7, 0);
OSD_Element_Capacity ( 13, 7);
OSD_Element_Current ( 8, 7);
OSD_Element_CareFree ( 0, 5);
OSD_Element_CompassDegree ( 13, 0, 0);
OSD_Element_CompassDirection( 18, 0, 0,0);
OSD_Element_CompassRose ( 12, 1);
OSD_Element_FlyingTime ( 0, 1);
OSD_Element_GroundSpeed ( 0, 0);
OSD_Element_HomeCircle ( 16, 4, 5, 0, 0,0);
OSD_Element_HomeDegree ( 12, 4);
OSD_Element_HomeDistance ( 10, 5, 0);
OSD_Element_Target ( 10, 6, 0);
//OSD_Element_TargetDegree ( x, y);
OSD_Element_WayPoint ( 5, 6);
OSD_Element_LED1Output ( 0, 6);
OSD_Element_LED2Output ( 3, 6);
//OSD_Element_Manuell ( x, y);
OSD_Element_NaviMode ( 0, 4);
//OSD_Element_RCIntensity ( x, y);
OSD_Element_VarioWert ( 12, 2);
OSD_Element_SatsInUse ( 18, 2, 0);
OSD_Element_StatusFlags ( 0, 2);
OSD_Element_Variometer ( 9, 0);
}
 
 
//--------------------------------------------------------------
// ehemals: OSD_ALTITUDE,Config.OSD_ScreenMode == 1
//--------------------------------------------------------------
void OSD_Screen_OSD1( void )
{
//uint8_t xoffs;
 
//-----------------------------------------
// REDRAW static screen elements
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// do things here for static screen elements like labels and so....
}
 
//OSD_Element_AltitudeControl( x, y);
OSD_Element_Altitude ( 1, 1, 1);
OSD_Element_BatteryLevel ( 0, 7, 1);
OSD_Element_Capacity ( 13, 7);
OSD_Element_Current ( 8, 7);
//OSD_Element_CareFree ( x, y);
OSD_Element_CompassDegree ( 13, 0, 1);
OSD_Element_CompassDirection( 18, 0, 0,0);
OSD_Element_CompassRose ( 12, 1);
OSD_Element_FlyingTime ( 7, 6);
OSD_Element_GroundSpeed ( 0, 0);
OSD_Element_HomeCircle ( 1, 3, 7, 0, 0,0);
OSD_Element_HomeDegree ( 8, 3);
OSD_Element_HomeDistance ( 7, 2, 1);
//OSD_Element_Target ( x, y, 1);
//OSD_Element_TargetDegree ( x, y);
//OSD_Element_WayPoint ( x, y);
//OSD_Element_LED1Output ( x, y);
//OSD_Element_LED2Output ( x, y);
//OSD_Element_Manuell ( x, y);
OSD_Element_NaviMode ( 8, 5);
OSD_Element_RCIntensity ( 15, 6);
OSD_Element_VarioWert ( 15, 2);
OSD_Element_SatsInUse ( 8, 4, 1);
//OSD_Element_StatusFlags ( x, y);
OSD_Element_Variometer ( 9, 0);
}
 
 
//--------------------------------------------------------------
// ehemals: OSD_ALTITUDE,Config.OSD_ScreenMode == 2
//--------------------------------------------------------------
void OSD_Screen_OSD2( void )
{
//uint8_t xoffs;
 
//-----------------------------------------
// REDRAW static screen elements
//-----------------------------------------
if( OSDScreenRefresh == OSD_SCREEN_REDRAW )
{
// do things here for static screen elements like labels and so....
}
 
OSD_Element_AltitudeControl ( 0, 1);
OSD_Element_Altitude ( 0, 4, 2);
OSD_Element_BatteryLevel ( 13, 7, 2);
OSD_Element_Capacity ( 0, 7);
OSD_Element_Current ( 8, 7);
OSD_Element_CareFree ( 0, 3);
OSD_Element_CompassDegree ( 12, 3, 2);
//OSD_Element_CompassDirection( x, y, 0,0);
//OSD_Element_CompassRose ( x, y);
OSD_Element_FlyingTime ( 15, 5);
//OSD_Element_GroundSpeed ( x, y);
OSD_Element_HomeCircle ( 16, 0, 5, 0, 0,0);
OSD_Element_HomeDegree ( 11, 5);
OSD_Element_HomeDistance ( 0, 5, 2);
OSD_Element_Target ( 0, 6, 2);
OSD_Element_TargetDegree ( 11, 6);
//OSD_Element_WayPoint ( x, y);
OSD_Element_LED1Output ( 12, 2);
OSD_Element_LED2Output ( 14, 2);
//OSD_Element_Manuell ( x, y);
OSD_Element_NaviMode ( 0, 2);
//OSD_Element_RCIntensity ( x, y);
OSD_Element_VarioWert ( 15, 4);
OSD_Element_SatsInUse ( 10, 0, 2);
OSD_Element_StatusFlags ( 0, 0);
//OSD_Element_Variometer ( x, y);
}
 
 
 
#endif // ifdef: USE_OSD_SCREEN_OLD
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/osd/osdold_screens.h
0,0 → 1,35
 
/*****************************************************************************
* hier wird Code von den alten OSD-Screens ausgelagert um osd.c zu entkernen
*****************************************************************************/
 
//############################################################################
//# HISTORY osdold_screens.h
//#
//# 01.06.2014 OG * NEU *
//# Auslagerung von Funktionen fuer alte OSD-Screens aus osd.c
//############################################################################
 
#ifndef _OSDOLD_SCREENS_H
#define _OSDOLD_SCREENS_H
 
 
#include "../main.h"
 
 
#ifdef USE_OSD_SCREEN_OLD
 
void OSD_Element_AltitudeControl( uint8_t x, uint8_t y );
void OSD_Element_CareFree( uint8_t x, uint8_t y );
void OSD_Element_NaviMode( uint8_t x, uint8_t y );
void OSD_Element_StatusFlags( uint8_t x, uint8_t y );
 
 
void OSD_Screen_OSD0( void );
void OSD_Screen_OSD1( void );
void OSD_Screen_OSD2( void );
 
 
#endif // USE_OSD_SCREEN_OLD
 
#endif // _OSDOLD_SCREENS_H_
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/pkt/pkt.c
0,0 → 1,1227
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY pkt.c
//#
//# 25.06.2014 OG
//# - chg: PKT_Ask(), PKT_Ask_P() auf PKT_AskX() angepasst
//# - add: PKT_AskX() - ehemals _pkt_ask(), jetzt erweitert um zusaetzliche progmen Parameter und exportiert
//#
//# 24.06.2014 OG
//# - add: PKT_Gauge_Begin(), PKT_Gauge_End(), PKT_Gauge_Next()
//#
//# 15.06.2014 OG
//# - add: PKT_Progress_Init(), PKT_Progress_Next()
//#
//# 14.06.2014 OG
//# - add: PKT_TitlePKTlipo() fuer optionale Anzeige der LiPo-Spannung
//#
//# 13.06.2014 OG
//# - add: PKT_Ask_Restart()
//#
//# 12.06.2014 OG
//# - add: PKT_Reset_EEprom() (ehemals in setup.c)
//# - chg: PKT_Update() auf PKT_Ask_P() umgestellt
//# - add: PKT_Ask(), PKT_Ask_P(), _pkt_ask()
//#
//# 11.06.2014 OG
//# - add: PKT_Title(), PKT_Title_P(), _pkt_title()
//# - chg: PKT_TitleFromMenuItem() umgestellt auf _pkt_title()
//# - chg: PKT_TitlePKTVersion() umbenannt zu PKT_TitlePKT()
//# - fix: PKT_TitleFromMenuItem() funktioniert jetzt auch wenn kein Menue vorhanden ist
//#
//# 04.06.2014 OG
//# - add: PKT_Message_Datenverlust()
//#
//# 31.05.2014 OG
//# - fix: PKT_CtrlHook() bzgl. PKT_CheckUpdate() - seit Februar 2014 Probleme
//# mit Update-Anforderung vom PKT-Updatetool -> PKT war zu schnell
//# Es wurde jetzt ein Timer in PKT_CtrlHook() eingebaut der den Aufruf
//# von PKT_CheckUpdate() etwas einbremst ohne das PKT auszubremsen.
//# Ich hoffe, das es ist Loesung ist (bin guter Dinge nach Test's)
//# - chg: PKT_CheckUpdate() - Code optimiert
//# - add: PKT_Info() - Anzeige ob SV2-Patch vorhanden ist oder nicht (ganz oben)
//# - add: PKT_Info() - Anzeige fuer USE_OSD_SCREEN_WAYPOINTS
//# - add: PKT_KeylineUpDown()
//#
//# 23.05.2014 OG
//# - add: PKT_TitleFromMenuItem()
//# - add: #include "../utils/menuctrl.h"
//#
//# 06.05.2014 OG
//# - chg: PKT_CheckUpdate() - seit Februar funktioniert die Update-Anforderung
//# vom PKT-Updatetool an das PKT nicht immer zuverlaessig - fgf. weil sich
//# seitens des PKT's Timings etwas geaendert haben (durch weglassen von Code).
//# Hier ein Versuch etwas daran wieder zu aendern... its zwar weiterhin
//# nicht immer zuverlaessig aber vieleicht etwas besser.
//# Wahrscheinlich kann man das nur richtig korrigieren in Verbindung mit
//# Anpassungen am PKT-Updatetool - aber das ist ein anderes Thema...
//# - chg: PKT_Update() - ein kurzer Beep wenn das PKT-Update aufgerufen wird
//#
//# 05.05.2014 OG
//# - add: PKT_Popup(), PKT_Popup_P(), _pkt_popup()
//#
//# 11.04.2014 OG
//# - chg: _pkt_message() ergaenzt um clear_key_all()
//#
//# 09.04.2014 OG
//# - chg: PKT_Update() - umgestellt auf ShowTitle_P()
//#
//# 08.04.2014 OG
//# - chg: PKT_Update() - Text bzgl. "Druecke Start..." zentriert
//#
//# 04.04.2014 OG
//# - fix: define ESC umbenannt zu PKTESC da es einen Namenskonflikt mit enum
//# STR in messages.h gab
//# - add: _pkt_message() zeigt einen Titel mit PKT Version und Lipo an
//#
//# 03.04.2014 OG
//# - chg: _pkt_message() abgesichert bzgl. zu langen Texten
//#
//# 27.03.2014 OG
//# - chg: PKT_SwitchOff() Anzeige optimiert
//#
//# 21.02.2014 OG
//# - fix: PKT_CheckUpdate() Zeile 0 flimmerte wegen einer nicht mehr
//# benoetigten Textausgabe
//# - chg: PKT_SwitchOff() auf PKT_TitlePKTVersion() angepasst
//# - chg: PKT_TitlePKTVersion()
//#
//# 17.02.2014 OG
//# - add: PKT_Message(), PKT_Message_P(), _pkt_message()
//# - chg: MK_Info() auf USE_MKSETTINGS angepasst (ehemals MKPARAMETER)
//#
//# 13.02.2014 OG
//# - chg: Screenlayout von PKT_Update()
//# - chg: Screenlayout von PKT_SwitchOff()
//#
//# 11.02.2014 OG
//# - chg: PKT_Info() Anzeige der FC-Version entfernt
//#
//# 04.02.2014 OG
//# - fix: #include "../lipo/lipo.h" hinzugefuegt
//#
//# 03.02.2014 OG
//# - chg: Layout von PKT_SwitchOff() und bessere Unterstuetzung von PKT_CtrlHook()
//# - add: PKT_ShowTitleVersion()
//#
//# 30.01.2014 OG
//# - chg: geaenderte Anzeige der Reihenfolgen unterstuetzter Module in PKT_Info()
//# - add: Unterstuetzung fuer USE_BLUETOOTH
//#
//# 24.01.2014 OG
//# - chg: PKT_SwitchOff(): Layout; Code eliminiert; Beep;
//# add PKT_Hook() (für PKT-Update)
//# - chg: PKT_Update(): Layout
//#
//# 21.10.2013 CB
//# - add: PKT_Info WyFly hinzugefügt
//#
//# 07.07.2013 OG
//# - del: PKT_Info(): USE_OSD_SCREEN_ELECTRIC_N
 
//# 26.06.2013 OG
//# - del: PKT_Info(): USE_PKT_STARTINFO
//#
//# 13.06.2013 OG
//# - add: PKT-Hardwareversion in der Titelanzeige von PKT_Info()
//# - chg: Layout Titelanzeige von PKT_Info()
//# - del: USE_PCFASTCONNECT in PKT_Info() (nicht mehr benoetigt)
//# - del: PC_Fast_Connect() - ersetzt durch Menu_PKTTools() in menu.c
//#
//# 20.05.2013 OG
//# - chg: PKT_CtrlHook() bei PKT-Update um WriteParameter() ergaenzt
//#
//# 19.05.2013 OG
//# - add: PKT_CtrlHook() ruft ggf. PKT_Update() auf und kann spaeter weitere
//# PKT interne Sachen verarbeiten wie z.B. senden von Daten an den PC
//# - chg: PKT_CheckUpdate() umgestellt auf timer_pktctrl um Konflikte mit
//# mit z.B. osd zu vermeiden
//# - chg: PKT_Info() bzgl. Codeverbrauch verringert
//# - fix: PKT_Info() Anzeige von USE_OSD_SCREEN_NAVIGATION
//# - add: PC_Fast_Connect() aus menu.c
//# - add: PKT_* Funktionen aus main.c bzw. menu.c
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <avr/wdt.h>
#include <util/delay.h>
#include <avr/eeprom.h>
#include <util/atomic.h>
 
#include "../main.h"
#include "../lcd/lcd.h"
#include "../uart/usart.h"
 
#include "../uart/uart1.h"
#include "../mk-data-structs.h"
#include "../timer/timer.h"
#include "../eeprom/eeprom.h"
#include "../messages.h"
#include "../utils/scrollbox.h"
#include "../utils/xutils.h"
#include "../lipo/lipo.h"
#include "../utils/menuctrl.h"
#include "pkt.h"
 
 
//#############################################################################################
//#############################################################################################
 
uint8_t pkt_progress_act = 0;
uint8_t pkt_progress_max = 0;
int8_t pkt_progress_yoffs = 0;
uint8_t pkt_progress_width = 0;
uint8_t pkt_progress_height = 0;
 
#define PROGRESS_YOFFS -8
#define PROGRESS_WIDTH 96
 
 
 
//#############################################################################################
//#############################################################################################
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void PKT_Progress_Init( uint8_t max, int8_t yoffs, uint8_t width, uint8_t height)
{
pkt_progress_act = 0;
pkt_progress_max = max;
pkt_progress_yoffs = yoffs;
pkt_progress_width = 0; // Parameter width - aktuell nicht unterstuetzt
pkt_progress_height = 0; // Parameter height - aktuell nicht unterstuetzt
 
if( pkt_progress_width == 0 )
pkt_progress_width = PROGRESS_WIDTH;
 
lcd_rect_round( 13, 32+pkt_progress_yoffs, 102, 6, 1, R1); // Rahmen fuer Progress
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t PKT_Progress_Next( void )
{
uint8_t width;
 
pkt_progress_act++; // Progress: hochzaehlen
width = (pkt_progress_act*pkt_progress_width) / pkt_progress_max; // Progress: Breite berechnen
lcd_frect( 16, 34+pkt_progress_yoffs, width, 2, 1); // Progress: anzeigen
 
return true;
}
 
 
 
//#############################################################################################
//# Anzeigefunktionen
//#############################################################################################
 
 
//--------------------------------------------------------------
// PKT_KeylineUpDown( xUp, xDown, xoffs,yoffs)
//
// gibt in der Keyline (y=7) ein Up- und Down-Zeichen aus.
// Das Up-Zeichen wird dabei um einen Pixel versetzt damit
// es besser aussieht
//
// Parameter:
// xUp : x-Position des Up-Zeichens in Zeile 7
// xDown: x-Position des Down-Zeichens in Zeile 7
// xoffs, yoffs: normalerweise 0,0
//--------------------------------------------------------------
void PKT_KeylineUpDown( uint8_t xUp, uint8_t xDown, uint8_t xoffs, uint8_t yoffs)
{
lcdx_printp_at( xUp , 7, PSTR("\x1a") , MNORMAL, xoffs,yoffs+1); // Up
lcdx_printp_at( xDown, 7, PSTR("\x1b") , MNORMAL, xoffs,yoffs); // Down
}
 
 
 
//#############################################################################################
//# Titel Funktionen
//#############################################################################################
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void _pkt_title( uint8_t progmem, const char *text, uint8_t lShowLipo, uint8_t clearscreen )
{
const char *pMask;
 
if( clearscreen ) lcd_cls();
 
lcd_frect( 0, 0, 127, 7, 1); // Titel: Invers
 
if( progmem ) pMask = PSTR("%19S");
else pMask = PSTR("%19s");
 
lcdx_printf_at_P( 1, 0, MINVERS, 0,0, pMask, text );
 
if( lShowLipo ) show_Lipo();
}
 
 
 
//--------------------------------------------------------------
// PKT_Title( text, lShowLipo, clearscreen )
//
// text im RAM
//--------------------------------------------------------------
void PKT_Title( const char *text, uint8_t lShowLipo, uint8_t clearscreen )
{
_pkt_title( false, text, lShowLipo, clearscreen );
}
 
 
 
//--------------------------------------------------------------
// PKT_Title_P( text, lShowLipo, clearscreen )
//
// text im PROGMEM
//--------------------------------------------------------------
void PKT_Title_P( const char *text, uint8_t lShowLipo, uint8_t clearscreen )
{
_pkt_title( true, text, lShowLipo, clearscreen );
}
 
 
 
//--------------------------------------------------------------
// zeigt als Titel die PKT-Version (invers)
// optional: rechts die PKT Lipo-Spannung anzeigen
//--------------------------------------------------------------
void PKT_TitlePKTlipo( uint8_t lShowLipo )
{
//PKT_Title( buffered_sprintf_P(PSTR("PKT v%S"),PSTR(PKTSWVersion)), true, false ); // showlipo, kein clearscreen
PKT_Title( buffered_sprintf_P(PSTR("PKT v%S"),PSTR(PKTSWVersion)), lShowLipo, true ); // showlipo und clearscreen
}
 
 
 
//--------------------------------------------------------------
// zeigt als Titel die PKT-Version (invers)
// und rechts die PKT Lipo-Spannung
//--------------------------------------------------------------
void PKT_TitlePKT( void )
{
PKT_TitlePKTlipo( true );
}
 
 
 
//--------------------------------------------------------------
// PKT_TitleFromMenuItem( lShowLipo )
//
// zeigt eine PKT-Titelzeile mit Text vom aufrufenden Menuepunkt
// optional kann die PKT LiPo-Spannung angezeigt werden
//
// wenn kein Menue vorhandenist wird die PKT-Version angezeigt
//--------------------------------------------------------------
void PKT_TitleFromMenuItem( uint8_t lShowLipo )
{
const char *pStr;
uint8_t isPGM;
 
if( MenuCtrl_GetMenuIndex() < 0 )
{
PKT_TitlePKT(); // kein Menue vorhanden -> PKT-Version anzeigen
return;
}
 
pStr = MenuCtrl_GetItemText();
isPGM = MenuCtrl_IsItemTextPGM();
 
_pkt_title( isPGM, pStr, lShowLipo, true ); // true = clearscreen
}
 
 
 
//#############################################################################################
//# PKT Message
//#############################################################################################
 
//--------------------------------------------------------------
// _pkt_message( progmem, text, error, timeout, beep, clearscreen)
//
// INTERN
// fuer: PKT_Message(), PKT_Message_P()
// Parameter? -> siehe dort...
//--------------------------------------------------------------
void _pkt_message( uint8_t progmem, const char *text, uint8_t error, uint16_t timeout, uint8_t beep, uint8_t clearscreen )
{
char *pStr;
 
if( clearscreen )
lcd_cls();
 
PKT_TitlePKT();
 
if( error )
{
//lcd_frect_round( 0+36, (2*8)-2, 127-73, 8+2, 1, R1); // Fill: Schwarz
lcd_frect_round( 0+36, (2*8)-1, 127-74, 8+2, 1, R1); // Fill: Schwarz
lcdx_printp_center( 2, strGet(STR_ERROR), MINVERS, 0,1); // "FEHLER"
}
else
lcdx_printp_center( 2, strGet(STR_PKT) , MNORMAL, 0,1); // "PKT"
 
 
//-----------------------
// Ausgabe der Nachricht
//-----------------------
pStr = buffered_sprintf_P( ( progmem ? PSTR("%20S") : PSTR("%20s")), text); // max. 20 Zeichen
strrtrim( pStr ); // alle Leerzeichen rechts loeschen
lcdx_print_center( 4, (uint8_t *)pStr, MNORMAL, 0,5); // Text zentriert; String im RAM
lcd_rect_round( 0, 32, 127, 16, 1, R2); // Rahmen
 
if( beep )
{
if( error )
set_beep( 1000, 0xffff, BeepNormal ); // langer Error-Beep
else
set_beep( 25, 0xffff, BeepNormal ); // kurzer Bestaetigungs-Beep
}
 
if( timeout )
{
//lcd_printp_at( 19, 7, strGet(OK), MNORMAL); // Keyline... tja, welche Variante nehmen wir denn nun Final??? OK oder ENDE?
lcd_printp_at(12, 7, strGet(ENDE), MNORMAL); // Keyline
 
clear_key_all();
 
timer2 = timeout; // max. Anzeigezeit (z.B. 800 = 8 Sekunden)
while( timer2 > 0 )
{
//if( get_key_short(1 << KEY_ENTER) ) break;
if( get_key_short(1 << KEY_ESC) ) break;
PKT_CtrlHook();
}
}
clear_key_all();
}
 
 
 
//--------------------------------------------------------------
// PKT_Message( text, error, timeout, beep, clearscreen)
//
// zeigt eine Nachricht an ggf. mit Display-Timeout, Tasten, Beep (String im RAM)
//
// Parameter:
// text : String im RAM
// error : true/false
// timeout : 0 = direktes Verlassen der Funktion ohne warten
// 1..nnnn = max. Anzeigezeit (timer); Keyline wird
// eingeblendet -> Benutzer kann auch eher beenden
// beep : true/false - bei true haengt die Art des Beep's von 'error' ab
// clearscreen: true/false - ggf. Bildschirm loeschen
//--------------------------------------------------------------
void PKT_Message( const char *text, uint8_t error, uint16_t timeout, uint8_t beep, uint8_t clearscreen )
{
_pkt_message( false, text, error, timeout, beep, clearscreen );
}
 
 
 
//--------------------------------------------------------------
// PKT_Message_P( text, error, timeout, beep, clearscreen)
//
// zeigt eine Nachricht an ggf. mit Display-Timeout, Tasten, Beep (String im PROGMEM)
//
// Parameter:
// text : String im PROGMEM
// error : true/false
// timeout : 0 = direktes Verlassen der Funktion ohne warten
// 1..nnnn = max. Anzeigezeit (timer); Keyline wird
// eingeblendet -> Benutzer kann auch eher beenden
// beep : true/false - bei true haengt die Art des Beep's von 'error' ab
// clrscreen: true/false - ggf. Bildschirm loeschen
//--------------------------------------------------------------
void PKT_Message_P( const char *text, uint8_t error, uint16_t timeout, uint8_t beep, uint8_t clearscreen )
{
_pkt_message( true, text, error, timeout, beep, clearscreen );
}
 
 
 
//--------------------------------------------------------------
// PKT_Message_Datenverlust( timeout, beep)
//--------------------------------------------------------------
void PKT_Message_Datenverlust( uint16_t timeout, uint8_t beep )
{
//_pkt_message( true, text, error, timeout, beep, clearscreen );
_pkt_message( true, strGet(ERROR_NODATA), true, timeout, beep, true );
}
 
 
 
//#############################################################################################
//# PKT Popup
//#############################################################################################
 
//--------------------------------------------------------------
// INTERN
//
// PARAMETER:
// progmem : true = Texte in PROGMEM
// false = Texte im RAM (RAM geht noch nicht!)
// timeout : Zeit bis zum automatischen beenden (z.B. 400 = 4 Sekunden)
// wenn timeout == 0 dann direkt beenden ohne auf Tastendruck zu warten
// text1..4: Text (die Hoehe des Popups berechnet sich aus der Anzahl der Texte)
// -> ein nicht benutzer Text wird mit NULL oder Dezimal 0 uebergeben
//--------------------------------------------------------------
void _pkt_popup( uint8_t progmem, uint16_t timeout, const char *text1, const char *text2, const char *text3, const char *text4)
{
uint8_t n = 0;
uint8_t yoffs = 0;
 
if( text1 ) { n = 1; yoffs = 1; }
if( text2 ) { n = 2; yoffs = 2; }
if( text3 ) { n = 3; yoffs = 2; }
if( text4 ) { n = 4; yoffs = 3; }
 
Popup_Draw(n+1);
 
if( text1 ) lcdx_printp_center( 8-n, text1, MINVERS, 0,-5-yoffs); // Text zentriert; String im PROGMEM
if( text2 ) lcdx_printp_center( 9-n, text2, MINVERS, 0,-4-yoffs); // Text zentriert; String im PROGMEM
if( text3 ) lcdx_printp_center( 10-n, text3, MINVERS, 0,-3-yoffs); // Text zentriert; String im PROGMEM
if( text4 ) lcdx_printp_center( 11-n, text4, MINVERS, 0,-2-yoffs); // Text zentriert; String im PROGMEM
 
if( timeout )
{
clear_key_all();
 
timer2 = timeout; // max. Anzeigezeit (z.B. 800 = 8 Sekunden)
while( timer2 > 0 )
{
if( get_key_short(1<<KEY_ESC)
|| get_key_short(1<<KEY_ENTER)
|| get_key_short(1<<KEY_PLUS)
|| get_key_short(1<<KEY_MINUS) )
{
break;
}
}
 
lcd_frect( 0, 58-((n+1)*8), 127, 5+((n+1)*8), 0); // Box clear - der Bereich des Popup's wird wieder geloescht (nur wenn timeout > 0!)
}
clear_key_all();
}
 
 
 
//--------------------------------------------------------------
// PKT_Popup( timeout, text1, text2, text3, text4 )
//
// Texte im RAM
//--------------------------------------------------------------
void PKT_Popup( uint16_t timeout, const char *text1, const char *text2, const char *text3, const char *text4 )
{
_pkt_popup( false, timeout, text1, text2, text3, text4 );
}
 
 
 
//--------------------------------------------------------------
// PKT_Popup_P( timeout, text1, text2, text3, text4 )
//
// Texte im PROGMEM
//--------------------------------------------------------------
void PKT_Popup_P( uint16_t timeout, const char *text1, const char *text2, const char *text3, const char *text4 )
{
_pkt_popup( true, timeout, text1, text2, text3, text4 );
}
 
 
 
//#############################################################################################
//# PKT Ask
//#############################################################################################
 
//--------------------------------------------------------------
// wahl = PKT_AskX( asktype, text1, text2, text_progmem, headline, headline_progmem, title, title_progmem)
//
// PARAMETER:
// asktype : ASK_YES_NO, ASK_NO_YES, ASK_CANCEL_OK, ASK_END_OK, ASK_END_START
// text1 : 1. Zeile Text
// text2 : optionale 2. Zeile Text
// text_progmem : text1 & text2 in PROGMEM oder RAM (PROGMEM = true)
// headline : Ueberschrift
// headline_progmem: -> PROGMEM oder RAM
// title : ganz oben der Titel (Zeile 0, Invers)
// title_progmem : -> PROGMEM oder RAM
//
// RUECKGABE:
// true : Ja
// false : Nein
//--------------------------------------------------------------
uint8_t PKT_AskX( uint8_t asktype, const char *text1, const char *text2, uint8_t text_progmem, const char *headline, uint8_t headline_progmem, const char *title, uint8_t title_progmem )
{
uint8_t redraw = true;
uint8_t keyenter = false;
uint8_t retcode = false;
const char *pMaskP;
const char *pMaskR;
const char *pMask;
 
pMaskP = PSTR("%S");
pMaskR = PSTR("%s");
 
set_beep( 35, 0xffff, BeepNormal ); // kurzer Beep
 
while( true )
{
//------------------------
// Screen zeichnen
//------------------------
if( redraw )
{
if( title == NULL ) PKT_TitlePKT(); // Titel mit PKT-Version anzeigen (und clearscreen)
else if( title_progmem ) PKT_Title_P( title, true, true ); // uebergebenen Titel anzeigen (und clearscreen) (PROGMEM)
else PKT_Title( title, true, true ); // uebergebenen Titel anzeigen (und clearscreen) (RAM)
 
if( text2 == NULL )
{
// 1 zeiliger Text
pMask = (headline_progmem ? pMaskP : pMaskR); // Formatmaske fuer headline je nach PROGMEN oder RAM
lcdx_printf_center_P( 2, MNORMAL, 0,2, pMask, headline); // headline
 
lcd_rect_round( 0, 3*7+2+10, 127, 16+0, 1, R2); // Rahmen
 
pMask = (text_progmem ? pMaskP : pMaskR); // Formatmaske fuer text1 und text2 je nach PROGMEN oder RAM
lcdx_printf_center_P( 4, MNORMAL, 0,6, pMask, text1); // text1
}
else
{
// 2 zeiliger Text
pMask = (headline_progmem ? pMaskP : pMaskR); // Formatmaske fuer headline je nach PROGMEN oder RAM
lcdx_printf_center_P( 2, MNORMAL, 0,-1, pMask, headline); // headline
 
lcd_rect_round(0, 4*8-5, 127, 16+7, 1, R2); // Rahmen
 
pMask = (text_progmem ? pMaskP : pMaskR); // Formatmaske fuer text1 und text2 je nach PROGMEN oder RAM
lcdx_printf_center_P( 4, MNORMAL, 0,-1, pMask, text1); // text1
lcdx_printf_center_P( 5, MNORMAL, 0, 0, pMask, text2); // text2
}
 
 
//------------------------
// Keyline
//------------------------
switch( asktype )
{
case ASK_NO_YES: lcd_printp_at(12, 7, strGet(NOYES), MNORMAL); // Keyline: "Nein Ja"
break;
 
case ASK_YES_NO: lcd_printp_at(12, 7, strGet(YESNO), MNORMAL); // Keyline: "Nein Ja"
break;
 
case ASK_CANCEL_OK: lcd_printp_at(11, 7, strGet(KEYCANCEL), MNORMAL); // Keyline: "Abbr. OK"
lcd_printp_at(19, 7, PSTR("OK") , MNORMAL);
break;
 
case ASK_END_OK: lcd_printp_at(12, 7, strGet(KEYLINE4), MNORMAL); // Keyline: "Ende OK"
break;
 
case ASK_END_START: lcd_printp_at(11, 7, strGet(ENDSTART), MNORMAL); // Keyline: "Ende Start"
break;
}
 
redraw = false;
}
 
//------------------------
// LiPo Spannung zeigen
//------------------------
show_Lipo();
 
//------------------------
// ggf. auf PKT-Update reagieren
//------------------------
if( PKT_CtrlHook() )
{
redraw = true;
}
 
//------------------------
// Tasten abfragen
//------------------------
if( get_key_short(1 << KEY_ESC) ) // 3. Taste
{
break;
}
 
if( get_key_press(1 << KEY_ENTER) ) // 4. Taste
{
keyenter = true;
break;
}
} // end: while( true )
 
 
//-------------------------
retcode = keyenter;
if( asktype == ASK_YES_NO ) retcode = !retcode;
 
clear_key_all();
 
return retcode;
}
 
 
//--------------------------------------------------------------
// wahl = PKT_Ask( asktype, text1, text2, headline, title)
//
// text1 und text2 im RAM
//--------------------------------------------------------------
uint8_t PKT_Ask( uint8_t asktype, const char *text1, const char *text2, const char *headline, const char *title )
{
//wahl = PKT_AskX( asktype, text1, text2, text_progmem, headline, headline_progmem, title, title_progmem)
return PKT_AskX( asktype, text1, text2, false, headline, true, title, true);
//return _pkt_ask( false, asktype, text1, text2, headline, title);
}
 
 
 
//--------------------------------------------------------------
// wahl = PKT_Ask_P( asktype, text1, text2, headline, title)
//
// text1 und text2 im PROGMEM
//--------------------------------------------------------------
uint8_t PKT_Ask_P( uint8_t asktype, const char *text1, const char *text2, const char *headline, const char *title )
{
//wahl = PKT_AskX( asktype, text1, text2, text_progmem, headline, headline_progmem, title, title_progmem)
return PKT_AskX( asktype, text1, text2, true, headline, true, title, true);
//return _pkt_ask( true, asktype, text1, text2, headline, title);
}
 
 
//#############################################################################################
//# PKT Gauge
//#############################################################################################
 
uint8_t Gauge_px;
uint8_t Gauge_py;
uint8_t Gauge_rx;
uint8_t Gauge_ry;
uint8_t Gauge_step;
volatile uint8_t Gauge_active; // wird in timer.c abgefragt
 
#define GAUGE_DEFAULT_PX 64 // Default X (Pixel)
#define GAUGE_DEFAULT_PY 40 // Default Y (Pixel)
#define GAUGE_DEFAULT_RX 10 // Default Radius X Gauge-Kreis
#define GAUGE_DEFAULT_RY 8 // Default Radius Y Gauge-Kreis
 
#define GAUGE_TIMER 40 // alle n aktualisieren (Timer Intervall)
#define GAUGE_DEGREE 45 // Winkel von Schritt zu Schritt
#define GAUGE_LROFFS -2 // die Laenge der Gauge-Linie verringern/vergroessern
 
//--------------------------------------------------------------
// PKT_Gauge_Begin( py )
//--------------------------------------------------------------
void PKT_Gauge_Begin( uint8_t py )
{
Gauge_px = GAUGE_DEFAULT_PX;
Gauge_py = GAUGE_DEFAULT_PY;
Gauge_rx = GAUGE_DEFAULT_RX;
Gauge_ry = GAUGE_DEFAULT_RY;
 
if( py>0 ) Gauge_py = py;
 
Gauge_step = 0;
timer_gauge = GAUGE_TIMER;
Gauge_active = true;
 
lcd_ellipse_line( Gauge_px, Gauge_py, Gauge_rx+GAUGE_LROFFS, Gauge_ry+GAUGE_LROFFS, (0), 1);
lcd_ellipse( Gauge_px, Gauge_py, Gauge_rx, Gauge_ry, 1);
}
 
 
//--------------------------------------------------------------
// PKT_Gauge_End()
//--------------------------------------------------------------
void PKT_Gauge_End( void )
{
Gauge_active = false;
}
 
 
// uint8_t old_step;
 
//--------------------------------------------------------------
// PKT_Gauge_Next()
//
// INTERN fuer Timer ISR!
//--------------------------------------------------------------
void PKT_Gauge_Next( void )
{
uint8_t old_step;
 
old_step = Gauge_step;
Gauge_step++;
if( Gauge_step >= (360/GAUGE_DEGREE)) Gauge_step = 0;
 
lcd_ellipse_line( Gauge_px, Gauge_py, Gauge_rx+GAUGE_LROFFS, Gauge_ry+GAUGE_LROFFS, (old_step*GAUGE_DEGREE) , 0);
lcd_ellipse_line( Gauge_px, Gauge_py, Gauge_rx+GAUGE_LROFFS, Gauge_ry+GAUGE_LROFFS, (Gauge_step*GAUGE_DEGREE), 1);
 
timer_gauge = GAUGE_TIMER;
}
 
 
 
//#############################################################################################
//# PKT Kontrollfunktionen
//#############################################################################################
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void PKT_Reset_EEprom( void )
{
// Text1: "PKT-EEProm" (EEPROM1)
// Text2: "wirklich löschen?" (EEPROM2)
// Head : "* ACHTUNG '" (STR_ATTENTION)
// Titel: PKT-Version (NULL)
 
if( PKT_Ask_P( ASK_YES_NO, strGet(EEPROM1), strGet(EEPROM2), strGet(STR_ATTENTION), NULL) )
{
Delete_EEPROM();
clr_V_On();
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void PKT_SwitchOff( void )
{
// Text1: "PKT ausschalten?" (SHUTDOWN)
// Text2: NULL
// Head : "PKT" (STR_PKT)
// Titel: PKT-Version (NULL)
 
if( PKT_Ask_P( ASK_NO_YES, strGet(SHUTDOWN), NULL, strGet(STR_PKT), NULL) )
{
WriteParameter(); // am Ende alle Parameter sichern
clr_V_On(); // Spannung abschalten
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void PKT_Ask_Restart( const char *title )
{
// Text1: "jetzt ausschalten?" (STR_PKT_SWITCHOFF_NOW)
// Text2: NULL
// Head : "PKT neu starten!" (STR_PKT_RESTART_NOW)
// Titel: via Parameter
 
if( PKT_Ask_P( ASK_NO_YES, strGet(STR_PKT_SWITCHOFF_NOW), NULL, strGet(STR_PKT_RESTART_NOW), title) )
{
WriteParameter(); // am Ende alle Parameter sichern
clr_V_On(); // Spannung abschalten
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void PKT_Update( void )
{
// Text1: "Drücke 'Start' für" (UPDATE2)
// Text2: "min. 2 Sekunden" (UPDATE3)
// Head : "Verbinde PKT mit PC!" (UPDATE1)
// Titel: "PKT Update"
 
if( PKT_Ask_P( ASK_END_START, strGet(UPDATE2), strGet(UPDATE3), strGet(UPDATE1), PSTR("PKT Update")) )
{
uart1_putc('S'); // Startzeichen zum Updatetool schicken
wdt_enable( WDTO_250MS ); // start bootloader with Reset, Hold KEY_ENTER
while(true);
}
}
 
 
 
//void PKT_Update( void )
//{
// ShowTitle_P( PSTR("PKT Update"), true );
// lcdx_printp_center( 2, strGet(UPDATE1), MNORMAL, 0,-1); // "Verbinde PKT mit PC!"
// lcd_rect_round(0, 4*8-5, 127, 16+7, 1, R2); // Rahmen
// lcdx_printp_center( 4, strGet(UPDATE2), MNORMAL, 0,-1); // "Drücke 'Start' für"
// lcdx_printp_center( 5, strGet(UPDATE3), MNORMAL, 0, 0); // "min. 2 Sekunden"
// lcd_printp_at(11, 7, strGet(ENDSTART), MNORMAL); // Keyline
// //PKTupdate = false; // Flag löschen
//
// set_beep( 80, 0x000f, BeepNormal); // kurzer Beep
//
// do
// {
// if( get_key_press (1 << KEY_ESC) )
// {
// //get_key_press(KEY_ALL);
// clear_key_all();
// return;
// }
// }
// while( !(get_key_press (1 << KEY_ENTER)) );
//
// uart1_putc('S'); // Startzeichen zum Updatetool schicken
// wdt_enable( WDTO_250MS ); // start bootloader with Reset, Hold KEY_ENTER
// while(true);
//}
 
 
 
//--------------------------------------------------------------
// prueft im Menue ob das Updatetool ein Update machen will
//--------------------------------------------------------------
uint8_t PKT_CheckUpdate(void)
{
unsigned int uart_data;
uint8_t state = 0;
uint8_t update = false;
uint8_t error = false;
uint8_t SendVersion = false;
char s[7];
 
 
//----------------------------
// empfangen
//----------------------------
if( uart1_available() > 0 ) // Zeichen von der USB-Schnittstelle vorhanden?
{
timer_pktupdatecheck = 100; // Timeouttimer um die Funktion abzubrechen
 
while( !timer_pktupdatecheck==0 && !update && !error && !SendVersion )
{
uart_data = uart1_getc();
if( !((uart_data & 0xFF00) == UART_NO_DATA) )
{
switch (state)
{
case 0: if( uart_data == PKTESC )
{
state = 1;
}
else error = true;
break;
 
case 1: if( uart_data == PKTESC )
{
state = 2;
}
else error = true;
break;
 
case 2: if( uart_data == PKTUPDATE ) update = true;
else if (uart_data == PKTVERSION) SendVersion = true;
else error = true;
break;
} // end: switch
} // end: if
} // end: while
 
 
//----------------------------
// Rueckmeldungen
//----------------------------
if( error )
{
uart1_putc('E'); // Rueckmeldungen zum Updatetool
}
else if( update )
{
uart1_putc('U');
}
else if( SendVersion )
{
uart1_putc('V');
itoa( EEpromVersion, s, 10 );
uart1_puts(s);
}
else if( timer_pktupdatecheck==0 )
{
uart1_putc('T');
}
 
//uart1_flush();
}
 
return update;
}
 
 
 
//--------------------------------------------------------------
// retcode = PKT_CtrlHook()
//
// ruft ggf. PKT_Update() auf und kann spaeter weitere PKT interne
// Sachen verarbeiten wenn der Hook (=Nagel) in entsprechende
// Routienen eingebaut ist (z.B. senden von Daten an den PC)
//
// Aktuell verwendet von: menuctrl, scrollbox, osd
//
// Rueckgabe:
// retcode: 0 = nichts wurde gemacht (false)
// 1 = es wurde etwas durchgefuehrt und die Aufruffunktion
// muss gff. einen Screenrefresh durchfuehren
// (z.B. wenn der PKT-Update Screen gezeigt wurde)
//--------------------------------------------------------------
uint8_t PKT_CtrlHook( void )
{
uint8_t retcode = 0;
 
// 31.05.2014 OG: PKT_CheckUpdate() darf nicht in 'Hoechstgeschwindigkeit'
// aufgerufen werden da es sonst seitens des PKT-Updatetools ggf. zu einer
// Fehlermeldung kommt - deswegen hier timer_pktupdatecheck der PKT_CheckUpdate
// etwas einbremst sich aber nicht negativ auf die PKT-Performance auswirkt.
if( !timer_pktupdatecheck )
{
if( PKT_CheckUpdate() ) // Update vom Updatetool angefordert?
{
WriteParameter();
PKT_Update();
retcode = 1;
}
timer_pktupdatecheck = 10;
}
 
return retcode;
}
 
 
 
//--------------------------------------------------------------
// zeigt PKT-Version und Credits / Entwickler
//--------------------------------------------------------------
void PKT_Info( void )
{
char *HWV_39m = "3.9m";
char *HWV_39x = "3.9x";
char *HWV = "????";
 
if( PCB_Version == PKT39m ) HWV = HWV_39m;
if( PCB_Version == PKT39x ) HWV = HWV_39x;
 
lcd_cls();
 
if( !ScrollBox_Create(55) ) // max. 55 Zeilen
return; // kein RAM mehr
 
ScrollBox_Push_P( MINVERS, PSTR(" PKT v%8S %s"), PSTR(PKTSWVersion), HWV ); // "3.6.8a..." und die PKT-Hardwareversion
ScrollBox_Push_P( MINVERS, PSTR(" %S SV2-Patch"), (PCB_SV2RxTxPatch ? strGet(STR_WITH) : strGet(STR_WITHOUT)) );
ScrollBox_Push_P( MNORMAL, PSTR("") );
ScrollBox_Push_P( MNORMAL, PSTR("(C) GNU GPL License") );
ScrollBox_Push_P( MNORMAL, PSTR(" NO WARRANTY") );
ScrollBox_Push_P( MNORMAL, PSTR("") );
 
 
#ifdef USE_MODULEINFO
 
const char *fmt = PSTR("%15S %4S");
 
//--- MODULE SUPPORT INFO ---
ScrollBox_Push_P( MINVERS, PSTR(" Modules installed") );
 
#ifdef USE_BLUETOOTH
ScrollBox_Push_P( MNORMAL, fmt, PSTR("Bluetooth"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("Bluetooth"), strGet(NOO) );
#endif
 
 
#ifdef USE_WLAN
ScrollBox_Push_P( MNORMAL, fmt, PSTR("WLAN WyFly"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("WLAN WyFly"), strGet(NOO) );
#endif
 
 
#ifdef USE_MKSETTINGS
ScrollBox_Push_P( MNORMAL, fmt, PSTR("MK Settings"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("MK Settings"), strGet(NOO) );
#endif
 
 
#ifdef USE_MKDEBUGDATA
ScrollBox_Push_P( MNORMAL, fmt, PSTR("MK Debug Data"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("MK Debug Data"), strGet(NOO) );
#endif
 
 
#ifdef USE_MKDISPLAY
ScrollBox_Push_P( MNORMAL, fmt, PSTR("MK Display"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("MK Display"), strGet(NOO) );
#endif
 
 
#ifdef USE_OSDDATA
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD-Data"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD-Data"), strGet(NOO) );
#endif
 
 
#ifdef USE_OSD_SCREEN_OLD
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD Old Screens"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD Old Screens"), strGet(NOO) );
#endif
 
 
#ifdef USE_OSD_SCREEN_NAVIGATION
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD Navigation"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD Navigation"), strGet(NOO) );
#endif
 
 
#ifdef USE_OSD_SCREEN_WAYPOINTS
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD Waypoints"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD Waypoints"), strGet(NOO) );
#endif
 
 
#ifdef USE_OSD_SCREEN_ELECTRIC
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD Electric"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD Electric"), strGet(NOO) );
#endif
 
 
#ifdef USE_OSD_SCREEN_MKSTATUS
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD MKStatus"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD MKStatus"), strGet(NOO) );
#endif
 
 
#ifdef USE_OSD_SCREEN_USERGPS
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD UserGPS"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD UserGPS"), strGet(NOO) );
#endif
 
 
#ifdef USE_OSD_SCREEN_3DLAGE
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD 3D-Lage"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD 3D-Lage"), strGet(NOO) );
#endif
 
 
#ifdef USE_OSD_SCREEN_STATISTIC
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD Statistic"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("OSD Statistic"), strGet(NOO) );
#endif
 
 
#ifdef USE_TRACKING
ScrollBox_Push_P( MNORMAL, fmt, PSTR("Tracking"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("Tracking"), strGet(NOO) );
#endif
 
 
#ifdef USE_FOLLOWME
ScrollBox_Push_P( MNORMAL, fmt, PSTR("Follow Me"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("Follow Me"), strGet(NOO) );
#endif
 
 
#ifdef USE_JOYSTICK
ScrollBox_Push_P( MNORMAL, fmt, PSTR("Joystick"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("Joystick"), strGet(NOO) );
#endif
 
 
#ifdef USE_I2CMOTORTEST
ScrollBox_Push_P( MNORMAL, fmt, PSTR("I2C Motortest"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("I2C Motortest"), strGet(NOO) );
#endif
 
 
#ifdef USE_SOUND
ScrollBox_Push_P( MNORMAL, fmt, PSTR("Sound"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("Sound"), strGet(NOO) );
#endif
 
 
#ifdef USE_FONT_BIG
ScrollBox_Push_P( MNORMAL, fmt, PSTR("Font Big"), strGet(YES) );
#else
ScrollBox_Push_P( MNORMAL, fmt, PSTR("Font Big"), strGet(NOO) );
#endif
 
ScrollBox_Push_P( MNORMAL, PSTR("") );
 
#endif // USE_MODULEINFO
 
 
//--- CREDITS INFO ---
ScrollBox_Push_P( MINVERS, PSTR(" Credits") );
ScrollBox_Push_P( MNORMAL, PSTR("2013 Oliver Gemesi") );
ScrollBox_Push_P( MNORMAL, PSTR("2012 Chr. Brandtner" ) );
ScrollBox_Push_P( MNORMAL, PSTR(" Harald Bongartz") );
ScrollBox_Push_P( MNORMAL, PSTR("2012 Martin Runkel") );
ScrollBox_Push_P( MNORMAL, PSTR("2012 gebad") );
ScrollBox_Push_P( MNORMAL, PSTR("2010 Sebastian Boehm") );
ScrollBox_Push_P( MNORMAL, PSTR("2009-2010 Peter Mack") );
ScrollBox_Push_P( MNORMAL, PSTR("2008 Thomas Kaiser") );
 
ScrollBox_Show();
ScrollBox_Destroy(); // free memory
}
 
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/pkt/pkt.h
0,0 → 1,148
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2012 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2012 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY pkt.h
//#
//# 25.06.2014 OG
//# - add: PKT_AskX()
//#
//# 24.06.2014 OG
//# - add: PKT_Gauge_Begin(), PKT_Gauge_End(), PKT_Gauge_Next()
//#
//# 15.06.2014 OG
//# - add: PKT_Progress_Init(), PKT_Progress_Next()
//#
//# 14.06.2014 OG
//# - add: PKT_TitlePKTlipo() fuer optionale Anzeige der LiPo-Spannung
//#
//# 13.06.2014 OG
//# - add: PKT_Ask_Restart()
//#
//# 12.06.2014 OG
//# - add: PKT_Reset_EEprom()
//# - add: PKT_Ask(), PKT_Ask_P()
//#
//# 11.06.2014 OG
//# - add: PKT_Title(), PKT_Title_P()
//#
//# 04.06.2014 OG
//# - add: PKT_Message_Datenverlust()
//#
//# 31.05.2014 OG
//# - add: PKT_KeylineUpDown()
//#
//# 23.05.2014 OG
//# - add: PKT_TitleFromMenuItem()
//#
//# 06.05.2014 OG
//# - add: PKT_Popup(), PKT_Popup_P()
//#
//# 04.04.2014 OG
//# - fix: define ESC umbenannt zu PKTESC da es einen Namenskonflikt mit enum
//# STR in messages.h gab
//#
//# 21.02.2014 OG
//# - chg: PKT_TitlePKTVersion()
//#
//# 17.02.2014 OG
//# - add: PKT_Message(), PKT_Message_P()
//#
//# 13.02.2014 OG
//# - add: PKT_print_PKT_center()
//#
//# 03.02.2014 OG
//# - add: PKT_ShowTitlePKTVersion()
//#
//# 13.06.2013 OG
//# - del: PC_Fast_Connect() - ersetzt durch Menu_PKTTools() in menu.c
//#
//# 19.05.2013 OG
//# - Ausgliederungen aus verschiedenen anderen Sourcen
//############################################################################
 
#ifndef _PKT_H
#define _PKT_H
 
#define PKTESC 27 // Parameter für PKT-Updatetool
#define PKTUPDATE 'u' // starte Update
#define PKTVERSION 'v' // sende PKT EEpromversion
#define PKTSENDCONF 'e' // sende PKT Konfigdaten
 
#define ASK_YES_NO 1
#define ASK_NO_YES 2
#define ASK_CANCEL_OK 3
#define ASK_END_OK 4
#define ASK_END_START 5
 
 
extern volatile uint8_t Gauge_active;
 
 
void PKT_Title( const char *text, uint8_t lShowLipo, uint8_t clearscreen );
void PKT_Title_P( const char *text, uint8_t lShowLipo, uint8_t clearscreen );
void PKT_TitlePKT( void );
void PKT_TitlePKTlipo( uint8_t lShowLipo );
void PKT_TitleFromMenuItem( uint8_t lShowLipo );
 
void PKT_KeylineUpDown( uint8_t xUp, uint8_t xDown, uint8_t xoffs, uint8_t yoffs);
 
void PKT_Progress_Init( uint8_t max, int8_t yoffs, uint8_t width, uint8_t height);
uint8_t PKT_Progress_Next( void );
 
void PKT_Gauge_Begin( uint8_t py);
void PKT_Gauge_End( void );
void PKT_Gauge_Next( void );
 
void PKT_Message( const char *text, uint8_t error, uint16_t timeout, uint8_t beep, uint8_t clearscreen );
void PKT_Message_P( const char *text, uint8_t error, uint16_t timeout, uint8_t beep, uint8_t clearscreen );
 
void PKT_Message_Datenverlust( uint16_t timeout, uint8_t beep );
 
void PKT_Popup( uint16_t timeout, const char *text1, const char *text2, const char *text3, const char *text4 );
void PKT_Popup_P( uint16_t timeout, const char *text1, const char *text2, const char *text3, const char *text4 );
 
uint8_t PKT_Ask( uint8_t asktype, const char *text1, const char *text2, const char *headline, const char *title );
uint8_t PKT_Ask_P( uint8_t asktype, const char *text1, const char *text2, const char *headline, const char *title );
uint8_t PKT_AskX( uint8_t asktype, const char *text1, const char *text2, uint8_t text_progmem, const char *headline, uint8_t headline_progmem, const char *title, uint8_t title_progmem );
 
uint8_t PKT_CtrlHook(void);
uint8_t PKT_CheckUpdate(void); // prüft im Hauptmenü ob das Updatetool ein Update machen will
 
void PKT_Reset_EEprom( void );
void PKT_Update(void);
void PKT_SwitchOff(void);
void PKT_Info(void);
void PKT_Ask_Restart( const char *title );
 
#endif // end: #ifndef _PKT_H
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/setup/setup.c
0,0 → 1,2649
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY setup.c
//#
//#
//# 03.08.2015 CB
//# - add: FollowMe Setup um Distance und Azimuth erweitert
//#
//# 27.06.2014 OG
//# - chg: Setup_MAIN() - Reihenfolge von GPS-Maus/FollowMe/Tracking geaendert
//#
//# 25.06.2014 OG
//# - chg: Text von GPS_SHOWDEV
//# - chg: Setup_FollowMe() - deaktiviert/auskommentiert: FME_REFRESH
//# - chg: Setup_GPSMouse() - deaktiviert/auskommentiert: GPS_TYPE, GPS_ACTIVE
//#
//# 24.06.2014 OG
//# - chg: Setup_GPSMouse() angepasst auf geaendertes GPSMouse_ShowData()
//#
//# 22.06.2014 OG
//# - del: verschiedene weitere Modul-Variablen entfernt weil nicht benoetigt
//# - del: Variable CheckGPS
//# - del: BT_ShowGPSData() - ist jetzt als GPSMouse_ShowData() in gps/gpsmouse.c
//# - chg: BT_ShowGPSData() - Parameter und Rueckgabe
//# - del: BT_ShowGPSData_OLD
//#
//# 21.06.2014 CB
//# - chg: BT_SearchDevices - Timeoutanzeige bei Devicesuche
//#
//# 16.06.2014 OG
//# - chg: BT_ShowGPSData() - neues Layout und Anzeige fuer "XCnt" (=RX-Count)
//# hinzugefuegt; XCnt zeigt die Anzahl empfangener GPS-Datenpakete an
//# und ist ein Indikator wie schnell die BT-GPS Maus Daten sendet
//#
//# 13.06.2014 OG
//# - chg: Setup_PKTGeneric() - neue Einstellung "PKT aus nach"
//# - del: ChangeWi_SV2()
//#
//# 12.06.2014 OG
//# - del: Reset_EEprom() - ist jetzt als PKT_Reset_EEprom() in pkt.c
//#
//# 11.06.2014 OG
//# - fix: Edit_generic() funktioniert jetzt auch, wenn kein vorgelagertes
//# Menue vorhanden ist (ggf. muss das Label angepasst werden)
//#
//# 10.06.2014 OG
//# - chg: verschiedene Funktionen umgestellt auf Wi232_Initalize()
//#
//# 08.06.2014 OG
//# - add: Setup_MKConnection() - hier ist auch das setzen der Baudrate Wi232/BT
//# hin verschoben worden (war vorher im Wi.232 Bereicch)
//#
//# 06.06.2014 OG
//# - chg: Setup_WI232_MenuCreate()... Eintraege geloescht...
//#
//# 04.06.2014 OG
//# - chg: Setup_PKTGeneric() eine Menue-Trennlinie hinter Sommerzeit eingefuegt
//#
//# 01.06.2014 OG
//# - chg: Edit_LED_Form() Parameter 'Text' entfernt und auf strGetOSDOLD()
//# umgestellt
//# - add: include "../osd/osdold_messages.h"
//#
//# 31.05.2014 OG
//# - chg: Edit_String() - Parameter 'Text' entfernt; angepasst auf neue
//# Titelzeile; PKT_CtrlHook integriert; PKT Lipo-Anzeige;
//# auf 'redraw' umgestellt
//#
//# 30.05.2014 OG
//# - chg: Edit_LipoOffset() - umgeschrieben auf neues Layout, Code optimiert,
//# Increment jetzt +/-50 (statt vorher 20), Offset bis 15000 (statt 10000)
//# - chg: Edit_LipoOffset() - keine Parameter mehr, keine Rueckgabe
//#
//# 29.05.2014 OG
//# - chg: Setup_OSD() umgestellt auf Menuetexte statt strGet() mit Textaenderung
//#
//# 28.05.2014 OG
//# - chg: Setup's auf das neue Edit_generic() umgestellt
//# - chg: Edit_generic() - geaenderte Aufrufparameter
//# (Text enfernt da vom Menue geerbt; optionale Hilfstexte moeglich)
//#
//# 27.05.2014 OG
//# - del: Edit_generic_int(), Edit_printout_int() - nicht mehr benoetigt da
//# anhaengende Werte umgemappt auf Edit_generic()
//#
//# 26.05.2014 OG
//# - chg: Menuetext TIME_ZONE ergaenzt um "UTC"
//# - chg: Setup_MAIN() - neue Anordnung der Menueeintraege mit Trennlinien
//# - chg: Setup_OSDScreens() - OSDSCREEN_WAYPOINTS hinzugefuegt
//# - chg: Text "LCD aus nach..." nach "LCD aus nach"
//# - chg: Text "PKT allgemein" geaendert auf "PKT Allgemein"
//# - del: PKT_LCDINVERS inkl. Sprachen
//# - chg: Setup_PKTGeneric() - PKT_LCDINVERS (Config.LCD_DisplayMode) entfernt,
//# nicht mehr unterstuetzt
//# - chg: Edit_printout() - Hilfstexte CHANGENORMREV1 und 2 fuer NormRev entfernt
//#
//# 23.05.2014 OG
//# - add: Edit_generic() - Anzeige Titel mit PKT_TitleFromMenuItem()
//# - fix: Setup_PKTGeneric() - PKT_LCDINVERS (Config.LCD_DisplayMode)
//# Edit-Range umgestellt von 0,4 auf 0,1
//#
//# 11.05.2014 OG
//# - chg: die Setup-Menues umgestellt auf MenuCtrl_SetTitleFromParentItem()
//# -> die Menues 'erben' damit ihren Titel vom aufrufenden Menuepunkt
//# - chg: ein paar Menuetexte fuer Setup_MAIN()
//#
//# 18.04.2014 OG
//# - chg: Setup_PKTGeneric() - PKT_BRIGHTNESS rausgenommen da es aktuell auch
//# nicht mehr mit PKT 3.9m Hardware geht (spart ca. 650 Bytes)
//# - chg: Text von "Tracking Servos" gekuerzt auf "Tracking"
//#
//# 09.04.2014 OG
//# - chg: Edit_printout() Text von WlanMode 'Nein' auf 'Aus' geaendert
//#
//# 04.04.2014 OG
//# - chg: Edit_String() auf ShowTitle_P() umgestellt
//# - del: Edit_ShowTitle_P()
//# - chg: in versch. Funktionen Titel-Strings fuer Edit_String() gekuerzt
//# - chg: Edit_String() auf Edit_ShowTitle_P() umgestellt
//#
//# 02.04.2014 OG
//# - add: Edit_ShowTitle_P()
//# - add: Edit_printout(): WlanMode (Aus, AP-Mode, AdHoc)
//# - chg: Edit_printout(): Code-Optimierung
//#
//# 01.04.2014 OG
//# - add: Unterstuetzung fuer BLE (Bluetooth 4 Low Energy Zusatzmodul an SV2)
//# - chg: PCB_WiFlyPatch umbenannt zu PCB_SV2RxTxPatch
//#
//# 30.03.2014 OG
//# - chg: Sprache Hollaendisch vollstaendig entfernt
//# - chg: MenuCtrl_PushML_P() umgestellt auf MenuCtrl_PushML2_P()
//#
//# 27.03.2014 OG
//# - chg: Setup_PKTGeneric(), Edit_printout() Sprache "Niederländisch" nicht mehr waehlbar
//#
//# 04.02.2014 OG
//# - chg: kleine Layoutaenderung von 'PKT_Akku' in Edit_printout()
//# - add: PKT_CtrlHook() in Edit_generic(), Edit_generic_int(), Edit_LipoOffset() eingebaut
//# - add: kleiner Hilfetext in Edit_printout() bei Aenderung von Einstellung
//# "LCD Normal/Invers" bzgl. PKT neu starten nach Aenderung
//# - chg: Anzeige von Edit_LipoOffset() geaendert und fix vom springen der
//# Eingabe wenn Wert geaendert wird
//#
//# 03.02.2014 OG
//# - add: SHOWCELLU in Setup_OSD() ("zeige Zellensp.")
//#
//# 30.01.2014 OG
//# - add: Unterstuetzung fuer USE_BLUETOOTH
//#
//# 29.07.2013 Cebra
//# - chg: Fehler in Setup_WI232_MenuCreate, MenuCtrl_Push_P( WI_INSTALLED.. war auskommentiert, dadurch Fehler im Menu bei nicht
//# aktivem Wi232
//#
//# 18.07.2013 Cebra
//# - chg: Edit_PKT_Accu entfernt, Edit_generic erweitert
//#
//# 15.07.2013 Cebra
//# - add: Edit_Printout um Wlan Security erweitert
//#
//# 07.07.2013 OG
//# - add: Setup_OSDScreens(), Mark_OSDScreen(), Edit_OSDScreen()
//#
//# 04.07.2013 Cebra
//# - chg: Setupmenü um Wlan erweitert
//#
//# 02.07.2013 Cebra
//# - chg: Edit_String, geändert für die Nutzung von SSID und Wlan Passwort
//#
//# 30.06.2013 OG
//# - del: Setup_OSD(): OSDS_HOMEVIEW
//#
//# 26.06.2013 OG
//# - del: USE_PKT_STARTINFO
//#
//# 24.06.2013 OG
//# - chg: vor dem editieren des Bluetooth Namens bt_fixname() eingefuegt
//#
//# 24.06.2013 OG
//# - fix: Edit_String(): Fehlermeldung bei EDIT_BT_NAME wenn erstes Zeichen = Space
//# - chg: Edit_String(): Code-Layout und diverses
//# - chg: Setup_BTM222(): Bearbeitung von BT_NAME geaendert
//# - chg: Setup_BTM222(): Menuetexte geaendert
//# - chg: Setup_MAIN(): Text im Setup-Hauptmenue von "BTM-222" auf "Bluetooth" geaendert
//#
//# 21.06.2013 OG
//# - fix: Menuetext GPSMouse "Zeige Geräteliste" (Anzeige "ä" korrigiert)
//#
//# 15.06.2013 OG
//# - add: "zeige MK-Setting" in Setup_OSD() hinzugefuegt
//#
//# 15.06.2013 OG
//# - chg: Umstrukturierungen am OSD-Setup
//# - chg: OSD Empfangsausfall von Setup_PKTGeneric() nach Setup_OSD() verschoben
//#
//# 13.06.2013 OG
//# - del: Setup_Time() - jetzt in Setup_PKTGeneric()
//# - del: Setup_PKTAccu() - jetzt in Setup_PKTGeneric()
//# - del: SETUP_PKTDEBUG in Setup_MAIN() entfernt (auskommentiert, wenn notwendig ggf. mit einem Debug define regeln)
//# - chg: diverse Aenderungen in Menutexten
//# - fix: keine LCD-Helligkeitseinstellung bei HW 3.9x mehr durch Abfrage von PCB_Version
//#
//# 31.05.2013 cebra
//# - chg: Umlaute, soweit gefunden, korrigiert
//#
//# 30.05.2013 cebra
//# - chg: doppelte Texte auf #define umgestellt
//#
//# 24.05.2013 OG
//# - chg: etliche Aenderungen rund um Bluetooth/BT-GPS Maus fuer bessere
//# Usebility, Code-Einsparung und Code-Lesbarkeit
//# - add: Wait4KeyOK()
//# - chg: Aufrufe von MenuCtrl_Push() umgestellt auf MenuCtrl_PushML_P()
//#
//# 22.05.2013 OG
//# - chg: umgestellt auf menuctrl: BT_SelectDevice()
//#
//# 22.05.2013 OG
//# - chg: umgestellt auf menuctrl: Setup_Time(), Setup_FollowMe(), Setup_OSD()
//# - chg: weitere Speicheroptimierungen fuer USE_*
//# - chg: Menu_Setup() umbenannt zu Setup_MAIN()
//#
//# 20.05.2013 OG
//# - chg: umgestellt auf menuctrl: Menu_Setup(), Setup_PKTGeneric(), Setup_WI232()
//# Setup_BTM222(), Setup_PKTAccu(), Setup_GPSMouse()
//# - add: GPSMouse_ShowData()
//#
//# 19.05.2013 OG
//# - chg: Aufruf von Update_PKT() umgestellt auf PKT_Update()
//#
//# 17.05.2013 OG
//# - chg: umgestellt auf utils/menuold.h
//#
//# 16.05.2013 Cebra
//# - chg: Fehler bei On/Off Settings
//#
//# 05.05.2013 Cebra
//# - add: PKT Zeitsetup
//#
//# 19.04.2013 Cebra
//# - chg: Fehlerbehandlung im GPS Menü für den Fall das kein BTM22 eingebaut oder GPS-Device konfiguriert
//#
//# 16.04.2013 Cebra
//# - chg: PROGMEM angepasst auf neue avr-libc und GCC, prog_char depreciated
//#
//# 12.04.2013 Cebra
//# - chg: edit_generic um Sprungfaktor erweitert, erm�glicht bei hohen Werten einen schnelleren Wertewechsel
//#
//# 03.04.2013 Cebra
//# - chg: find/replace Fehler bei lcd_puts_at beseitigt, GPS und BT-Maus Bereich
//#
//# 02.04.2013 Cebra
//# - chg: Textfehler bei der Einstellung "Verbindung zum MK" beseitigt
//#
//# 04.03.2013 Cebra
//# - del: OSD-Sreenmode ,is no longer necessary, last OSD-Screen is saved at shutdown
//#
//# 27.03.2013 Cebra
//# - chg: Fehler bei der Menüsteuerung behoben
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <string.h>
#include <util/delay.h>
#include "../main.h"
#include "../setup/setup.h"
#include "../lcd/lcd.h"
#include "../timer/timer.h"
#include "../wi232/Wi232.h"
#include "../bluetooth/bluetooth.h"
#include "../connect.h"
#include "../lipo/lipo.h"
#include "../messages.h"
#include "../eeprom/eeprom.h"
#include "../tracking/tracking.h"
#include "../uart/uart1.h"
#include "../sound/pwmsine8bit.h"
#include "../tracking/servo_setup.h"
#include "../bluetooth/error.h"
#include "../stick/stick_setup.h"
#include "../utils/menuctrl.h"
#include "../utils/xutils.h"
#include "../pkt/pkt.h"
#include "../osd/osd.h"
#include "../wifly/wifly_setup.h"
#include "../gps/gpsmouse.h"
#include "../utils/scrollbox.h"
#include "../osd/osdold_messages.h"
 
 
uint8_t edit = 0;
uint16_t Pre;
char EditString[21];
uint8_t length_tmp;
uint8_t Old_Baudrate; //Merkzelle für alte Baudrate
 
 
//############################################################################
//############################################################################
 
//-----------------------------
// Setup_Main()
//-----------------------------
#define SETUP_MKCONNECTION 1
#define SETUP_PKTCONFIG 2
#define SETUP_WI232 3
#define SETUP_BTM222 4
#define SETUP_SERVOCONFIG 5
#define SETUP_OSDVIEW 6
#define SETUP_TIME 7
#define SETUP_GPSMAUS 8
#define SETUP_FOLLOWME 9
#define SETUP_JOYSTICK 10
#define SETUP_PKTAKKU 11
#define SETUP_PKTUPDATE 12
#define SETUP_PKTDEBUG 13
#define SETUP_EEPROMRESET 14
#define SETUP_WIFLY 15
#define SETUP_OSDSCREENS 16
#define SETUP_BLE 17
 
 
static const char SETUP_MKCONNECTION_de[] PROGMEM = "Verbindung MK";
static const char SETUP_MKCONNECTION_en[] PROGMEM = "connection MK";
 
static const char SETUP_PKTCONFIG_de[] PROGMEM = "PKT Allgemein";
static const char SETUP_PKTCONFIG_en[] PROGMEM = "PKT general";
 
static const char SETUP_WI232_de[] PROGMEM = "Wi.232";
#define SETUP_WI232_en SETUP_WI232_de
 
static const char SETUP_BTM222_de[] PROGMEM = "Bluetooth";
#define SETUP_BTM222_en SETUP_BTM222_de
 
static const char SETUP_BLE_de[] PROGMEM = "Bluetooth BLE";
#define SETUP_BLE_en SETUP_BLE_de
 
static const char SETUP_WIFLY_de[] PROGMEM = "WLAN WiFly";
#define SETUP_WIFLY_en SETUP_WIFLY_de
 
static const char SETUP_SERVOCONFIG_de[] PROGMEM = "Tracking";
#define SETUP_SERVOCONFIG_en SETUP_SERVOCONFIG_de
 
static const char SETUP_OSDVIEW_de[] PROGMEM = "OSD Anzeige";
static const char SETUP_OSDVIEW_en[] PROGMEM = "OSD display";
 
static const char SETUP_OSDSCREENS_de[] PROGMEM = "OSD Screens";
static const char SETUP_OSDSCREENS_en[] PROGMEM = "OSD screens";
 
static const char SETUP_GPSMAUS_de[] PROGMEM = "GPS Maus";
static const char SETUP_GPSMAUS_en[] PROGMEM = "GPS mouse";
 
static const char SETUP_FOLLOWME_de[] PROGMEM = "Follow Me";
#define SETUP_FOLLOWME_en SETUP_FOLLOWME_de
 
static const char SETUP_JOYSTICK_de[] PROGMEM = "Joystick";
#define SETUP_JOYSTICK_en SETUP_JOYSTICK_de
 
static const char SETUP_PKTUPDATE_de[] PROGMEM = "PKT Update";
#define SETUP_PKTUPDATE_en SETUP_PKTUPDATE_de
 
static const char SETUP_PKTDEBUG_de[] PROGMEM = "Debug PKT";
#define SETUP_PKTDEBUG_en SETUP_PKTDEBUG_de
 
static const char SETUP_EEPROMRESET_de[] PROGMEM = "PKT Reset";
#define SETUP_EEPROMRESET_en SETUP_EEPROMRESET_de
 
//############################################################################
 
//-----------------------------
// Setup_PKTGeneric() ("PKT allgemein")
//-----------------------------
#define PKT_LANGUAGE 3
#define PKT_LIGHTOFF 4
#define PKT_BRIGHTNESS 5
#define PKT_CONTRAST 6
#define PKT_SOUNDMODUL 9
#define PKT_BEEPER 10
#define PKT_VOLUME 11
#define PKT_ACCUTYPE 12
#define PKT_ACCUMEASURE 13
#define TIME_ZONE 14
#define TIME_SUMMER 15
#define PKT_PKTOFF 16
 
 
static const char LANGUAGE_de[] PROGMEM = "Sprache";
static const char LANGUAGE_en[] PROGMEM = "language";
 
static const char TIME_ZONE_de[] PROGMEM = "Zeitzone UTC";
static const char TIME_ZONE_en[] PROGMEM = "time zone UTC";
 
static const char TIME_SUMMER_de[] PROGMEM = "Sommerzeit";
static const char TIME_SUMMER_en[] PROGMEM = "summer time";
 
static const char PKT_PKTOFF_de[] PROGMEM = "PKT aus nach";
static const char PKT_PKTOFF_en[] PROGMEM = "PKT off after";
 
static const char LIGHTOFF_de[] PROGMEM = "LCD aus nach";
static const char LIGHTOFF_en[] PROGMEM = "LCD off after";
 
//static const char BRIGHTNESS_de[] PROGMEM = "LCD Helligkeit";
//static const char BRIGHTNESS_en[] PROGMEM = "LCD brightness";
 
static const char CONTRAST_de[] PROGMEM = "LCD Kontrast";
static const char CONTRAST_en[] PROGMEM = "LCD contrast";
 
static const char BEEPER_de[] PROGMEM = "Hardware Beeper";
#define BEEPER_en BEEPER_de
 
#ifdef USE_SOUND
static const char SOUNDMODUL_de[] PROGMEM = "Soundmodul";
static const char SOUNDMODUL_en[] PROGMEM = "Soundmodule";
 
static const char VOLUME_de[] PROGMEM = "Lautstärke Sound";
static const char VOLUME_en[] PROGMEM = "Volume Sound";
#endif
 
static const char ACCUTYPE_de[] PROGMEM = "Akku Typ";
static const char ACCUTYPE_en[] PROGMEM = "Accu type";
 
static const char ACCUMEASURE_de[] PROGMEM = "Akku Messung";
static const char ACCUMEASURE_en[] PROGMEM = "Accu measure";
 
//############################################################################
 
//-----------------------------
// Setup_MKConnection()
//-----------------------------
 
#define MKCONN_CONNECTION 1
#define MKCONN_BAUDRATE 2
 
#define MKCONN_CONNECTION_de SETUP_MKCONNECTION_de
#define MKCONN_CONNECTION_en SETUP_MKCONNECTION_en
 
static const char MKCONN_BAUDRATE_de[] PROGMEM = "Baudrate Wi232/BT";
#define MKCONN_BAUDRATE_en MKCONN_BAUDRATE_de
 
 
//############################################################################
 
//-----------------------------
// Setup_WI232()
//-----------------------------
#define WI_INSTALLED 1
#define WI_TXRX 2
#define WI_GROUP 3
#define WI_MODE 4
#define WI_TIMEOUT 5
#define WI_MTU 6
#define WI_INIT 7
#define WI_PCCONFIG 8
 
static const char WI_INSTALLED_de[] PROGMEM = "Modul eingebaut";
static const char WI_INSTALLED_en[] PROGMEM = "module built in";
 
static const char WI_TXRX_de[] PROGMEM = "TX/RX Kanal";
static const char WI_TXRX_en[] PROGMEM = "TX/RX Channel";
 
static const char WI_GROUP_de[] PROGMEM = "NetW. Gruppe";
static const char WI_GROUP_en[] PROGMEM = "NetW. Group";
 
static const char WI_MODE_de[] PROGMEM = "NetW. Mode";
#define WI_MODE_en WI_MODE_de
 
static const char WI_TIMEOUT_de[] PROGMEM = "TX Timeout";
#define WI_TIMEOUT_en WI_TIMEOUT_de
 
static const char WI_MTU_de[] PROGMEM = "TX MTU";
#define WI_MTU_en WI_MTU_de
 
static const char WI_INIT_de[] PROGMEM = "Initialisieren";
static const char WI_INIT_en[] PROGMEM = "initialize";
 
static const char WI_PCCONFIG_de[] PROGMEM = "Konfig. mit PC";
static const char WI_PCCONFIG_en[] PROGMEM = "config. with PC";
 
 
//############################################################################
 
//-----------------------------
// Setup_BTM222() (Bluetooth)
//-----------------------------
#define BT_INSTALLED 1
#define BT_NAME 2
#define BT_PIN 3
#define BT_INIT 4
#define BT_MAC 5
#define BT_REID 6
#define BT_PCCONFIG 7
#define BT_SHOWCONFIG 8
 
#define BT_INSTALLED_de WI_INSTALLED_de
#define BT_INSTALLED_en WI_INSTALLED_en
 
static const char BT_NAME_de[] PROGMEM = "BT Name";
static const char BT_NAME_en[] PROGMEM = "BT name";
 
static const char BT_PIN_de[] PROGMEM = "BT Pin";
static const char BT_PIN_en[] PROGMEM = "BT pin";
 
#define BT_INIT_de WI_INIT_de
#define BT_INIT_en WI_INIT_en
 
static const char BT_MAC_de[] PROGMEM = "zeige BT MAC";
static const char BT_MAC_en[] PROGMEM = "show BT MAC";
 
static const char BT_REID_de[] PROGMEM = "RE-ID Notiz";
#define BT_REID_en BT_REID_de
 
#define BT_PCCONFIG_de WI_PCCONFIG_de
#define BT_PCCONFIG_en WI_PCCONFIG_en
 
static const char BT_SHOWCONFIG_de[] PROGMEM = "zeige BT Konfig";
static const char BT_SHOWCONFIG_en[] PROGMEM = "show BT config";
 
//############################################################################
 
//-----------------------------
// Setup_BLE() (Bluetooth 4 Low Energy)
//-----------------------------
#define BLE_INSTALLED 1
 
// Text ist in messages.c: MODULE_EXIST
 
 
//############################################################################
 
//-----------------------------
// Setup_GPSMouse()
//-----------------------------
#define GPS_DEVICES 1
#define GPS_SEARCH 2
#define GPS_TYPE 3
#define GPS_ACTIVE 4
#define GPS_SHOWDEV 5
#define GPS_DATA 6
 
 
static const char GPS_SEARCH_de[] PROGMEM = "suche GPS-Maus";
static const char GPS_SEARCH_en[] PROGMEM = "search GPS-mouse";
 
static const char GPS_DEVICES_de[] PROGMEM = "Geräteliste";
static const char GPS_DEVICES_en[] PROGMEM = "devicelist";
 
static const char GPS_SHOWDEV_de[] PROGMEM = "aktuelle Maus";
static const char GPS_SHOWDEV_en[] PROGMEM = "act. GPS-mouse";
 
static const char GPS_DATA_de[] PROGMEM = "GPS-Maus Daten";
static const char GPS_DATA_en[] PROGMEM = "GPS-mouse data";
 
static const char GPS_TYPE_de[] PROGMEM = "GPS-Maus Typ"; // aktuell nicht verwendet
static const char GPS_TYPE_en[] PROGMEM = "GPS-mouse typ";
 
static const char GPS_ACTIVE_de[] PROGMEM = "GPS-Maus aktiv"; // aktuell nicht verwendet
static const char GPS_ACTIVE_en[] PROGMEM = "GPS-mouse activ";
 
 
//############################################################################
 
//-----------------------------
// Setup_FollowMe()
//-----------------------------
#define FME_DISTANCE 1
#define FME_SPEED 2
#define FME_RADIUS 3
#define FME_AZIMUTH 4
 
static const char FME_DISTANCE_de[] PROGMEM = "FollowMe Abstand";
static const char FME_DISTANCE_en[] PROGMEM = "followMe distance";
 
static const char FME_AZIMUTH_de[] PROGMEM = "FollowMe Winkel";
static const char FME_AZIMUTH_en[] PROGMEM = "followMe angle";
 
static const char FME_SPEED_de[] PROGMEM = "FollowMe Speed";
#define FME_SPEED_en FME_SPEED_de
 
static const char FME_RADIUS_de[] PROGMEM = "Toleranz Radius";
static const char FME_RADIUS_en[] PROGMEM = "tolerance radius";
 
 
 
 
//############################################################################
 
//-----------------------------
// Setup_OSD()
//-----------------------------
#define OSDS_SHOWCELLU 1
#define OSDS_LOWBAT 2
#define OSDS_RCERROR 3
#define OSDS_MKSETTING 4
#define OSDS_MAH 5
#define OSDS_DATASV2 6
#define OSDS_OUTFORMAT 7
#define OSDS_OUTPOLARITY 8
#define OSDS_FALLSPEED 9
#define OSDS_VARIOBEEP 10
#define OSDS_VOLTBAR 11
 
 
static const char OSDS_LOWBAT_de[] PROGMEM = "Warn Unterspannung";
static const char OSDS_LOWBAT_en[] PROGMEM = "Warn LowBat";
 
static const char OSDS_MAH_de[] PROGMEM = "Warn mAh";
static const char OSDS_MAH_en[] PROGMEM = "Warn mAh";
 
static const char OSDS_RCERROR_de[] PROGMEM = "Warn RC-Fehler";
static const char OSDS_RCERROR_en[] PROGMEM = "Warn RC-Error";
 
static const char OSDS_SHOWCELLU_de[] PROGMEM = "zeige Zellspannung";
static const char OSDS_SHOWCELLU_en[] PROGMEM = "show cell voltage";
 
static const char OSDS_MKSETTING_de[] PROGMEM = "zeige MK Setting";
static const char OSDS_MKSETTING_en[] PROGMEM = "show mk setting";
 
static const char OSDS_DATASV2_de[] PROGMEM = "Navi Daten an SV2";
static const char OSDS_DATASV2_en[] PROGMEM = "Navi data to SV2";
 
 
#ifdef USE_OSD_SCREEN_OLD
static const char OSDS_OUTFORMAT_de[] PROGMEM = "OUT1/2 Format";
static const char OSDS_OUTFORMAT_en[] PROGMEM = "OUT1/2 format";
 
static const char OSDS_FALLSPEED_de[] PROGMEM = "Max. Sinkrate m/s";
static const char OSDS_FALLSPEED_en[] PROGMEM = "max fallspeed m/s";
 
static const char OSDS_VARIOBEEP_de[] PROGMEM = "Variometer Beep";
static const char OSDS_VARIOBEEP_en[] PROGMEM = "Variometer beep";
 
static const char OSDS_OUTPOLARITY_de[] PROGMEM = "OUT1/2 Polarität";
static const char OSDS_OUTPOLARITY_en[] PROGMEM = "OUT1/2 polarity";
 
static const char OSDS_VOLTBAR_de[] PROGMEM = "Volt Balken";
static const char OSDS_VOLTBAR_en[] PROGMEM = "volt bargraph";
#endif
 
 
 
//############################################################################
 
 
//############################################################################
//# Allgemeines
//############################################################################
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Wait4KeyOK( void )
{
set_beep( 60, 0xffff, BeepNormal);
lcd_printp_at(19, 7, strGet(OK) , MNORMAL);
while( !get_key_press(1 << KEY_ENTER) ) PKT_CtrlHook(); // PKT-Update usw...
clear_key_all();
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Wait4KeyENDE( uint8_t beep )
{
if( beep ) set_beep( 60, 0xffff, BeepNormal);
lcd_printp_at(12, 7, strGet(ENDE) , MNORMAL);
while( !get_key_press(1 << KEY_ESC) )
{
show_Lipo();
PKT_CtrlHook(); // PKT-Update usw...
}
clear_key_all();
}
 
 
//############################################################################
//# BT-Funktionen (GPS-Maus)
//############################################################################
 
#ifdef USE_BLUETOOTH
 
//--------------------------------------------------------------
// BT_CheckBTM222()
//
// prueft ob das Bluetooth Modul im PKT installiert ist
//--------------------------------------------------------------
uint8_t BT_CheckBTM222( void )
{
if( !Config.UseBT )
{
// PKT_Message_P( text, error, timeout, beep, clearscreen)
PKT_Message_P( strGet(STR_NOBTM222), true, 1000, true, true); // 1000 = max. 10 Sekunden anzeigen; "kein BTM222 vorh."
return false; // -> kein BTM222 eingebaut
}
 
return true;
}
 
 
 
//--------------------------------------------------------------
// BT_SelectDevice()
//
// Auswahl eines BT-Device aus einer Liste von BT-Devices
//--------------------------------------------------------------
void BT_SelectDevice( void )
{
uint8_t itemid;
uint8_t event;
uint8_t i;
 
//-------------------------------
// BTM222 Modul vorhanden?
//-------------------------------
if( !BT_CheckBTM222() ) return;
 
 
//-------------------------------
// BT Device-Suche durchgefuert?
//-------------------------------
if( bt_devicecount == 0 )
{
// PKT_Message_P( text, error, timeout, beep, clearscreen)
PKT_Message_P( PSTR("Suche durchführen!"), true, 1000, true, true); // 1000 = max. 10 Sekunden anzeigen; "kein BTM222 vorh."
return;
}
 
 
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitle_P( strGet(STR_BT_DEVICES) ); // "BT Geräte"
 
//---------------
// Menuitems
//---------------
for( i = 0; i < bt_devicecount; i++ )
{
MenuCtrl_Push( i, MENU_ITEM, NOFUNC, device_list[i].DevName );
 
if( strncmp(device_list[i].mac,Config.gps_UsedMac,14) == 0 )
MenuCtrl_ItemMark( i, true ); // aktuelles BT-Device markieren
}
 
//---------------
// Control
//---------------
event = MenuCtrl_Control( MENUCTRL_EVENT );
 
if( event == MENUEVENT_ITEM )
{
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
strncpy( Config.gps_UsedMac , device_list[itemid].mac , 14);
strncpy( Config.gps_UsedDevName, device_list[itemid].DevName, 20);
}
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
 
//--------------------------------------------------------------
// BT_SearchDevices()
//
// sucht BT-Devices
//--------------------------------------------------------------
void BT_SearchDevices( void )
{
uint8_t wahl;
 
char *title;
 
//-------------------
// 1. Frage: suchen?
//-------------------
if( Config.gps_UsedDevName[0] != 0 ) // ist eine BT GPS-Maus bereits vorhanden?
title = Config.gps_UsedDevName; // dann zeige im Titel den Namen der GPS-Maus an
else
title = "BT Devices";
 
set_beep( 50, 0xffff, BeepNormal);
 
//wahl = PKT_AskX( asktype, text1, text2, text_progmem, headline, headline_progmem, title, title_progmem)
wahl = PKT_AskX( ASK_END_START, strGet(STR_SEARCH_BT_ASK), strGet(STR_BT_SEARCHTIME), true, MenuCtrl_GetItemText(), true, title, false); // "BT Geräte suchen?"
 
 
//-------------------
// 2. BT suchen
//-------------------
if( wahl )
{
if( BT_CheckBTM222() )
{
//PKT_Title_P( text, lShowLipo, clearscreen )
PKT_Title_P( PSTR("BT Suche"), true, true );
 
lcdx_printp_center( 2, strGet(STR_SEARCH_BT), MNORMAL, 0,1); // "suche BT Geräte"
 
//PKT_Gauge_Begin( 0 ); // Gauge: 0 = Default fuer y verwenden
 
set_BTOn();
bt_downlink_init();
 
lcd_printp_at( 11, 7, strGet(KEYCANCEL), MNORMAL); // Keyline: "Abbr." bzw "Cancel"
bt_searchDevice();
 
set_BTOff();
 
//PKT_Gauge_End(); // Gauge: Ende
 
if( bt_devicecount==0 )
{
//PKT_Message_P( text, error, timeout, beep, clearscreen)
PKT_Message_P( strGet(STR_NO_BT_FOUND), true, 2000, true, true);
}
else
{
set_beep( 50, 0xffff, BeepNormal);
BT_SelectDevice();
}
}
}
}
 
 
#endif // end: #ifdef USE_BLUETOOTH
 
 
 
 
//############################################################################
//# Edit-Funktionen
//############################################################################
 
 
//--------------------------------------------------------------
// Ausgabe von Werten fuer Edit_generic()
//--------------------------------------------------------------
void Edit_generic_printout( int16_t Value, int16_t min, int16_t max, uint8_t what, int8_t yoffs)
{
const char *pStr = 0; // PGM
const char *pstr = 0; // RAM
//uint8_t x = 0;
//uint8_t y = 3;
 
 
switch( what )
{
case Show_uint3: pstr = buffered_sprintf_P( PSTR("%3d"), Value );
break;
 
 
case Show_uint5: pstr = buffered_sprintf_P( PSTR("%5d"), Value );
break;
 
 
case Show_uint10th: pstr = buffered_sprintf_P( PSTR("%2.1d"), Value );
break;
 
 
case MK_Connection: switch( Value )
{
case 0: pStr = PSTR("Wi.232"); break;
case 1: pStr = strGet(KABEL); break;
}
 
if( (Value == 0) && (Config.UseWi == false) )
{
lcd_rect_round( 0, 37, 127, 21-6, 1, R2); // Rahmen
lcdx_printp_center( 6, strGet(STR_WI232_ACTIVATE), MNORMAL, 0,-7); // "aktiviere Wi.232!"
}
else
{
lcd_frect( 0, 37, 127, 21-6, 0); // Hilfebereich loeschen
}
break;
 
 
case GPSMOUSE: switch( Value )
{
case GPS_Bluetoothmouse1: pStr = PSTR("BT-Mouse"); break;
case GPS_Mikrokopter: pStr = PSTR("Mikrokopter"); break;
default: pStr = PSTR("unknown");
}
break;
 
 
case Wi_Netmode: switch( Value )
{
case false: pStr = strGet(SLAVE); break;
case true : pStr = strGet(NORMAL); break;
}
break;
 
 
 
case OnOff: switch( Value )
{
case 0: pStr = strGet(OFF); break;
case 1: pStr = strGet(ON); break;
}
break;
 
 
case YesNo: switch( Value )
{
case 0: pStr = strGet(NOO); break;
case 1: pStr = strGet(YES); break;
}
break;
 
 
case WlanMode: switch( Value )
{
case 0: pStr = strGet(OFF); break;
case 1: pStr = PSTR("AP-Mode"); break;
case 2: pStr = PSTR("AdHoc"); break;
}
break;
 
 
 
case NormRev: switch( Value ) // wird noch von stick/stick_setup.c verwendet
{
case 0 : pStr = strGet(NORMAL); break;
case 1 : pStr = strGet(REVERSE); break;
}
break;
 
 
case Kontrast: if( Value >= max )
{
Value = max;
set_beep( 200, 0x0080, BeepNormal);
}
 
if( Value == min )
{
Value = min;
set_beep( 200, 0x0080, BeepNormal);
}
 
lcd_set_contrast( Value );
 
pstr = buffered_sprintf_P( PSTR("%3d"), Value );
break;
 
 
case Baudrate: pstr = buffered_sprintf_P( PSTR("%ld"), Baud_to_uint32(Value) );
break;
 
 
case Language: switch( Value )
{
case 0: pStr = strGet(DEUTSCH); break;
case 1: pStr = strGet(ENGLISCH); break;
}
break;
 
 
case Sticktype: switch( Value )
{
case false: pStr = strGet(POTI); break;
case true : pStr = strGet(TASTER); break;
}
break;
 
 
/*
case WlanSecurity: // Anmerkung 02.04.2014 OG: wird aktuell nicht benoetigt weil anders geloest
switch (Value)
{
case 0x0 : lcd_printp_at(15, 2, PSTR("Adhoc"), 0);
break;
case 0x1 : lcd_printp_at(15, 2, PSTR("WPA "), 0);
break;
}
break;
*/
 
case PKT_Akku: switch( Value )
{
case true : pStr = PSTR("Lipo"); break;
case false: pStr = PSTR("LiIon"); break;
}
break;
} // end: switch( what )
 
 
 
//lcdx_printf_at_P( uint8_t x, uint8_t y, uint8_t mode, int8_t xoffs, int8_t yoffs, const char *format, ... )
 
if( pStr ) lcdx_printf_at_P( 0, 3, MNORMAL, 0,yoffs, PSTR("> %16S"), pStr ); // PGM
if( pstr ) lcdx_printf_at_P( 0, 3, MNORMAL, 0,yoffs, PSTR("> %16s"), pstr ); // RAM
}
 
 
 
 
//--------------------------------------------------------------
// int16_t Edit_generic( Value, min, max, what, Addfactor, strHelp1, strHelp2)
//
// generische Funktion zum aendern von Setup-Werten
//
// PARAMETER:
// Value: Ausgangswert der zu aendern ist
// min : minimaler Wert
// max : maximaler Wert
// what : Typ des Wertes, abhaengig davon wird der Wert dargestellt, ENUM dafuer in setup.h
// Addfactor : Sprungwert der beim erhöhen und erniedrigen addiert wird
// strHelp1 : Hilefetext 1 (PGM)
// strHelp2 : Hilefetext 2 (PGM)
//S
// RUECKGABE:
// int16_t Return : Ergebnis der Veraenderung des Wertes
//--------------------------------------------------------------
int16_t Edit_generic( int16_t Value, int16_t min, int16_t max, uint8_t what, uint8_t Addfactor, const char *strHelp1, const char *strHelp2 )
{
uint8_t redraw = true;
uint8_t noCancel = false;
int8_t yoffs = 0; // yoffs fuer das Edit-Label
int8_t yoffsV = 4; // yoffs fuer den Eingabebereich
const char *pStr;
 
Pre = Value;
 
do
{
//------------------------
// Screen neu zeichnen
//------------------------
if( redraw )
{
PKT_TitleFromMenuItem( true ); // Titel mit PKT-LiPo Anzeige und clearcsreen
 
 
//------------------------
// Platz reservieren fuer
// spezielle Typen
//------------------------
if( what == MK_Connection )
{
yoffs = -2; // yoffs fuer das Edit-Label
yoffsV = 0; // yoffs fuer den Eingabebereich
}
 
//------------------------
// 1 zeiliger Hilfstext
//------------------------
if( strHelp1 != NULL && strHelp2 == NULL )
{
lcd_rect_round( 0, 37, 127, 21-6, 1, R2); // Rahmen
lcdx_printp_center( 6, strHelp1, MNORMAL, 0,-7); // Hilfe-Text 1
yoffs = -2; // yoffs fuer das Edit-Label
yoffsV = 0; // yoffs fuer den Eingabebereich
}
 
//------------------------
// 2 zeiliger Hilfstext
//------------------------
if( strHelp2 != NULL )
{
lcd_rect_round( 0, 32, 127, 21, 1, R2); // Rahmen
lcdx_printp_center( 5, strHelp1, MNORMAL, 0,-5); // Hilfe-Text 1
lcdx_printp_center( 6, strHelp2, MNORMAL, 0,-5); // Hilfe-Text 2
yoffs = -4; // yoffs fuer das Edit-Label
yoffsV = -2; // yoffs fuer den Eingabebereich
}
 
//------------------------
// Label
//------------------------
pStr = PSTR("???");
if( MenuCtrl_GetMenuIndex() >= 0 ) pStr = MenuCtrl_GetItemText(); // das Label wird vom Menueeintrag uebernommen (Menuetext muss im PGM sein!)
else
{
if( what == Language ) // Ausnahme: wird ggf. beim Start vom PKT von HAL_HW3_9.c aufgerufen
{
pStr = strGetLanguage( LANGUAGE_de, LANGUAGE_en);
noCancel = true;
}
}
lcdx_printf_at_P( 0, 2, MNORMAL, 0,yoffs, PSTR("%S:"), pStr ); // Ausgabe des Labels
 
 
lcd_printp_at( 0, 7, strGet(KEYLINE5) , MNORMAL); // Keyline: <- -> Abbr. OK
if( noCancel ) lcd_printp_at(11, 7, PSTR(" "), MNORMAL); // Keyline: "Abbr." loeschen wenn noCancel
 
Edit_generic_printout( Value, min, max, what, yoffsV); // aktuellen Eingabewert anzeigen
redraw = false;
}
 
 
//------------------------
// PKT CtrlHook
//------------------------
if( PKT_CtrlHook() )
{
redraw = true;
}
 
 
//------------------------
// Key: PLUS
//------------------------
if( (get_key_press(1 << KEY_PLUS) || get_key_long_rpt_sp((1 << KEY_PLUS), 2)) )
{
if( Value <= (max-Addfactor) ) Value = Value + Addfactor;
else Value = min;
 
Edit_generic_printout( Value, min, max, what, yoffsV);
}
 
 
//------------------------
// Key: MINUS
//------------------------
if( (get_key_press(1 << KEY_MINUS) || get_key_long_rpt_sp((1 << KEY_MINUS), 2)) )
{
if( Value >= (min + Addfactor) ) Value = Value - Addfactor;
else Value = max;
 
Edit_generic_printout( Value, min, max, what, yoffsV);
}
 
 
//------------------------
// Key: ENTER
//------------------------
if( get_key_press(1 << KEY_ENTER) )
{
return Value;
}
 
 
//------------------------
// Key: ESC
//------------------------
if( !noCancel && get_key_press(1 << KEY_ESC) ) // Ende ohne speichern
{
break;
}
}
while( true );
 
get_key_press(KEY_ALL);
return Pre;
}
 
 
 
//--------------------------------------------------------------
// bei HW 3.9x geht das nicht mehr wegen dem Platinenlayout
// bei HW 3.9m geht es theoretisch noch - aber durch einen Bug scheinbar
// nicht mehr. Kann nur von jemanden mit HW 3.9m repariert werden.
// ALSO -> raus und Speicher sparen
//--------------------------------------------------------------
/*
uint8_t Edit_DisplayHelligkeit(uint8_t Value, uint8_t min, uint8_t max)
{
float ValCorr = 2.55; // (Value * ValCorr) maximal 255
Pre = Value;
OCR2A = Value * ValCorr;
 
lcd_cls();
// lcd_printp_at (0, 2, Text, 0);
lcdx_printf_at_P( 0, 2, MNORMAL, 0,0, PSTR("%S:"), MenuCtrl_GetItemText() ); // Menuetext muss im PGM sein! (aktuell keine Unterscheidung RAM/PGM)
write_ndigit_number_u (16, 2, Value, 3, 0,0);
lcd_printp_at (17, 2, PSTR("%"), 0);
// lcd_printp_at (0, 7, PSTR(KEY_LINE_2), 0);
lcd_printp_at(0, 7, strGet(KEYLINE2), 0);
 
do
{
write_ndigit_number_u (16, 2,Value, 3, 0,0);
lcd_frect ((8*0), (8*4), (Value * (16*8) / 100), 6, 1);
 
if ((get_key_press (1 << KEY_PLUS) || get_key_long_rpt_sp ((1 << KEY_PLUS), 3)) && (Value < max))
{
Value++;
 
if (Value >= max)
{
Value = max;
set_beep ( 200, 0x0080, BeepNormal);
}
else
OCR2A = Value * ValCorr;
 
}
 
if ((get_key_press (1 << KEY_MINUS) || get_key_long_rpt_sp ((1 << KEY_MINUS), 3)) && (Value > min))
{
lcd_frect (((Value - 1) * (16*8) / 100), (8*4), (16*8), 6, 0);
Value--;
 
if (Value == min)
{
Value = min;
set_beep ( 200, 0x0080, BeepNormal);
}
else
OCR2A = Value * ValCorr;
 
}
 
if (get_key_press (1 << KEY_ENTER))
{
OCR2A = Value * ValCorr;
Config.LCD_Helligkeit = Value;
// WriteParameter();
edit = 0;
return Value;
}
}
 
while (!get_key_press (1 << KEY_ESC));
{
get_key_press(KEY_ALL);
OCR2A = Pre * ValCorr;
Config.LCD_Helligkeit = Pre;
// WriteParameter();
return Pre;
}
}
*/
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t Edit_String( const char *data, const uint8_t length, uint8_t type)
{
uint8_t redraw = true;
uint8_t x = 1;
uint8_t I = 0;
uint8_t lOk = false;
uint8_t i;
 
 
for( i = 0; i < length; i++)
{
EditString[i] = data[i];
}
 
 
do
{
//-------------------------
// Screen zeichnen
//-------------------------
if( redraw )
{
PKT_TitleFromMenuItem( true ); // true = showlipo (mit clearscreen)
 
for( i = 0; i < length; i++)
{
lcd_putc ( (i*2)+1, 3, EditString[i], MNORMAL);
lcd_printp_at( (i*2)+2, 3, PSTR(" ") , MNORMAL);
}
 
lcd_rect( (x*6)-3, (8*3)-2, 10, 10, 1);
lcd_printp_at(13, 6, PSTR("C"), MNORMAL);
lcd_printp_at( 0, 7, PSTR(" \x17 \x16 \x19 OK"), MNORMAL); // Keyline
 
redraw = false;
}
 
 
//-------------------------
// PKT-LiPo anzeigen
//-------------------------
show_Lipo();
 
 
//-------------------------
// PKT Update-Anforderung?
//-------------------------
if( PKT_CtrlHook() )
{
redraw = true;
}
 
 
if( (type == EDIT_BT_NAME) || (type == EDIT_SSID) || (type == EDIT_WL_PASSWORD)) // Name
{
if ((get_key_press (1 << KEY_PLUS) || get_key_long_rpt_sp ((1 << KEY_PLUS), 2)) && EditString[I] < 'z')
{
EditString[I]++;
 
if (EditString[I] >= 0x00 && EditString[I] < ' ')
EditString[I] = ' ';
 
if (EditString[I] > ' ' && EditString[I] < '0')
EditString[I] = '0';
 
if (EditString[I] > '9' && EditString[I] < 'A')
EditString[I] = 'A';
 
if (EditString[I] > 'Z' && EditString[I] < 'a')
EditString[I] = 'a';
 
lcd_putc (x, 3, EditString[I], 0);
edit = 1;
}
 
if ((get_key_press (1 << KEY_MINUS) || get_key_long_rpt_sp ((1 << KEY_MINUS), 2)) && EditString[I] > ' ')
{
EditString[I]--;
 
if (EditString[I] < 'a' && EditString[I] > 'Z')
EditString[I] = 'Z';
 
if (EditString[I] < 'A' && EditString[I] > '9')
EditString[I] = '9';
 
if (EditString[I] < '0' && EditString[I] > ' ')
EditString[I] = ' ';
 
lcd_putc (x, 3, EditString[I], 0);
edit = 1;
}
}
else if( type == EDIT_BT_PIN ) // PIN
{
if ((get_key_press (1 << KEY_PLUS) || get_key_long_rpt_sp ((1 << KEY_PLUS), 1)) && (EditString[I] < '9'))
{
EditString[I]++;
 
if (EditString[I] >= 0x00 && EditString[I] < ' ')
EditString[I] = ' ';
 
if (EditString[I] > ' ' && EditString[I] < '0')
EditString[I] = '0';
 
lcd_putc (x, 3, EditString[I], 0);
edit = 1;
}
 
if ((get_key_press (1 << KEY_MINUS) || get_key_long_rpt_sp ((1 << KEY_MINUS), 1)) && (EditString[I] > '0'))
{
EditString[I]--;
 
if (EditString[I] < 'A' && EditString[I] > '9')
EditString[I] = '9';
 
lcd_putc (x, 3, EditString[I], 0);
edit = 1;
}
}
 
if( get_key_long (1 << KEY_ESC))
{
if( type == EDIT_BT_NAME|| type == EDIT_SSID || type == EDIT_WL_PASSWORD) EditString[I] = ' '; // Zeichen loeschen
if( type == EDIT_BT_PIN) EditString[I] = '0'; // Zeichen setzen
lcd_putc (x, 3, EditString[I], 0);
edit = 1;
}
 
if( get_key_short (1 << KEY_ESC))
{
if( type == EDIT_BT_NAME ) length_tmp = bt_name_length;
if( type == EDIT_BT_PIN ) length_tmp = bt_pin_length;
if (type == EDIT_SSID ) length_tmp = wlan_ssid_length;
if (type == EDIT_WL_PASSWORD ) length_tmp = wlan_password_length;
 
if ((x / 2) + 2 > length_tmp)
{
lcd_rect ((x*6)-3, (8*3)-2, 10, 10, 0);
x = 1;
lcd_rect ((x*6)-3, (8*3)-2, 10, 10, 1);
I = 0;
}
else
{
lcd_rect ((x*6)-3, (8*3)-2, 10, 10, 0);
x++;
x++;
lcd_rect ((x*6)-3, (8*3)-2, 10, 10, 1);
I++; //Zeiger auf Zeichen
}
}
 
if( get_key_press (1 << KEY_ENTER) )
{
lOk = true;
if( type == EDIT_BT_NAME && EditString[0] == ' ' ) // BT-Name: 1. Zeichen darf nicht Space sein
{
lcdx_printp_at( 0, 5, PSTR(" FEHLER! 1. Zeichen! "), MNORMAL, 0,-4);
set_beep ( 300, 0xf00f, BeepNormal);
_delay_ms(2000);
lcd_frect( 0, 5*8-4, 127, 7, 0); // loesche Fehlertext
 
lcd_rect ((x*6)-3, (8*3)-2, 10, 10, 0); // setze Cursor auf Position 1
x = 1;
lcd_rect ((x*6)-3, (8*3)-2, 10, 10, 1);
I = 0;
 
get_key_press(KEY_ALL);
lOk = false;
}
}
 
} while( !lOk );
 
return 1;
}
 
 
 
//--------------------------------------------------------------
// min,max sind in Setup_PKTGeneric() festgelegt
//--------------------------------------------------------------
void Edit_LipoOffset( void )
{
uint8_t redraw = true;
uint8_t inc = 50; // in diesen Schritten hoch/runter zaehlen
uint16_t min = 0; // min. Offset Wert
uint16_t max = 15000; // max. Offset Wert
uint16_t oldValue;
 
if( Config.Lipo_UOffset % inc ) // ggf. wurde frueher ein anderer Wert fuer das Increment 'inc' verwendet
Config.Lipo_UOffset = (uint16_t)(Config.Lipo_UOffset/inc)*inc; // hier wird der Wert auf das aktuelle 'inc' angepasst
 
oldValue = Config.Lipo_UOffset;
 
do
{
//-------------------------
// Screen zeichnen
//-------------------------
if( redraw )
{
PKT_TitleFromMenuItem( true ); // true = showlipo (mit clearscreen)
 
lcdx_printf_at_P( 0, 2, MNORMAL, 0,-4, PSTR("%S:"), MenuCtrl_GetItemText() ); // Menuetext muss im PGM sein! (aktuell keine Unterscheidung RAM/PGM)
 
lcd_rect_round( 0, 32, 127, 21, 1, R2); // Rahmen
lcdx_printp_at( 1, 5, strGet(STR_HELP_LIPOOFFSET1), MNORMAL, 0,-5); // Hilfe-Text 1
lcdx_printp_at( 1, 6, strGet(STR_HELP_LIPOOFFSET2), MNORMAL, 0,-5); // Hilfe-Text 2
lcd_printp_at( 0, 7, strGet(KEYLINE5), MNORMAL); // Keyline
redraw = false;
}
 
 
//-------------------------
// Wert ausgeben
//-------------------------
lcdx_printf_at_P( 0, 3, MNORMAL, 0,-2, PSTR("> %5d => %1.2dv"), Config.Lipo_UOffset, volt_avg );
show_Lipo();
 
 
//-------------------------
// PKT Update-Anforderung?
//-------------------------
if( PKT_CtrlHook() )
{
redraw = true;
}
 
 
//-------------------------
// Tasten
//-------------------------
if( (get_key_press(1 << KEY_PLUS) || get_key_long_rpt_sp((1 << KEY_PLUS),2)) && (Config.Lipo_UOffset < max) )
{
Config.Lipo_UOffset = Config.Lipo_UOffset + inc;
}
 
if( (get_key_press(1 << KEY_MINUS) || get_key_long_rpt_sp((1 << KEY_MINUS),2)) && (Config.Lipo_UOffset > min) )
{
Config.Lipo_UOffset = Config.Lipo_UOffset - inc;
}
 
if( get_key_press(1 << KEY_ENTER) )
{
clear_key_all();
return;
}
 
} while( !get_key_press(1 << KEY_ESC) );
 
clear_key_all();
 
Config.Lipo_UOffset = oldValue; // Abbruch, orginalen Wert wieder herstellen
return;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
#ifdef USE_OSD_SCREEN_OLD
uint8_t Edit_LED_Form (uint8_t Value, uint8_t min, uint8_t max )
{
Pre = Value;
lcd_cls();
 
lcd_printp_at(0, 2, strGetOSDOLD(OSD_LED_Form), MNORMAL);
 
switch (Value)
{
case 0x1:
lcd_circle (14 * 6 + 5, 2 * 8 + 3, 3, 1); // kreis
 
lcd_fcircle (16 * 6 + 5, 2 * 8 + 3, 3, 0); // l�schen
lcd_circle (16 * 6 + 5, 2 * 8 + 3, 3, 1); // kreis
lcd_fcircle (16 * 6 + 5, 2 * 8 + 3, 1, 1); // plus
break;
case 0x3 :
lcd_circle (14 * 6 + 5, 2 * 8 + 3, 3, 1); // kreis
 
lcd_fcircle (16 * 6 + 5, 2 * 8 + 3, 3, 1); // schwarz
break;
break;
}
 
lcd_printp_at(0, 7, strGet(KEYLINE2), 0);
 
do
{
if ((get_key_press (1 << KEY_PLUS)) && (Value == 1))
{
Value = 3;
lcd_circle (14 * 6 + 5, 2 * 8 + 3, 3, 1); // kreis
 
lcd_fcircle (16 * 6 + 5, 2 * 8 + 3, 3, 1); // schwarz
}
 
if ((get_key_press (1 << KEY_MINUS)) && (Value == 3))
{
Value = 1;
lcd_circle (14 * 6 + 5, 2 * 8 + 3, 3, 1); // kreis
 
lcd_fcircle (16 * 6 + 5, 2 * 8 + 3, 3, 0); // l�schen
lcd_circle (16 * 6 + 5, 2 * 8 + 3, 3, 1); // kreis
lcd_fcircle (16 * 6 + 5, 2 * 8 + 3, 1, 1); // plus
}
 
if (get_key_press (1 << KEY_ENTER))
{
edit = 1;
Config.OSD_LEDform = Value;
// WriteParameter();
edit = 0;
return Value;
}
}
 
while (!get_key_press (1 << KEY_ESC));
{
get_key_press(KEY_ALL);
edit = 0;
Config.OSD_LEDform = Pre;
return Pre;
}
}
#endif // USE_OSD_SCREEN_OLD
 
 
 
//--------------------------------------------------------------
// Show_MAC( progmem, headline, mac)
//--------------------------------------------------------------
void Show_MAC( uint8_t progmem, const char *headline, const char *mac )
{
uint8_t i;
uint8_t z;
 
lcd_cls();
PKT_TitleFromMenuItem( true );
 
if( progmem )
lcdx_printp_center( 2, headline, MNORMAL, 0,2);
else
lcdx_print_center( 2, (uint8_t *)headline, MNORMAL, 0,2);
 
z = 0;
for( i = 0; i < 13; i++)
{
lcdx_putc( z+2, 5, mac[i], MNORMAL, 0,-1);
if( (i%2==1) && (i<11) )
{
z++;
lcdx_printp_at( z+2, 5, PSTR(":"), MNORMAL, 0,-1);
}
z++;
}
lcd_rect_round( 0, 34, 127, 16, 1, R2); // Rahmen
Wait4KeyENDE( false );
}
 
 
 
//--------------------------------------------------------------
// Setup_OSD()
//--------------------------------------------------------------
void Setup_OSD( void )
{
uint8_t itemid;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "OSD Anzeige"
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( OSDS_LOWBAT , MENU_ITEM, NOFUNC , OSDS_LOWBAT_de , OSDS_LOWBAT_en );
//MenuCtrl_PushML2_P( OSDS_MAH , MENU_ITEM, NOFUNC , OSDS_MAH_de , OSDS_MAH_en );
MenuCtrl_PushML2_P( OSDS_RCERROR , MENU_ITEM, NOFUNC , OSDS_RCERROR_de , OSDS_RCERROR_en );
 
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
 
MenuCtrl_PushML2_P( OSDS_SHOWCELLU , MENU_ITEM, NOFUNC , OSDS_SHOWCELLU_de , OSDS_SHOWCELLU_en );
MenuCtrl_PushML2_P( OSDS_MKSETTING , MENU_ITEM, NOFUNC , OSDS_MKSETTING_de , OSDS_MKSETTING_en );
 
#ifdef USE_OSD_SCREEN_OLD
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
MenuCtrl_PushML2_P( OSDS_FALLSPEED , MENU_ITEM, NOFUNC , OSDS_FALLSPEED_de , OSDS_FALLSPEED_en );
MenuCtrl_PushML2_P( OSDS_VARIOBEEP , MENU_ITEM, NOFUNC , OSDS_VARIOBEEP_de , OSDS_VARIOBEEP_en );
MenuCtrl_PushML2_P( OSDS_VOLTBAR , MENU_ITEM, NOFUNC , OSDS_VOLTBAR_de , OSDS_VOLTBAR_en );
MenuCtrl_PushML2_P( OSDS_OUTFORMAT , MENU_ITEM, NOFUNC , OSDS_OUTFORMAT_de , OSDS_OUTFORMAT_en );
MenuCtrl_PushML2_P( OSDS_OUTPOLARITY , MENU_ITEM, NOFUNC , OSDS_OUTPOLARITY_de , OSDS_OUTPOLARITY_en );
#endif
 
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
 
MenuCtrl_PushML2_P( OSDS_DATASV2 , MENU_ITEM, NOFUNC , OSDS_DATASV2_de , OSDS_DATASV2_en );
 
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) break; // ENDE
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
if( itemid == OSDS_LOWBAT ) { Config.MK_LowBat = Edit_generic( Config.MK_LowBat ,32,255, Show_uint10th,1 ,strGet(STR_HELP_LOWBAT1),strGet(STR_HELP_LOWBAT2)); }
if( itemid == OSDS_SHOWCELLU ) { Config.OSD_ShowCellU = Edit_generic( Config.OSD_ShowCellU , 0, 1, YesNo,1 ,NULL,NULL); }
if( itemid == OSDS_MAH ) { Config.OSD_mAh_Warning = Edit_generic( Config.OSD_mAh_Warning , 0,30000, Show_uint5,100 ,NULL,NULL); }
if( itemid == OSDS_RCERROR ) { Config.OSD_RCErrorbeep = Edit_generic( Config.OSD_RCErrorbeep , 0, 1, OnOff,1 ,NULL,NULL); }
if( itemid == OSDS_MKSETTING ) { Config.OSD_ShowMKSetting = Edit_generic( Config.OSD_ShowMKSetting, 0, 1, YesNo,1 ,NULL,NULL); }
if( itemid == OSDS_DATASV2 ) { Config.OSD_SendOSD = Edit_generic( Config.OSD_SendOSD , 0, 1, YesNo,1 ,NULL,NULL); }
 
#ifdef USE_OSD_SCREEN_OLD
if( itemid == OSDS_FALLSPEED ) { Config.OSD_Fallspeed = Edit_generic( Config.OSD_Fallspeed , 0,247, Show_uint10th,1 ,NULL,NULL); }
if( itemid == OSDS_VARIOBEEP ) { Config.OSD_VarioBeep = Edit_generic( Config.OSD_VarioBeep , 0, 1, YesNo,1 ,NULL,NULL); }
if( itemid == OSDS_OUTFORMAT ) { Config.OSD_LEDform = Edit_LED_Form(Config.OSD_LEDform , 1, 3 ); }
if( itemid == OSDS_OUTPOLARITY ) { Config.OSD_InvertOut = Edit_generic( Config.OSD_InvertOut , 0, 1, YesNo,1 ,NULL,NULL); }
if( itemid == OSDS_VOLTBAR ) { Config.OSD_LipoBar = Edit_generic( Config.OSD_LipoBar , 0, 1, YesNo,1 ,NULL,NULL); }
#endif
}
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Mark_OSDScreen( uint8_t osdscreenid )
{
MenuCtrl_ItemMarkR( osdscreenid, (Config.OSD_UseScreen & (1 << osdscreenid)) != 0 );
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Edit_OSDScreen( uint8_t osdscreenid )
{
if( (Config.OSD_UseScreen & (1 << osdscreenid)) == 0 )
Config.OSD_UseScreen = (Config.OSD_UseScreen | (1 << osdscreenid));
else
Config.OSD_UseScreen = (Config.OSD_UseScreen ^ (1 << osdscreenid));
 
Mark_OSDScreen( osdscreenid );
}
 
 
 
//--------------------------------------------------------------
// Setup_OSDScreens()
//--------------------------------------------------------------
void Setup_OSDScreens( void )
{
uint8_t itemid;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "OSD Screens"
 
//---------------
// Menuitems
//---------------
#ifdef USE_OSD_SCREEN_NAVIGATION
MenuCtrl_Push_P( OSDSCREEN_NAVIGATION, MENU_ITEM, NOFUNC, strGet(STR_OSDSCREEN_NAVIGATION) ); Mark_OSDScreen( OSDSCREEN_NAVIGATION );
#endif
 
#ifdef USE_OSD_SCREEN_WAYPOINTS
MenuCtrl_Push_P( OSDSCREEN_WAYPOINTS , MENU_ITEM, NOFUNC, strGet(STR_OSDSCREEN_WAYPOINTS) ); Mark_OSDScreen( OSDSCREEN_WAYPOINTS );
#endif
 
#ifdef USE_OSD_SCREEN_ELECTRIC
MenuCtrl_Push_P( OSDSCREEN_ELECTRIC , MENU_ITEM, NOFUNC, strGet(STR_OSDSCREEN_ELECTRIC) ); Mark_OSDScreen( OSDSCREEN_ELECTRIC );
#endif
 
#ifdef USE_OSD_SCREEN_ELECTRIC_N
MenuCtrl_Push_P( OSDSCREEN_ELECTRIC , MENU_ITEM, NOFUNC, strGet(STR_OSDSCREEN_ELECTRIC) ); Mark_OSDScreen( OSDSCREEN_ELECTRIC );
#endif
 
#ifdef USE_OSD_SCREEN_MKSTATUS
MenuCtrl_Push_P( OSDSCREEN_MKSTATUS , MENU_ITEM, NOFUNC, strGet(STR_OSDSCREEN_MKSTATUS) ); Mark_OSDScreen( OSDSCREEN_MKSTATUS );
#endif
 
#ifdef USE_OSD_SCREEN_USERGPS
MenuCtrl_Push_P( OSDSCREEN_USERGPS , MENU_ITEM, NOFUNC, strGet(STR_OSDSCREEN_USERGPS) ); Mark_OSDScreen( OSDSCREEN_USERGPS );
#endif
 
#ifdef USE_OSD_SCREEN_3DLAGE
MenuCtrl_Push_P( OSDSCREEN_3DLAGE , MENU_ITEM, NOFUNC, strGet(STR_OSDSCREEN_3DLAGE) ); Mark_OSDScreen( OSDSCREEN_3DLAGE );
#endif
 
#ifdef USE_OSD_SCREEN_STATISTIC
MenuCtrl_Push_P( OSDSCREEN_STATISTICS, MENU_ITEM, NOFUNC, strGet(STR_OSDSCREEN_STATISTIC) ); Mark_OSDScreen( OSDSCREEN_STATISTICS );
#endif
 
#ifdef USE_OSD_SCREEN_OLD
MenuCtrl_Push_P( OSDSCREEN_OSD0, MENU_ITEM, NOFUNC, strGet(STR_OSDSCREEN_OSD0) ); Mark_OSDScreen( OSDSCREEN_OSD0 );
MenuCtrl_Push_P( OSDSCREEN_OSD1, MENU_ITEM, NOFUNC, strGet(STR_OSDSCREEN_OSD1) ); Mark_OSDScreen( OSDSCREEN_OSD1 );
MenuCtrl_Push_P( OSDSCREEN_OSD2, MENU_ITEM, NOFUNC, strGet(STR_OSDSCREEN_OSD2) ); Mark_OSDScreen( OSDSCREEN_OSD2 );
#endif
 
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) break; // ENDE
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
Edit_OSDScreen( itemid );
}
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
//--------------------------------------------------------------
// Setup_FollowMe()
//--------------------------------------------------------------
#ifdef USE_FOLLOWME
void Setup_FollowMe( void )
{
uint8_t itemid;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitle_P( PSTR("FollowMe Setup") );
 
//---------------
// Menuitems
//---------------
//--------------------------------------------------------------------------------------------------------
// 25.06.2014 OG - auskommentiert weil nicht verwendet. FollowMe wird aktuell ueber die Daten-Updaterate
// der BT GPS-Maus getriggert!
//--------------------------------------------------------------------------------------------------------
//MenuCtrl_PushML2_P( FME_REFRESH , MENU_ITEM, NOFUNC , FME_REFRESH_de , FME_REFRESH_en );
 
 
 
#ifdef USE_FOLLOWME_STEP2
MenuCtrl_PushML2_P( FME_DISTANCE, MENU_ITEM, NOFUNC, FME_DISTANCE_de, FME_DISTANCE_en );
MenuCtrl_PushML2_P( FME_AZIMUTH , MENU_ITEM, NOFUNC, FME_AZIMUTH_de , FME_AZIMUTH_en );
#endif
MenuCtrl_PushML2_P( FME_SPEED , MENU_ITEM, NOFUNC, FME_SPEED_de , FME_SPEED_en );
MenuCtrl_PushML2_P( FME_RADIUS , MENU_ITEM, NOFUNC, FME_RADIUS_de , FME_RADIUS_en );
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
MenuCtrl_PushML2_P( GPS_DATA , MENU_ITEM, NOFUNC, GPS_DATA_de , GPS_DATA_en );
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) break; // ENDE
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
//if( itemid == FME_REFRESH ) { Config.FM_Refresh = Edit_generic( Config.FM_Refresh ,250,60000, Show_uint3,1 ,NULL,NULL); }
 
if( itemid == FME_DISTANCE) { Config.FM_Distance= Edit_generic( Config.FM_Distance , 0, 100, Show_uint3,1 ,strGet(STR_METERS),NULL); }
if( itemid == FME_AZIMUTH ) { Config.FM_Azimuth = Edit_generic( Config.FM_Azimuth , 0, 360, Show_uint3,1 ,PSTR("Grad"),NULL); }
if( itemid == FME_SPEED ) { Config.FM_Speed = Edit_generic( Config.FM_Speed , 0, 100, Show_uint3,1 ,PSTR("0.1 m/s") ,NULL); }
if( itemid == FME_RADIUS ) { Config.FM_Radius = Edit_generic( Config.FM_Radius , 1, 20, Show_uint3,1 ,strGet(STR_METERS),NULL); }
 
//--------------------
// GPS_DATA
//--------------------
if( itemid == GPS_DATA )
{
GPSMouse_ShowData( GPSMOUSE_SHOW_TIME, 0 ); // 0 = beenden mit Verbindungstrennung
}
}
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
#endif // USE_FOLLOWME
 
 
 
//--------------------------------------------------------------
// Setup_GPSMouse()
//--------------------------------------------------------------
#ifdef USE_BLUETOOTH
 
void Setup_GPSMouse( void )
{
uint8_t itemid;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "GPS Maus"
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( GPS_SEARCH , MENU_ITEM, &BT_SearchDevices , GPS_SEARCH_de , GPS_SEARCH_en );
MenuCtrl_PushML2_P( GPS_DEVICES , MENU_ITEM, &BT_SelectDevice , GPS_DEVICES_de , GPS_DEVICES_en );
 
//--------------------------------------------------------------------------------------------------------
// 25.06.2014 OG - auskommentiert weil erstmal nicht weiter benoetigt. Wurde zwar verwendet in tracking.c
// aber auch dort wurde betroffener Code deaktiviert - siehe Anmerkung tracking.c / PKT_tracking()
//--------------------------------------------------------------------------------------------------------
//MenuCtrl_PushML2_P( GPS_TYPE , MENU_ITEM, NOFUNC , GPS_TYPE_de , GPS_TYPE_en );
 
//--------------------------------------------------------------------------------------------------------
// 25.06.2014 OG - auskommentiert weil nirgendwo verwendet
//--------------------------------------------------------------------------------------------------------
//MenuCtrl_PushML2_P( GPS_ACTIVE , MENU_ITEM, NOFUNC , GPS_ACTIVE_de , GPS_ACTIVE_en );
 
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
MenuCtrl_PushML2_P( GPS_SHOWDEV , MENU_ITEM, NOFUNC , GPS_SHOWDEV_de , GPS_SHOWDEV_en );
MenuCtrl_PushML2_P( GPS_DATA , MENU_ITEM, NOFUNC , GPS_DATA_de , GPS_DATA_en );
 
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) break; // ENDE
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
//--------------------
// GPS_TYPE
//--------------------
/*
if( itemid == GPS_TYPE )
{
Config.gps_UsedGPSMouse = Edit_generic( Config.gps_UsedGPSMouse, 0,1,GPSMOUSE,1 ,NULL,NULL);
}
*/
 
//--------------------
// GPS_ACTIVE
//--------------------
/*
if( itemid == GPS_ACTIVE )
{
Config.gps_UseGPS = Edit_generic( Config.gps_UseGPS, 0,1,YesNo,1 ,NULL,NULL);
}
*/
 
 
//--------------------
// GPS_SHOWDEV
//--------------------
if( itemid == GPS_SHOWDEV )
{
//Show_MAC( progmem, headline, mac)
Show_MAC( false, Config.gps_UsedDevName, Config.gps_UsedMac);
}
 
 
//--------------------
// GPS_DATA
//--------------------
if( itemid == GPS_DATA )
{
GPSMouse_ShowData( GPSMOUSE_SHOW_TIME, 0 ); // 0 = beenden mit Verbindungstrennung
}
 
}
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
 
 
//--------------------------------------------------------------
// zeigt die Konfig des BTM-222
//--------------------------------------------------------------
void BTM222_Info( void )
{
 
lcd_cls();
 
set_Modul_On( Bluetooth );
 
if( !ScrollBox_Create(55) ) // max. 55 Zeilen
return; // kein RAM mehr
 
ScrollBox_Push_P( MNORMAL, PSTR("BTM-222 Config") );
ScrollBox_Push_P( MNORMAL, PSTR("") );
bt_showsettings();
ScrollBox_Push_P( MNORMAL, PSTR("End of Config") );
 
ScrollBox_Show();
ScrollBox_Destroy(); // free memory
 
set_Modul_On( USB );
 
}
 
 
 
//--------------------------------------------------------------
// Setup_BTM222_MenuCreate()
//
// das Menue aendert sich je nachdem ob BTM222 ein- oder
// ausgeschaltet ist
//--------------------------------------------------------------
void Setup_BTM222_MenuCreate( void )
{
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "Bluetooth"
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( BT_INSTALLED , MENU_ITEM, NOFUNC , BT_INSTALLED_de , BT_INSTALLED_en );
 
if( Config.UseBT )
{
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
MenuCtrl_PushML2_P( BT_NAME , MENU_ITEM, NOFUNC , BT_NAME_de , BT_NAME_en );
MenuCtrl_PushML2_P( BT_PIN , MENU_ITEM, NOFUNC , BT_PIN_de , BT_PIN_en );
MenuCtrl_PushML2_P( BT_REID , MENU_ITEM, NOFUNC , BT_REID_de , BT_REID_en );
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
MenuCtrl_PushML2_P( BT_INIT , MENU_ITEM, NOFUNC , BT_INIT_de , BT_INIT_en );
MenuCtrl_PushML2_P( BT_PCCONFIG , MENU_ITEM, &Port_FC2CFG_BT , BT_PCCONFIG_de , BT_PCCONFIG_en );
MenuCtrl_PushML2_P( BT_SHOWCONFIG, MENU_ITEM, &BTM222_Info , BT_SHOWCONFIG_de, BT_SHOWCONFIG_en);
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
MenuCtrl_PushML2_P( BT_MAC , MENU_ITEM, NOFUNC , BT_MAC_de , BT_MAC_en );
}
}
 
#endif // end: #ifdef USE_BLUETOOTH
 
 
 
//--------------------------------------------------------------
// Setup_BTM222()
//--------------------------------------------------------------
#ifdef USE_BLUETOOTH
 
void Setup_BTM222( void )
{
uint8_t itemid;
uint8_t UseBT;
uint8_t i;
char string[11];
 
Setup_BTM222_MenuCreate();
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) break; // ENDE
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
edit = 0;
 
//--------------------
// BT_INSTALLED
//--------------------
if( itemid == BT_INSTALLED )
{
UseBT = Config.UseBT;
Config.UseBT = Edit_generic( Config.UseBT ,0,1, YesNo,1 ,NULL,NULL);
 
if( UseBT != Config.UseBT ) // hat Benutzer Einstellung geaendert?
{
if( Config.UseBT ) // BTM222 wurde aktiviert - initialisieren
{
BTM222_Initalize();
 
//if( bt_init() )
// Config.BTIsSet = true;
//else
// Config.BTIsSet = false;
}
 
MenuCtrl_Destroy(); // Menue aendern wegen wechsel Wi232 vorhanden / nicht vorhanden
Setup_BTM222_MenuCreate();
continue;
}
}
 
 
//--------------------
// BT_NAME
//--------------------
if( itemid == BT_NAME )
{
bt_fixname();
strncpyfill( string, Config.bt_name, bt_name_length+1 ); // bt_name_length=10 + 1 Terminierende 0
Edit_String( string, bt_name_length, EDIT_BT_NAME );
 
if( edit == 1 )
{
strrtrim( EditString); // Leerzeichen rechts entfernen
//lcd_print_at( 0, 5, EditString, 0); // DEBUG
//lcdx_printf_at( 17, 5, MNORMAL, 0,0, "%3d", strlen(EditString) );
//_delay_ms(8000);
 
strncpy( Config.bt_name, EditString, bt_name_length+1 );
}
}
 
 
//--------------------
// BT_PIN
//--------------------
if( itemid == BT_PIN )
{
for( i = 0; i < bt_pin_length; i++)
{
string[i] = Config.bt_pin[i];
}
string[bt_pin_length] = 0;
Edit_String( string, bt_pin_length, EDIT_BT_PIN );
 
if (edit == 1)
{
for( i = 0; i < bt_pin_length; i++)
{
Config.bt_pin[i] = EditString[i];
}
}
}
 
 
//--------------------
// BT_INIT
//--------------------
if( itemid == BT_INIT )
{
//lcd_cls ();
//Old_Baudrate = Config.PKT_Baudrate;
 
BTM222_Initalize();
 
/*
if( bt_init() == true )
{
lcd_printp_at( 0, 3, PSTR("BT Init ok"), MNORMAL);
WriteBTInitFlag();
}
else
{
lcd_printp_at( 0, 3, PSTR("BT Init Error"), MNORMAL);
Config.BTIsSet = false;
set_beep( 1000, 0x0040, BeepNormal);
}
_delay_ms(2500); // 2.5 Sekunden anzeigen fuer Benutzer
*/
}
 
 
//--------------------
// BT_MAC
//--------------------
if( itemid == BT_MAC )
{
//Show_MAC( progmem, headline, mac)
Show_MAC( true, PSTR("BTM-222 MAC"), Config.bt_Mac);
}
 
 
//--------------------
// BT_REID
//--------------------
if( itemid == BT_REID )
{
for( i = 0; i < RE_ID_length; i++)
{
string[i] = Config.RE_ID[i];
}
string[RE_ID_length] = 0;
Edit_String( string, RE_ID_length, EDIT_BT_PIN );
 
if( edit == 1 )
{
for( i = 0; i < RE_ID_length; i++)
{
Config.RE_ID[i] = EditString[i];
}
}
}
 
} // end: while( true )
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
 
} // end: Setup_BTM222()
 
#endif // end: #ifdef USE_BLUETOOTH
 
 
 
 
//--------------------------------------------------------------
// Setup_BLE()
//--------------------------------------------------------------
void Setup_BLE( void )
{
uint8_t itemid;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "Bluetooth BLE"
 
//---------------
// Menuitems
//---------------
MenuCtrl_Push_P( BLE_INSTALLED, MENU_ITEM, NOFUNC, strGet(MODULE_EXIST) );
 
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) break; // ENDE
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
//--------------------
// BT_INSTALLED
//--------------------
if( itemid == BT_INSTALLED )
{
Config.UseBLE = Edit_generic( Config.UseBLE, 0, 1, YesNo, 1 ,strGet(STR_EXTSV2MODULE),NULL);
}
} // end: while( true )
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
 
} // end: Setup_BTM222()
 
 
 
//--------------------------------------------------------------
// Setup_MKConnection()
//--------------------------------------------------------------
void Setup_MKConnection( void )
{
uint8_t itemid;
uint8_t old;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "Bluetooth BLE"
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( MKCONN_CONNECTION , MENU_ITEM, NOFUNC , MKCONN_CONNECTION_de , MKCONN_CONNECTION_en );
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
MenuCtrl_PushML2_P( MKCONN_BAUDRATE , MENU_ITEM, NOFUNC , MKCONN_BAUDRATE_de , MKCONN_BAUDRATE_en );
 
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) break; // ENDE
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
 
//--------------------
// MKCONN_CONNECTION
//--------------------
if( itemid == MKCONN_CONNECTION )
{
old = Config.U02SV2;
Config.U02SV2 = Edit_generic( Config.U02SV2, 0, 1, MK_Connection,1, NULL,NULL);
 
if( Config.U02SV2 != old ) // Verbindung geaendert?
{
if( Config.U02SV2 == 1 ) Change_Output( Uart02FC ); // 1 = Kabel
else Change_Output( Uart02Wi ); // 0 = Wi.232
}
 
if( (Config.U02SV2 == 0) && (Config.UseWi == false) ) // FEHLER: Wi.232 nicht aktiviert (Config.U02SV2 = 0 -> entspricht Wi.232)
{
//PKT_Message_P( text , error, timeout, beep, clear)
PKT_Message_P( strGet(STR_WI232_ACTIVATE), true , 3000 , true, true);
}
}
 
 
//--------------------
// MKCONN_BAUDRATE
//--------------------
if( itemid == MKCONN_BAUDRATE )
{
old = Config.PKT_Baudrate;
Config.PKT_Baudrate = Edit_generic( Config.PKT_Baudrate ,1,6,Baudrate,1 ,PSTR("Standard: ! 57600 !"),NULL);
 
if( Config.PKT_Baudrate != old )
{
// Wi.232 umkonfigurieren
if( Config.UseWi )
{
Wi232_Initalize();
}
 
// BTM222 umkonfigurieren
#ifdef USE_BLUETOOTH
if( Config.UseBT )
{
//set_BTOn();
BTM222_Initalize();
//set_BTOff();
}
#endif // end: #ifdef USE_BLUETOOTH
}
}
 
} // end: while( true )
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
 
} // end: Setup_BTM222()
 
 
 
 
//--------------------------------------------------------------
// Setup_WI232_MenuCreate()
//
// das Menue aendert sich je nachdem ob Wi.232 ein- oder
// ausgeschaltet ist
//--------------------------------------------------------------
void Setup_WI232_MenuCreate( void )
{
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "Wi.232"
 
//---------------
// Menuitems
//---------------
MenuCtrl_Push_P( WI_INSTALLED , MENU_ITEM, NOFUNC , strGet(CONNECT13) );
 
if( Config.UseWi )
{
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
MenuCtrl_PushML2_P( WI_TXRX , MENU_ITEM, NOFUNC , WI_TXRX_de , WI_TXRX_en );
MenuCtrl_PushML2_P( WI_GROUP , MENU_ITEM, NOFUNC , WI_GROUP_de , WI_GROUP_en );
 
// 06.06.2014 OG
//MenuCtrl_PushML2_P( WI_MODE , MENU_ITEM, NOFUNC , WI_MODE_de , WI_MODE_en );
//MenuCtrl_PushML2_P( WI_TIMEOUT , MENU_ITEM, NOFUNC , WI_TIMEOUT_de , WI_TIMEOUT_en );
//MenuCtrl_PushML2_P( WI_MTU , MENU_ITEM, NOFUNC , WI_MTU_de , WI_MTU_en );
 
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
MenuCtrl_PushML2_P( WI_INIT , MENU_ITEM, NOFUNC , WI_INIT_de , WI_INIT_en );
 
//MenuCtrl_PushML2_P( WI_PCCONFIG , MENU_ITEM, &Port_USB2CFG_Wi , WI_PCCONFIG_de , WI_PCCONFIG_en );
MenuCtrl_PushML2_P( WI_PCCONFIG , MENU_ITEM, &Wi232_ConfigPC , WI_PCCONFIG_de , WI_PCCONFIG_en );
 
 
}
}
 
 
 
//--------------------------------------------------------------
// Setup_WI232()
//--------------------------------------------------------------
void Setup_WI232( void )
{
uint8_t itemid;
uint8_t UseWi;
 
Setup_WI232_MenuCreate();
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) break; // ENDE
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
edit = 0;
 
if( itemid == WI_TXRX ) { Config.WiTXRXChannel = Edit_generic( Config.WiTXRXChannel , 0, 5, Show_uint3,1 ,NULL,NULL); }
if( itemid == WI_GROUP ) { Config.WiNetworkGroup = Edit_generic( Config.WiNetworkGroup , 0, 127, Show_uint3,1 ,NULL,NULL); }
//if( itemid == WI_MODE ) { Config.WiNetworkMode = Edit_generic( Config.WiNetworkMode , 0, 1, Wi_Netmode,1 ,NULL,NULL); }
//if( itemid == WI_TIMEOUT ) { Config.WiTXTO = Edit_generic( Config.WiTXTO , 0, 127, Show_uint3,1 ,NULL,NULL); }
//if( itemid == WI_MTU ) { Config.WiUartMTU = Edit_generic( Config.WiUartMTU , 0, 127, Show_uint3,1 ,NULL,NULL); }
if( itemid == WI_INIT ) { Wi232_Initalize(); }
 
//--------------------
// WI_INSTALLED
//--------------------
if( itemid == WI_INSTALLED )
{
UseWi = Config.UseWi;
Config.UseWi = Edit_generic( Config.UseWi, 0,1, YesNo,1, NULL,NULL);
if( UseWi != Config.UseWi ) // hat Benutzer Einstellung geaendert?
{
if( Config.UseWi )
Wi232_Initalize(); // Wi232 wurde aktiviert: init
 
MenuCtrl_Destroy(); // Menue aendern wegen wechsel Wi232 vorhanden / nicht vorhanden
Setup_WI232_MenuCreate();
continue;
}
}
}
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
 
//--------------------------------------------------------------
// Setup_PKTGeneric()
//
// entspricht "PKT allgemein"
//--------------------------------------------------------------
void Setup_PKTGeneric( void )
{
uint8_t itemid;
uint8_t old;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
 
//---------------
// Einstellungen
//---------------
MenuCtrl_SetTitleFromParentItem(); // "PKT allgemein"
//MenuCtrl_SetCycle( false );
//MenuCtrl_SetShowBatt( false );
//MenuCtrl_SetBeep( true );
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( PKT_LANGUAGE , MENU_ITEM, NOFUNC , LANGUAGE_de , LANGUAGE_en );
MenuCtrl_PushML2_P( TIME_ZONE , MENU_ITEM, NOFUNC , TIME_ZONE_de , TIME_ZONE_en );
MenuCtrl_PushML2_P( TIME_SUMMER , MENU_ITEM, NOFUNC , TIME_SUMMER_de , TIME_SUMMER_en );
 
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
 
MenuCtrl_PushML2_P( PKT_PKTOFF , MENU_ITEM, NOFUNC , PKT_PKTOFF_de , PKT_PKTOFF_en );
MenuCtrl_PushML2_P( PKT_LIGHTOFF , MENU_ITEM, NOFUNC , LIGHTOFF_de , LIGHTOFF_en );
 
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
 
// 18.04.2014 OG: rausgenommen da es aktuell auch nicht mehr mit PKT 3.9m Hardware geht
//if( PCB_Version == PKT39m ) // Helligkeit nur bei PKT39m - bei der PKT39x geht das nicht mehr
// MenuCtrl_PushML2_P( PKT_BRIGHTNESS , MENU_ITEM, NOFUNC , BRIGHTNESS_de , BRIGHTNESS_en );
 
MenuCtrl_PushML2_P( PKT_CONTRAST , MENU_ITEM, NOFUNC , CONTRAST_de , CONTRAST_en );
MenuCtrl_PushML2_P( PKT_BEEPER , MENU_ITEM, NOFUNC , BEEPER_de , BEEPER_en );
 
#ifdef USE_SOUND
MenuCtrl_PushML2_P( PKT_SOUNDMODUL , MENU_ITEM, NOFUNC , SOUNDMODUL_de , SOUNDMODUL_en );
MenuCtrl_PushML2_P( PKT_VOLUME , MENU_ITEM, NOFUNC , VOLUME_de , VOLUME_en );
#endif
 
MenuCtrl_PushML2_P( PKT_ACCUTYPE , MENU_ITEM, NOFUNC , ACCUTYPE_de , ACCUTYPE_en );
MenuCtrl_PushML2_P( PKT_ACCUMEASURE , MENU_ITEM, NOFUNC , ACCUMEASURE_de , ACCUMEASURE_en );
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) break;
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
if( itemid == PKT_LANGUAGE )
{
old = Config.DisplayLanguage;
Config.DisplayLanguage = Edit_generic( Config.DisplayLanguage , 0, 1, Language,1, NULL,NULL);
 
if( old != Config.DisplayLanguage )
{
PKT_Ask_Restart( strGetLanguage(LANGUAGE_de,LANGUAGE_en) );
}
}
 
if( itemid == TIME_ZONE ) Config.timezone = Edit_generic( Config.timezone ,-12, 12, Show_uint3,1, PSTR("+1 = Berlin "),PSTR("-5 = New York"));
if( itemid == TIME_SUMMER ) Config.summertime = Edit_generic( Config.summertime , 0, 1, YesNo,1, NULL,NULL);
if( itemid == PKT_LIGHTOFF ) Config.DisplayTimeout = Edit_generic( Config.DisplayTimeout , 0,254, Show_uint3,1, strGet(STR_HELP_PKTOFFTIME1),NULL);
if( itemid == PKT_PKTOFF ) Config.PKTOffTimeout = Edit_generic( Config.PKTOffTimeout , 0,254, Show_uint3,1, strGet(STR_HELP_PKTOFFTIME1),NULL);
if( itemid == PKT_BEEPER ) Config.HWBeeper = Edit_generic( Config.HWBeeper , 0, 1, YesNo,1, NULL,NULL);
if( itemid == PKT_SOUNDMODUL ) Config.HWSound = Edit_generic( Config.HWSound , 0, 1, YesNo,1, NULL,NULL);
if( itemid == PKT_VOLUME ) Config.Volume = Edit_generic( Config.Volume , 0, 50, Show_uint3,1, NULL,NULL);
if( itemid == PKT_CONTRAST ) { Config.LCD_Kontrast = Edit_generic( Config.LCD_Kontrast , 10, 40, Kontrast,1, NULL,NULL);
lcd_set_contrast( Config.LCD_Kontrast );
}
 
//if( itemid == PKT_BRIGHTNESS ) Config.LCD_Helligkeit = Edit_DisplayHelligkeit(Config.LCD_Helligkeit,0,100);
if( itemid == PKT_ACCUTYPE ) Config.PKT_Accutyp = Edit_generic( Config.PKT_Accutyp , 0, 1, PKT_Akku,1, NULL,NULL);
if( itemid == PKT_ACCUMEASURE ) Edit_LipoOffset();
}
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
 
//--------------------------------------------------------------
// Setup_Main()
//
// Das Hauptmenue fuer das gesamte Setup
//--------------------------------------------------------------
void Setup_MAIN( void )
{
uint8_t itemid;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
 
//---------------
// Einstellungen
//---------------
MenuCtrl_SetTitleFromParentItem(); // "PKT Setup"
//MenuCtrl_SetTitle_P( PSTR("PKT Setup") );
//MenuCtrl_SetCycle( false );
//MenuCtrl_SetShowBatt( false );
//MenuCtrl_SetBeep( true );
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( SETUP_PKTCONFIG , MENU_SUB , &Setup_PKTGeneric , SETUP_PKTCONFIG_de , SETUP_PKTCONFIG_en );
MenuCtrl_PushML2_P( SETUP_OSDVIEW , MENU_SUB , &Setup_OSD , SETUP_OSDVIEW_de , SETUP_OSDVIEW_en );
MenuCtrl_PushML2_P( SETUP_OSDSCREENS , MENU_SUB , &Setup_OSDScreens , SETUP_OSDSCREENS_de , SETUP_OSDSCREENS_en );
 
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
 
MenuCtrl_PushML2_P( SETUP_MKCONNECTION , MENU_SUB , &Setup_MKConnection , SETUP_MKCONNECTION_de , SETUP_MKCONNECTION_en );
 
MenuCtrl_PushML2_P( SETUP_WI232 , MENU_SUB , &Setup_WI232 , SETUP_WI232_de , SETUP_WI232_en );
 
#ifdef USE_BLUETOOTH
MenuCtrl_PushML2_P( SETUP_BTM222 , MENU_SUB , &Setup_BTM222 , SETUP_BTM222_de , SETUP_BTM222_en );
#endif
 
#if (defined(USE_SV2MODULE_BLE) || defined(USE_WLAN))
if( PCB_SV2RxTxPatch ) // nur sichtbar mit SV2 Patch!
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
#endif
 
#ifdef USE_SV2MODULE_BLE
if( PCB_SV2RxTxPatch ) // nur sichtbar mit SV2 Patch!
MenuCtrl_PushML2_P( SETUP_BLE , MENU_SUB , &Setup_BLE , SETUP_BLE_de , SETUP_BLE_en );
#endif
 
#ifdef USE_WLAN
if( PCB_SV2RxTxPatch ) // nur sichtbar mit SV2 Patch!
MenuCtrl_PushML2_P( SETUP_WIFLY , MENU_SUB , &Setup_WiFly , SETUP_WIFLY_de , SETUP_WIFLY_en );
#endif
 
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
 
#ifdef USE_BLUETOOTH
MenuCtrl_PushML2_P( SETUP_GPSMAUS , MENU_SUB , &Setup_GPSMouse , SETUP_GPSMAUS_de , SETUP_GPSMAUS_en );
#endif
 
#ifdef USE_FOLLOWME
MenuCtrl_PushML2_P( SETUP_FOLLOWME , MENU_SUB , &Setup_FollowMe , SETUP_FOLLOWME_de , SETUP_FOLLOWME_en );
#endif
 
#ifdef USE_TRACKING
MenuCtrl_PushML2_P( SETUP_SERVOCONFIG , MENU_SUB , &Setup_ServoTracking, SETUP_SERVOCONFIG_de , SETUP_SERVOCONFIG_en ); // tracking/servo_setup.c
#endif
 
#ifdef USE_JOYSTICK
MenuCtrl_PushML2_P( SETUP_JOYSTICK , MENU_SUB , &Setup_Joysticks , SETUP_JOYSTICK_de , SETUP_JOYSTICK_en );
#endif
 
MenuCtrl_PushSeparator(); // MENUE TRENNLINIE
 
MenuCtrl_PushML2_P( SETUP_PKTUPDATE , MENU_ITEM, &PKT_Update , SETUP_PKTUPDATE_de , SETUP_PKTUPDATE_en );
//MenuCtrl_PushML2_P( SETUP_PKTDEBUG , MENU_ITEM, NOFUNC , SETUP_PKTDEBUG_de , SETUP_PKTDEBUG_en );
MenuCtrl_PushML2_P( SETUP_EEPROMRESET , MENU_ITEM, &PKT_Reset_EEprom , SETUP_EEPROMRESET_de , SETUP_EEPROMRESET_en );
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
if( MenuCtrl_GetKey() == KEY_ESC ) break;
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
//--------------------
// SETUP_PKTDEBUG
//--------------------
if( itemid == SETUP_PKTDEBUG )
{
Config.Debug = Edit_generic( Config.Debug, 0,1,Show_uint3,1 ,NULL,NULL);
}
 
}
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/setup/setup.h
0,0 → 1,111
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY setup.h
//#
//# 26.06.2014 OG
//# - add: Setup_FollowMe()
//#
//# 22.06.2014 OG
//# - del: Variable CheckGPS
//#
//# 13.06.2014 OG
//# - del: ChangeWi_SV2()
//#
//# 11.06.2014 OG
//# - del: Edit_Language()
//#
//# 31.04.2014 OG
//# - chg: Edit_String() - Parameter 'Text' entfernt
//#
//# 28.05.2014 OG
//# - chg: Edit_generic() - geaenderte Aufrufparameter
//# - Parameter 'Text' enfernt da vom Menue geerbt
//# - Parameter fuer Hilfetexte
//#
//# 04.04.2014 OG
//# - del: Edit_ShowTitle_P()
//#
//# 02.04.2014 OG
//# - add: Edit_ShowTitle_P()
//# - add: WlanMode
//#
//# 15.07.2013 Cebra
//# - add: Edit_Printout um WlanSecurity erweitert
//#
//# 22.05.2013 OG
//# - del: verschiedene Cleanups
//############################################################################
 
 
#ifndef _setup_H
#define _setup_H
 
 
#define EDIT_BT_NAME 1
#define EDIT_BT_PIN 2
#define EDIT_SSID 3
#define EDIT_WL_PASSWORD 4
 
 
typedef enum // Varianten fuer die Anzeige der Werte im Setupmenüe
{
Show_uint3, Show_int3, Show_uint5, Show_uint10th, GPSMOUSE, Wi_Netmode,
OnOff, YesNo, Orientation, NormRev, Kontrast, Baudrate, Language, Sticktype, WlanMode, WlanSecurity, PKT_Akku, MK_Connection
} EditMode;
 
void Setup_MAIN(void);
void Setup_FollowMe( void );
 
void Display_Setup (void);
void Wi_Use (void);
void BT_Use (void);
void BT_SelectDevice (void);
uint8_t BT_CheckBTM222( void );
 
void Wait4KeyOK( void );
 
int16_t Edit_generic( int16_t Value, int16_t min, int16_t max, uint8_t what, uint8_t Addfactor, const char *strHelp1, const char *strHelp2 );
uint8_t Edit_String( const char *data, const uint8_t length, uint8_t type);
 
uint8_t BT_ShowGPSData( uint8_t modus );
 
void BTM222_Info( void );
 
extern uint8_t bt_name_len;
extern uint8_t length_tmp;
extern uint8_t Old_Baudrate; //Merkzelle für alte Baudrate
extern uint8_t edit;
extern char EditString[21];
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/setup
Property changes:
Added: svn:ignore
+_old_source
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/sound/pwmsine8bit.c
0,0 → 1,280
//file pwmsine8bit.c
//generate 8 bit sinewave using wavetable lookup
//12khz sample rate, 62500 hz pwm on pd5 oc1a
//for ere co embmega32 16Mhz 38400
 
//May 3 07 Bob G initial edit 8 bit
//May 5 07 Bob G add traffic tones
//Jan 18 08 Bob G compile with 7.15
 
//#include <stdio.h>
//#include <stdlib.h>
 
 
#include <ctype.h>
#include <math.h> //sin
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <string.h>
#include <stdint.h>
#include "../timer/timer.h"
#include "../main.h"
#ifdef USE_SOUND
 
 
#define INTR_OFF() asm("CLI")
#define INTR_ON() asm("SEI")
 
 
//------vars in bss-------
 
volatile unsigned char sindat[256]; //8 bit sine table
//unsigned int addat[8]; //internal 10 bit
unsigned int idesfreq;
unsigned char iattenfac; //0-255
unsigned char dispon;
unsigned char freqincipart,freqincfpart;
unsigned char waveptipart,waveptfpart;
unsigned char tics;
unsigned char generate;
 
float basefreq;
float freqratio;
float sampfreq; //12khz
float samppd; //83.33usec
float fdesfreq;
float attendb; //0-50
float attenfac; //.999-0
const float pi=3.141592654;
 
 
 
#define MSB(w) ((char*) &w)[1]
#define LSB(w) ((char*) &w)[0]
 
#define TONE_BUFFER_SIZE 64
#define TONE_BUFFER_MASK ( TONE_BUFFER_SIZE - 1)
 
static volatile unsigned char ToneBuf[TONE_BUFFER_SIZE];
static volatile unsigned char ToneBufHead;
static volatile unsigned char ToneBufTail;
 
 
//-------------------------------
void cvtfreq2frac(void){
//calc freq ratio, separate into integer and fractional parts
fdesfreq=idesfreq;
freqratio=fdesfreq/basefreq; //calc freq ratio from basefreq
freqincipart=(int)freqratio; //calc integer part
freqincfpart=(freqratio-freqincipart)*256; //calc fractional part
// cprintf("ipart %02x fpart %02x\n",freqincipart,freqincfpart);
}
 
//-------------------------------
void cvtdb2fac(void){
//cvt db to attenuation factor
 
attenfac=pow(10.0,-attendb/20.0); //10^0=1
iattenfac=(unsigned char)(attenfac*255.0);
// cprintf("attenfac %#7.5f\n",attenfac);
// cprintf("iattenfac %02x\n",iattenfac);
}
 
//-------------------------
void initsindat(void){
//init 8 bit signed sin table 0-ff in ram 36dB s/n 46Hz basefreq
unsigned int n;
 
for(n=0; n < 256; n++){
sindat[n]=(signed char)127.0*sin(2.0*pi*n/256.0); //256 sin points
}
}
 
 
//-------------------------
void initvars(void){
//init vars
 
// sampfreq=12000.0; //hz
sampfreq=19530.0; //hz
// printf("samp freq %#7.1f hz\n\r",sampfreq);
// printf("samp freq %#7.1f hz\n\r",1234567.1);
samppd=1.0/sampfreq; //83.33usec
// printf("samppd %#7.1f usec \n\r",samppd*1e6);
basefreq=sampfreq/256.0; //46.875hz
// printf("basefreq %#7.5f hz\n\r",basefreq);
idesfreq=400;
cvtfreq2frac();
cvtdb2fac(); //0db =.9999= 0xff
}
 
 
//---------------------
 
 
 
 
void tone1(int hz)
//tone at hz for ms
 
{
 
uint8_t volume = 0;
// TCNT2=0;
// sound_timer = ms/5;
// soundpause_timer = soundpause/5;
 
idesfreq=hz;
cvtfreq2frac();
attendb=volume;
cvtdb2fac();
if (hz ==0) generate=0;
else { generate = 1;
// TIMSK2 |= _BV(TOIE2); // Interrupt freigeben
}
 
}
 
 
 
//-------------------------------
void tone_handler(void) // wird aus Timerinterrupt aufgerufen
 
{
uint16_t f_Hz=0;
uint16_t dur_ms=0;
char volume=0;
char tmp_high = 0;
char tmp_low = 0;
unsigned char tmptail;
 
 
if ( ToneBufHead != ToneBufTail) {
/* calculate and store new buffer index */
tmptail = (ToneBufTail + 1) & TONE_BUFFER_MASK;
ToneBufTail = tmptail;
/* get one byte from buffer */
tmp_low = ToneBuf[tmptail]; /* f_Hz low */
}else{
 
return;
}
if ( ToneBufHead != ToneBufTail) {
/* calculate and store new buffer index */
tmptail = (ToneBufTail + 1) & TONE_BUFFER_MASK;
ToneBufTail = tmptail;
/* get one byte from buffer */
tmp_high = ToneBuf[tmptail]; /* f_Hz high */
}else{
return;
}
 
f_Hz = (((uint16_t) tmp_high) << 8) | tmp_low;
 
if ( ToneBufHead != ToneBufTail) {
/* calculate and store new buffer index */
tmptail = (ToneBufTail + 1) & TONE_BUFFER_MASK;
ToneBufTail = tmptail;
/* get one byte from buffer*/
volume = ToneBuf[tmptail]; /* volume */
}else{
return;
}
 
if ( ToneBufHead != ToneBufTail) {
/* calculate and store new buffer index */
tmptail = (ToneBufTail + 1) & TONE_BUFFER_MASK;
ToneBufTail = tmptail;
/* get one byte from buffer */
tmp_low = ToneBuf[tmptail]; /* low Duratuion */
}else{
return;
}
if ( ToneBufHead != ToneBufTail) {
/* calculate and store new buffer index */
tmptail = (ToneBufTail + 1) & TONE_BUFFER_MASK;
ToneBufTail = tmptail;
/* get one byte from buffer*/
tmp_high = ToneBuf[tmptail]; /* high Duration */
}else{
return;
}
 
dur_ms = (((uint16_t) tmp_high) << 8) | tmp_low;
 
sound_timer = dur_ms/10;
// TCNT2=0;
idesfreq= f_Hz;
cvtfreq2frac();
attendb= volume;
cvtdb2fac();
 
if (f_Hz ==0) generate=0;
else { generate = 1;
// TIMSK2 |= _BV(TOIE2); // Interrupt freigeben
}
 
 
 
// printf("tone_handler f_Hz: %i dur_ms: %i volume: %i\n\r", f_Hz,dur_ms,volume);
 
}
 
 
void tone_putc(unsigned char data)
{
unsigned char tmphead;
 
tmphead = (ToneBufHead + 1) & TONE_BUFFER_MASK;
 
while ( tmphead == ToneBufTail ){
;/* wait for free space in buffer */
}
 
ToneBuf[tmphead] = data;
ToneBufHead = tmphead;
 
}/* tone_putc */
 
 
void playTone(uint16_t f_Hz, uint16_t dur_ms, uint8_t volume)
 
{
 
// printf("Playtone f_Hz: %i dur_ms: %i volume: %i\n\r", f_Hz,dur_ms,volume);
 
tone_putc(LSB(f_Hz));
tone_putc( MSB(f_Hz));
tone_putc( volume);
tone_putc(LSB(dur_ms));
tone_putc(MSB(dur_ms));
 
 
}
 
 
//-----------------
void InitSound(void){//main program
 
 
 
ToneBufHead = 0;
ToneBufTail = 0;
 
initvars();
initsindat();
 
Timer2_Init();
Timer3_Init();
 
 
 
 
}
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/sound/pwmsine8bit.h
0,0 → 1,22
/*
* pwmsine8bit.h
*
* Created on: 01.09.2012
* Author: cebra
*/
 
#ifndef PWMSINE8BIT_H_
#define PWMSINE8BIT_H_
 
extern unsigned char freqincipart,freqincfpart;
extern unsigned char waveptipart,waveptfpart;
extern unsigned char iattenfac; //0-255
extern unsigned char generate;
extern volatile unsigned char sindat[256]; //8 bit sine table
void InitSound(void);
void tone(int hz,uint8_t volume, uint16_t ms, uint16_t soundpause);
void tone1(int hz);
void playTone(uint16_t f_Hz, uint16_t dur_ms, uint8_t volume);
void tone_handler(void);
 
#endif /* PWMSINE8BIT_H_ */
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/stick/stick.c
0,0 → 1,507
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* Copyright (C) 2012 Martin Runkel *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
 
#include <string.h>
#include <stdlib.h>
 
#include "../lcd/lcd.h"
#include "../timer/timer.h"
//#include "../tracking/servo.h"
#include "../messages.h"
#include "../lipo/lipo.h"
#include "stick.h"
#include "stick_setup.h"
#include "../eeprom/eeprom.h"
#include "../setup/setup.h"
 
#define SERVO_CORRECT 3.125
 
 
#include <util/delay.h>
#include <inttypes.h>
#include <stdlib.h>
 
#include "../main.h"
#include "../uart/uart1.h"
#include "../uart/usart.h"
 
 
#define LIMIT_MIN_MAX(value, min, max) {if(value <= min) value = min; else if(value >= max) value = max;}
 
int16_t Pos_Stick[12]; // 1,5mS
int16_t Pos_alt[5]; //
 
uint8_t BalkenPos = 0;
uint8_t Stick_Display = 0;
//uint8_t serialChannelRichtung = 0;
//uint8_t serialChannelNeutral = 0;
//uint8_t serialChannelConfig = 2;
 
 
//--------------------------------------------------------------
//
void joystick (void)
{
// uint8_t chg = 0;
// uint8_t Pos_Stick = 150; // 1,5mS
// uint8_t Pos_alt = 150; //
//int16_t Pos_Stick[12]; // 1,5mS
uint8_t chg = 0;
//uint8_t BalkenPos = 0;
uint8_t Stick_Nr = 0;
//uint8_t Stick_Display = 0;
uint8_t i = 0;
 
memset (Pos_Stick, 150, 3); // füllt 3+1 Byte vom Pos_Stick[12] mit 150
//int16_t Pos_alt[5]; //
int16_t Poti_Summe[5]; //
memset (Poti_Summe, 0, 5); // füllt 3+1 Byte mit 0
int16_t Poti_Neutral[5]; //
 
 
// ADC- init
//if (Config.Lipomessung == true)
//{
 
//}
//for (uint8_t i = 0; i < 4; i++)
 
if (Config.stick_typ[0] == 0) // Poti
{
PORTA &= ~(1<<PORTA0);
DDRA &= ~(1<<DDA0);
}
else // Taster
{
PORTA |= (1<<PORTA0);
DDRA |= (1<<DDA0);
}
if (Config.Lipomessung == false)
{
if (Config.stick_typ[1] == 0) // Poti
{
PORTA &= ~(1<<PORTA1);
DDRA &= ~(1<<DDA1);
}
else // Taster
{
PORTA |= (1<<PORTA1);
DDRA |= (1<<DDA1);
}
}
if (Config.stick_typ[2] == 0)
{
PORTA &= ~(1<<PORTA2);
DDRA &= ~(1<<DDA2);
}
else
{
PORTA |= (1<<PORTA2);
DDRA |= (1<<DDA2);
}
if (Config.stick_typ[3] == 0)
{
PORTA &= ~(1<<PORTA3);
DDRA &= ~(1<<DDA3);
}
else
{
PORTA |= (1<<PORTA3);
DDRA |= (1<<DDA3);
}
 
//if (Config.stick_dir[i] == 0) serialChannelRichtung &= ~(1<<i); else serialChannelRichtung |= (1<<i);
//if (Config.stick_neutral[i] == 0) serialChannelNeutral &= ~(1<<i); else serialChannelNeutral |= (1<<i);
 
//if (Config.Lipomessung == true)
 
//serialChannelConfig
 
 
// Ermittlung der Neutralposition
for (uint8_t i = 0; i < 4; i++)
{
ADMUX = (1<<REFS0)|(0<<MUX0); // Multiplexer selection Register: AVCC with external capacitor at AREF pin , ADC1
ADMUX = (ADMUX & ~(0x1F)) | (i & 0x1F); // ADC[i] verwenden
 
timer = 50;
while (timer > 0);
 
ADCSRA = (1<<ADEN)|(1<<ADSC)|(1<<ADPS2)|(1<<ADPS1)|(1<<ADPS0); // ADC Enable, ADC Start, Prescaler 128
 
 
while (ADCSRA & (1<<ADSC)); // wenn ADC fertig
 
Poti_Neutral[i] = ((ADCW>>2)&0xff);
LIMIT_MIN_MAX (Poti_Neutral[i],108,148);
 
ADMUX = (ADMUX & ~(0x1F)) | (i & 0x1F); // ADC[i] verwenden
// Stick_Nr 1,2,3 = Potis, Stick_Nr 1= Lipo
ADCSRA |= (1<<ADSC); // ADC Start
 
while (ADCSRA & (1<<ADSC)); // wenn ADC fertig
 
Poti_Neutral[i] = ((ADCW>>2)&0xff);
LIMIT_MIN_MAX (Poti_Neutral[i],108,148);
}
Stick_Nr = 0;
ADMUX = (ADMUX & ~(0x1F)) | (Stick_Nr & 0x1F); // ADC[i] verwenden
ADCSRA |= (1<<ADSC); // ADC Start
 
/*
Stick_Nr = 0;
ADMUX = (1<<REFS0)|(0<<MUX0); // Multiplexer selection Register: AVCC with external capacitor at AREF pin , ADC1
ADMUX = (ADMUX & ~(0x1F)) | (Stick_Nr & 0x1F); // ADC[Stick_Nr] verwenden
timer = 50;
while (timer > 0);
ADCSRA = (1<<ADEN)|(1<<ADSC)|(1<<ADPS2)|(1<<ADPS1)|(1<<ADPS0); // ADC Enable, ADC Start, Prescaler 128
 
// Stick-Neutralposition bestimmen
 
while (ADCSRA & (1<<ADSC)); // wenn ADC fertig
Poti_Neutral[Stick_Nr] = ((ADCW>>2)&0xff);
LIMIT_MIN_MAX (Poti_Neutral[Stick_Nr],108,148);
Stick_Nr = 2 ;
ADMUX = (ADMUX & ~(0x1F)) | (Stick_Nr & 0x1F); // ADC[i] verwenden
// Stick_Nr 1,2,3 = Potis, Stick_Nr 1= Lipo
ADCSRA |= (1<<ADSC); // ADC Start
while (ADCSRA & (1<<ADSC)); // wenn ADC fertig
Poti_Neutral[Stick_Nr] = ((ADCW>>2)&0xff);
LIMIT_MIN_MAX (Poti_Neutral[Stick_Nr],108,148);
Stick_Nr = 0;
ADMUX = (ADMUX & ~(0x1F)) | (Stick_Nr & 0x1F); // ADC[i] verwenden
// Stick_Nr 1,2,3 = Potis, Stick_Nr 1= Lipo
ADCSRA |= (1<<ADSC); // ADC Start
*/
 
 
 
//OCR1A = 150 * SERVO_CORRECT; // Servomitte
 
lcd_cls ();
// Kopfzeile und Rahmen zeichnen
lcd_printp (PSTR(" serielle Potis 1-5 "), 2);
//lcd_printp_at (7, 5, PSTR("%"), 0);
//lcd_printp_at (16, 5, PSTR("mS"), 0);
 
lcd_printp_at(0, 7, strGet(KEYLINE3), 0);
lcd_printp_at (18, 7, PSTR("\x19O\x18"), 0);
for (i=0 ; i< 5 ; i++)
{
BalkenPos = 12 + (i*8) ;
 
lcd_rect(3,BalkenPos, 120, 6, 1); // +-150% Rahmen
lcd_line(23,BalkenPos,23,(BalkenPos+6),1); // -100%
lcd_line(43,BalkenPos,43,(BalkenPos+6),1); // -50%
lcd_frect(62,BalkenPos, 2, 6, 1); // 0%
lcd_line(83,BalkenPos,83,(BalkenPos+6),1); // +50%
lcd_line(103,BalkenPos,103,(BalkenPos+6),1); // +100%
}
// Reset auf Mittelstellung
Pos_Stick[0] = 150;
Poti_Summe[0] = 0;
Pos_Stick[2] = 150;
Poti_Summe[2] = 0;
Pos_Stick[4] = 150;
Poti_Summe[4] = 0;
chg = 255;
 
do
{
if (!(ADCSRA & (1<<ADSC))) // wenn ADC fertig
{
//Pos_Stick[Stick_Nr] = 150 + 128 - ((ADCW>>2)&0xff);
//if (serialChannelRichtung & (1<<Stick_Nr))
if (Config.stick_dir[Stick_Nr] > 0)
Pos_Stick[Stick_Nr] = Poti_Neutral[Stick_Nr] - ((ADCW>>2)&0xff);
else
Pos_Stick[Stick_Nr] = ((ADCW>>2)&0xff) - Poti_Neutral[Stick_Nr];
 
 
LIMIT_MIN_MAX (Pos_Stick[Stick_Nr],-120,120);
//if ((Stick_Nr==0) || (Stick_Nr==2)) // nur die Potis 1,2 sind nicht neutralisierend
if (Config.stick_neutral[Stick_Nr]==0) // nicht neutralisierend
{
Poti_Summe[Stick_Nr] += (Pos_Stick[Stick_Nr]/8) * abs(Pos_Stick[Stick_Nr]/8);
LIMIT_MIN_MAX (Poti_Summe[Stick_Nr],-(120*128),(120*128));
Pos_Stick[Stick_Nr]= Poti_Summe[Stick_Nr] / 128; // nicht neutralisierend
}
Pos_Stick[Stick_Nr] += 150;
//LIMIT_MIN_MAX (Pos_Stick[Stick_Nr],30,270); // war 75 , 225
LIMIT_MIN_MAX (Pos_Stick[Stick_Nr],Config.stick_min[Stick_Nr],Config.stick_max[Stick_Nr]); // war 30, 270
if (Pos_Stick[Stick_Nr] != Pos_alt[Stick_Nr]) // nur bei Änderung
{
chg |= (1<<Stick_Nr) ;
//Pos_alt=Pos_Stick ; // verschoben
}
Stick_Nr ++ ;
//if (Stick_Nr==1) Stick_Nr=2; // Lipo überspringen
if (Stick_Nr==3) // Taster
{
if (Config.stick_dir[Stick_Nr] > 0)
{
if (PINA & (1 << KEY_EXT)) Pos_Stick[Stick_Nr] = Config.stick_min[Stick_Nr];
else Pos_Stick[Stick_Nr] = Config.stick_max[Stick_Nr];
}
else
{
if (PINA & (1 << KEY_EXT)) Pos_Stick[Stick_Nr] = Config.stick_max[Stick_Nr];
else Pos_Stick[Stick_Nr] = Config.stick_min[Stick_Nr];
}
if (Pos_Stick[Stick_Nr] != Pos_alt[Stick_Nr])
{
chg |= (1<<Stick_Nr) ;
}
Stick_Nr=0;
}
/*
#ifndef ohne_Lipo // MartinR
Stick_Nr = 1; // MartinR AD-Kanal 1 überspringen wegen Lipo Überwachung
#endif
*/
 
ADMUX = (ADMUX & ~(0x1F)) | (Stick_Nr & 0x1F); // ADC[i] verwenden
// Stick_Nr 1,2,3 = Potis, Stick_Nr 0= Lipo
ADCSRA |= (1<<ADSC); // ADC Start
//serialPotis ();
}
 
if ((get_key_press (1 << KEY_PLUS) | get_key_long_rpt_sp ((1 << KEY_PLUS), 3)))
//if (get_key_press (1 << KEY_PLUS))
//if (PINA & (1 << KEY_PLUS))
{
if (Config.stick_neutral[4]==0) // nicht neutralisierend
{
if (Config.stick_dir[4] == 0) Pos_Stick[4] ++ ; else Pos_Stick[4] -- ;
LIMIT_MIN_MAX (Pos_Stick[4],Config.stick_min[4],Config.stick_max[4]); // war 30, 270
}
else
{
if (Config.stick_dir[4] == 0) Pos_Stick[4] = Config.stick_max[4] ; else Pos_Stick[4] = Config.stick_min[4] ;
}
chg |= (1<<4) ;
}
else if ((get_key_press (1 << KEY_MINUS) | get_key_long_rpt_sp ((1 << KEY_MINUS), 3)))
{
if (Config.stick_neutral[4]==0) // nicht neutralisierend
{
if (Config.stick_dir[4] == 0) Pos_Stick[4] -- ; else Pos_Stick[4] ++ ;
LIMIT_MIN_MAX (Pos_Stick[4],Config.stick_min[4],Config.stick_max[4]); // war 30, 270
//LIMIT_MIN_MAX (Pos_Stick[Stick_Nr],30,270); // war 75 , 225
}
else
{
if (Config.stick_dir[4] == 0) Pos_Stick[4] = Config.stick_min[4] ; else Pos_Stick[4] = Config.stick_max[4] ;
}
chg |= (1<<4) ;
}
 
if (Config.stick_neutral[4]!= 0 && Pos_Stick[4]!= 150 && (PINA &(1 << KEY_PLUS)) && (PINA &(1 << KEY_MINUS)))
{
Pos_Stick[4] = 150 ;
chg |= (1<<4) ;
}
 
if (get_key_press (1 << KEY_ENTER))
{
/*
for (i=0 ; i< 4 ; i++)
{
BalkenPos = 12 + (i*8) ;
lcd_frect (4, (BalkenPos+1), 118, 4, 0); // Balken löschen
lcd_frect(62, BalkenPos, 2, 6, 1); // 0%
}
*/
Pos_Stick[0] = 150;
Poti_Summe[0] = 0;
Pos_Stick[2] = 150;
Poti_Summe[2] = 0;
Pos_Stick[4] = 150;
Poti_Summe[4] = 0;
BeepTime = 200;
BeepMuster = 0x0080;
chg = 255;
}
 
if (chg)
{
if (chg & (1<<0)); // Stick 1
{
BalkenPos = 12 + (0*8) ;
Stick_Display = 0;
Balken_Zeichnen () ;
Pos_alt[Stick_Display]=Pos_Stick[Stick_Display];
}
// Stick 2 = Lipo
if (chg & (1<<1)); // Stick 2
{
BalkenPos = 12 + (1*8) ;
Stick_Display = 1;
//if (serialChannelConfig & (0<<1)) Balken_Zeichnen () ; // nur wenn keine Lipo-Spannung
if (Config.Lipomessung == false) Balken_Zeichnen () ; // nur wenn keine Lipo-Spannung
Pos_alt[Stick_Display]=Pos_Stick[Stick_Display];
}
if (chg & (1<<2)); // Stick 3
{
BalkenPos = 12 + (2*8) ;
Stick_Display = 2;
Balken_Zeichnen () ;
Pos_alt[Stick_Display]=Pos_Stick[Stick_Display];
}
if (chg & (1<<3)); // Stick 4 = Taster
{
BalkenPos = 12 + (3*8) ;
Stick_Display = 3;
Balken_Zeichnen () ;
Pos_alt[Stick_Display]=Pos_Stick[Stick_Display];
}
if (chg & (1<<4)); // Stick 5 = Taster vom PKT
{
BalkenPos = 12 + (4*8) ;
Stick_Display = 4;
Balken_Zeichnen () ;
//OCR1A = (((Pos_Stick[Stick_Display]-150)/1.6)+150) * SERVO_CORRECT; // Servostellung , 1.6=0.8*0.5
Pos_alt[Stick_Display]=Pos_Stick[Stick_Display];
}
chg = 0;
serialPotis ();
}
}
while (!get_key_press (1 << KEY_ESC));
get_key_press(KEY_ALL);
//#ifdef HWVERSION3_9
//#ifndef ohne_Lipo // MartinR
if (Config.Lipomessung == true) // MartinR: geändert
{
//DDRA &= ~(1<<DDA1); // Eingang: PKT Lipo Messung
//PORTA &= ~(1<<PORTA1);
ADC_Init(); // ADC für Lipomessung wieder aktivieren
}
 
//ADC_Init(); // ADC für Lipomessung wieder aktivieren
//#endif
//#endif
 
}
 
//--------------------------------------------------------------
//
void serialPotis (void)
{
uint8_t i = 0;
memset (buffer, 0, 12); // füllt die 12+1 Byte vom buffer mit 0
 
for (i=0 ; i< 5 ; i++)
{
buffer[i] = Pos_Stick[i]-150 ;
}
SendOutData('y', ADDRESS_FC, 1, buffer, 12);
}
//--------------------------------------------------------------
//
void Balken_Zeichnen (void)
{
// Balken löschen
if ((Pos_Stick[Stick_Display] > Pos_alt[Stick_Display])&&(Pos_alt[Stick_Display] < 150)) // Balken links löschen
lcd_frect ((63-((150 -Pos_alt[Stick_Display]) * 0.5)), (BalkenPos+1), (63-((150- Pos_Stick[Stick_Display]) * 0.5)), 4, 0);
if ((Pos_Stick[Stick_Display] < Pos_alt[Stick_Display])&&(Pos_alt[Stick_Display] > 150)) // Balken rechts löschen
lcd_frect ((63+((Pos_Stick[Stick_Display] - 150) * 0.5)), (BalkenPos+1), (63+((Pos_alt[Stick_Display] - 150) * 0.5)), 4, 0);
// Balken zeichnen
if (Pos_Stick[Stick_Display] >= 150)
{
lcd_frect (63, (BalkenPos+1), ((Pos_Stick[Stick_Display] - 150) * 0.5), 4, 1);
//write_ndigit_number_u (4, 5, ((Pos_Stick[Stick_Display] - 150) * 1.25), 3, 0, 0); // Pulse width in %
lcd_frect(62, (BalkenPos), 2, 6, 1); // 0%
}
else
{
lcd_frect (63 - ((150 - Pos_Stick[Stick_Display]) * 0.5), (BalkenPos+1), ((150 - Pos_Stick[Stick_Display]) * 0.5), 4, 1);
//write_ndigit_number_u (4, 5, ((150 - Pos_Stick[Stick_Display]) * 1.25), 3, 0, 0); // Pulse width in %
lcd_frect(62, (BalkenPos), 2, 6, 1); // 0%
}
// Raster zeichnen
lcd_line(3, BalkenPos,3, (BalkenPos+6),1); // -150%
lcd_line(23, BalkenPos,23, (BalkenPos+6),1); // -100%
lcd_line(43, BalkenPos,43, (BalkenPos+6),1); // -50%
lcd_line(83, BalkenPos,83, (BalkenPos+6),1); // +50%
lcd_line(103,BalkenPos,103,(BalkenPos+6),1); // +100%
lcd_line(123,BalkenPos,123,(BalkenPos+6),1); // +150%
}
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/stick/stick.h
0,0 → 1,42
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
 
#ifndef _STICK_H
#define _STICK_H
 
void joystick (void);
void serialPotis (void);
void Balken_Zeichnen (void);
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/stick/stick_setup.c
0,0 → 1,279
 
/****************************************************************/
/* Setup für die Sticks */
/* 2013 Cebra */
/****************************************************************/
 
//############################################################################
//# HISTORY stick_setup.c
//#
//# 28.05.2014 OG
//# - chg: Setup's auf das neue Edit_generic() umgestellt
//#
//# 11.05.2014 OG
//# - chg: einge Setup-Menues umgestellt auf MenuCtrl_SetTitleFromParentItem()
//# -> die Menues 'erben' damit ihren Titel vom aufrufenden Menuepunkt
//#
//# 30.03.2014 OG
//# - chg: ein paar englische Texte auf DE gemappt weil der Unterschied unerheblich war
//# - chg: Sprache Hollaendisch vollstaendig entfernt
//# - chg: MenuCtrl_PushML_P() umgestellt auf MenuCtrl_PushML2_P()
//#
//# 31.05.2013 OG
//# - chg: einige redundante Menuetitel auf define umgestellt
//#
//# 24.05.2013 OG
//# - chg: Aufrufe von MenuCtrl_Push() umgestellt auf MenuCtrl_PushML_P()
//#
//# 22.05.2013 OG
//# - umgestellt auf menuctrl
//# - del: include utils/menuold.h
//#
//# 17.05.2013 OG
//# - chg: umgestellt auf utils/menuold.h
//#
//# 16.04.2013 Cebra
//# - chg: PROGMEM angepasst auf neue avr-libc und GCC, prog_char depreciated
//#
//# 04.04.2013 Cebra
//# - chg: Texttuning
//#
//# 03.04.2013 Cebra
//# - chg: Holländische Menütexte
//#
//# 27.03.2013 Cebra
//# - chg: Fehler bei der Menüsteuerung behoben
//############################################################################
 
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include "../cpu.h"
#include <util/delay.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include "../main.h"
#include "../timer/timer.h"
#include "stick_setup.h"
#include "../lcd/lcd.h"
#include "../timer/timer.h"
#include "../messages.h"
#include "../mk-data-structs.h"
#include "../eeprom/eeprom.h"
#include "../setup/setup.h"
#include "../utils/menuctrl.h"
 
 
//############################################################################
#ifdef USE_JOYSTICK
//############################################################################
 
//-----------------------------
// Setup_Joysticks()
//-----------------------------
#define JSTICKS_OVERVIEW 1
#define JSTICKS_STICK1 2
#define JSTICKS_STICK2 3
#define JSTICKS_STICK3 4
#define JSTICKS_STICK4 5
#define JSTICKS_STICK5 6
#define JSTICKS_LIPO 7
 
static const char JSTICKS_OVERVIEW_de[] PROGMEM = "Übersicht";
static const char JSTICKS_OVERVIEW_en[] PROGMEM = "summary";
 
static const char JSTICKS_STICK1_de[] PROGMEM = "Stick 1";
#define JSTICKS_STICK1_en JSTICKS_STICK1_de
 
static const char JSTICKS_STICK2_de[] PROGMEM = "Stick 2";
#define JSTICKS_STICK2_en JSTICKS_STICK2_de
 
static const char JSTICKS_STICK3_de[] PROGMEM = "Stick 3";
#define JSTICKS_STICK3_en JSTICKS_STICK3_de
 
static const char JSTICKS_STICK4_de[] PROGMEM = "Stick 4";
#define JSTICKS_STICK4_en JSTICKS_STICK4_de
 
static const char JSTICKS_STICK5_de[] PROGMEM = "Stick 5";
#define JSTICKS_STICK5_en JSTICKS_STICK5_de
 
static const char JSTICKS_LIPO_de[] PROGMEM = "PKT Lipomessung";
static const char JSTICKS_LIPO_en[] PROGMEM = "PKT Lipo measure.";
 
 
//############################################################################
 
//-----------------------------
// Setup_Stick()
//-----------------------------
#define MSTICK_MIN 1
#define MSTICK_MAX 2
#define MSTICK_TYPE 3
#define MSTICK_DIR 4
#define MSTICK_NEUT 5
 
static const char MSTICK_MIN_de[] PROGMEM = "Minimal Wert";
static const char MSTICK_MIN_en[] PROGMEM = "minimal value";
 
static const char MSTICK_MAX_de[] PROGMEM = "Maximal Wert";
static const char MSTICK_MAX_en[] PROGMEM = "maximal value";
 
static const char MSTICK_TYPE_de[] PROGMEM = "Type";
static const char MSTICK_TYPE_en[] PROGMEM = "type";
 
static const char MSTICK_DIR_de[] PROGMEM = "Richtung";
static const char MSTICK_DIR_en[] PROGMEM = "direction";
 
static const char MSTICK_NEUT_de[] PROGMEM = "Neutralisiered";
static const char MSTICK_NEUT_en[] PROGMEM = "neutralizing";
 
//############################################################################
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Joysticks_Uebersicht(void)
{
lcd_cls ();
lcd_printpns_at(0, 0, PSTR(" Joystick Setup "), 2);
lcd_printpns_at(0, 1, PSTR("S Min Max Typ Dir N"), 0);
 
for (uint8_t i = 0; i < 5; i++) {
 
write_ndigit_number_u (0, 2+i,i+1, 1, 0,0);
write_ndigit_number_u (2, 2+i,Config.stick_min[i], 3, 0,0);
write_ndigit_number_u (6, 2+i,Config.stick_max[i], 3, 0,0);
if (Config.stick_typ[i] == 0) lcd_printpns_at(10, 2+i, PSTR("Poti"), 0); else lcd_printpns_at(10, 2+i, PSTR("Tast"), 0);
//if (Config.stick_typ[i] == 0) // MartinR: geändert
//{
if (Config.stick_dir[i] == 0) lcd_printpns_at(15, 2+i, PSTR("Norm"), 0); else lcd_printpns_at(15, 2+i, PSTR("Rev"), 0);
if (Config.stick_neutral[i] == 0) lcd_printpns_at(20, 2+i, PSTR("N"), 0); else lcd_printpns_at(20, 2+i, PSTR("Y"), 0);
//}
if (i == 1) if (Config.Lipomessung == true) lcd_printpns_at(3, 2+i, PSTR("PKT Lipomessung "), 0);
 
}
 
 
lcd_printp_at (18, 7, PSTR("OK"), 0);
 
do{}
while (!(get_key_press (1 << KEY_ENTER)));
}
 
 
 
//--------------------------------------------------------------
// Setup_Stick()
//--------------------------------------------------------------
void Setup_Stick( uint8_t stick )
{
uint8_t itemid;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "Stick n"
//MenuCtrl_SetTitle_P( PSTR("Joystick") );
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( MSTICK_MIN , MENU_ITEM, NOFUNC , MSTICK_MIN_de , MSTICK_MIN_en );
MenuCtrl_PushML2_P( MSTICK_MAX , MENU_ITEM, NOFUNC , MSTICK_MAX_de , MSTICK_MAX_en );
MenuCtrl_PushML2_P( MSTICK_TYPE , MENU_ITEM, NOFUNC , MSTICK_TYPE_de , MSTICK_TYPE_en );
MenuCtrl_PushML2_P( MSTICK_DIR , MENU_ITEM, NOFUNC , MSTICK_DIR_de , MSTICK_DIR_en );
MenuCtrl_PushML2_P( MSTICK_NEUT , MENU_ITEM, NOFUNC , MSTICK_NEUT_de , MSTICK_NEUT_en );
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) break; // ENDE
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
if( itemid == MSTICK_MIN ) { Config.stick_min[stick] = Edit_generic( Config.stick_min[stick] ,0,300,Show_uint3,1 ,NULL,NULL); }
if( itemid == MSTICK_MAX ) { Config.stick_max[stick] = Edit_generic( Config.stick_max[stick] ,0,300,Show_uint3,1 ,NULL,NULL); }
if( itemid == MSTICK_TYPE ) { Config.stick_typ[stick] = Edit_generic( Config.stick_typ[stick] ,0, 1,Sticktype,1 ,NULL,NULL); }
if( itemid == MSTICK_DIR ) { Config.stick_dir[stick] = Edit_generic( Config.stick_dir[stick] ,0, 1,NormRev,1 ,NULL,NULL); }
if( itemid == MSTICK_NEUT ) { Config.stick_neutral[stick]= Edit_generic( Config.stick_neutral[stick] ,0, 1,YesNo,1 ,NULL,NULL); }
 
}
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
 
//--------------------------------------------------------------
// Setup_Joysticks()
//--------------------------------------------------------------
void Setup_Joysticks( void )
{
uint8_t itemid;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "Joystick"
//MenuCtrl_SetTitle_P( PSTR("Joystick Setup") );
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( JSTICKS_OVERVIEW , MENU_ITEM, NOFUNC , JSTICKS_OVERVIEW_de , JSTICKS_OVERVIEW_en );
MenuCtrl_PushML2_P( JSTICKS_STICK1 , MENU_SUB , NOFUNC , JSTICKS_STICK1_de , JSTICKS_STICK1_en );
MenuCtrl_PushML2_P( JSTICKS_STICK2 , MENU_SUB , NOFUNC , JSTICKS_STICK2_de , JSTICKS_STICK2_en );
MenuCtrl_PushML2_P( JSTICKS_STICK3 , MENU_SUB , NOFUNC , JSTICKS_STICK3_de , JSTICKS_STICK3_en );
MenuCtrl_PushML2_P( JSTICKS_STICK4 , MENU_SUB , NOFUNC , JSTICKS_STICK4_de , JSTICKS_STICK4_en );
MenuCtrl_PushML2_P( JSTICKS_STICK5 , MENU_SUB , NOFUNC , JSTICKS_STICK5_de , JSTICKS_STICK5_en );
MenuCtrl_PushML2_P( JSTICKS_LIPO , MENU_ITEM, NOFUNC , JSTICKS_LIPO_de , JSTICKS_LIPO_en );
 
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) break; // ENDE
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
if( itemid == JSTICKS_OVERVIEW ) { Joysticks_Uebersicht(); }
if( itemid == JSTICKS_STICK1 ) { Setup_Stick(0); }
if( itemid == JSTICKS_STICK2 ) { if (Config.Lipomessung == true)
{
lcd_cls ();
lcd_printp_at(0, 3, PSTR("LiPo measure!"), MNORMAL);
_delay_ms(1000);
}
else Setup_Stick(1); //Stick 2
}
if( itemid == JSTICKS_STICK3 ) { Setup_Stick(2); }
if( itemid == JSTICKS_STICK4 ) { Setup_Stick(3); }
if( itemid == JSTICKS_STICK5 ) { Setup_Stick(4); }
if( itemid == JSTICKS_LIPO ) { Config.Lipomessung = Edit_generic( Config.Lipomessung ,0,1,YesNo,1 ,NULL,NULL); }
 
}
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
//############################################################################
#endif // USE_JOYSTICK
//############################################################################
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/stick/stick_setup.h
0,0 → 1,13
//############################################################################
//# HISTORY stick_setup.h
//#
//# 22.05.2013 OG
//# - umgestellt auf menuctrl
//############################################################################
 
#ifndef _STICK_SETUP_H_
#define _STICK_SETUP_
 
void Setup_Joysticks(void);
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/stick
Property changes:
Added: svn:ignore
+_old_source
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/timer/timer.c
0,0 → 1,856
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* based on the key handling by Peter Dannegger *
* see www.mikrocontroller.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY timer.c
//#
//#
//# 08.08.2015 CB
//# - add: timer_nmea_timeout
//#
//# 29.06.2014 OG
//# - chg: ISR( TIMER0_COMPA_vect ) - LipoCheck() wieder hinzugefuegt
//# - chg: LipoCheck() - leichte optische Anpassung und lcd-Ausgabe an ISR angepasst
//# - add: #include "../lipo/lipo.h"
//#
//# 24.06.2014 OG
//# - add: timer_gauge
//# - add: #include "../pkt/pkt.h"
//#
//# 13.06.2014 OG
//# - del: IdleTimer entfernt da nicht verwendet
//# - chg: ISR(TIMER0_COMPA_vect) - "PKT aus nach" (via timer_pkt_off)
//# - chg: ISR(TIMER0_COMPA_vect) - "LCD aus nach" umgestellt von Sekunden
//# auf Minuten (via timer_lcd_off)
//# - chg: Code-Formattierung
//#
//# 31.05.2014 OG
//# - chg: 'timer_pktctrl' umbenannt zu 'timer_pktupdatecheck' (exklusiv fuer pkt.c)
//#
//# 25.04.2014 OG
//# - add: timer_get_displaydata
//#
//# 24.04.2014 OG
//# - add: timer1 (generischer Timer)
//# - add: timer3 (generischer Timer)
//# - add: timer_mk_timeout
//# - del: timer_get_erdata
//#
//# 29.03.2014 OG
//# - add: clear_key_all() - loescht ALLE Tasten egal ob short, long, repeat...
//#
//# 13.06.2013 cebra
//# - chg: Abfrage nach Hardwaresound bei Displaybeleuchtung entfällt
//#
//# 19.05.2013 OG
//# - add: timer_pktctrl - exclusive Verwendung von pkt.c
//#
//# 24.03.2013 OG
//# - add: UTCTime - inkrementiert wird UTCTime.seconds auf der Basis
//# von timer_pkt_uptime (modulo 100) aktuell initialisert von
//# der MK-NC Time durch OSD_MK_UTCTime()
//# - add: timer_get_tidata
//#
//# 21.03.2013 OG
//# - add: timer_pkt_uptime (auch in timer.h)
//# - add: timer_osd_refresh (auch in timer.h) -> verwendet in osd.c
//# - add: timer_get_bldata (auch in timer.h) -> verwendet in osd.c
//# - add: timer_get_erdata (auch in timer.h) -> verwendet in osd.c
//#
//# 09.03.2013 OG
//# - add: timer2 (auch in timer.h)
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <string.h>
#include <util/delay.h>
#include <inttypes.h>
 
 
#include "../main.h"
#include "../timer/timer.h"
#include "../eeprom/eeprom.h"
#include "../lcd/lcd.h"
#include "../uart/uart1.h"
#include "../bluetooth/bluetooth.h"
#include "../setup/setup.h"
#include"../tracking/tracking.h"
#include "../sound/pwmsine8bit.h"
#include "../lipo/lipo.h"
#include "../pkt/pkt.h"
 
//
//#if defined HWVERSION1_2W || defined HWVERSION1_2
//#include "HAL_HW1_2.h"
//#endif
//
//#if defined HWVERSION1_3W || defined HWVERSION1_3
//#include "HAL_HW1_3.h"
//#endif
 
//#ifdef HWVERSION3_9
#include "../HAL_HW3_9.h"
//#endif
 
//----------------------
// generische Timer
//----------------------
volatile uint16_t timer;
volatile uint16_t timer1;
volatile uint16_t timer2;
volatile uint16_t timer3;
 
//----------------------
// spezielle Timer
//----------------------
volatile uint16_t timer_pktupdatecheck; // verwendet von pkt.c (!EXKLUSIV!)
volatile uint16_t timer_osd_refresh; // verwendet in osd.c
volatile uint16_t timer_get_bldata; // verwendet in osd.c
volatile uint16_t timer_get_tidata; // verwendet in osd.c
volatile uint16_t timer_get_displaydata; // verwendet in osd.c
volatile uint16_t timer_mk_timeout; // verwendet u.a. in osd.c
volatile uint16_t timer_gauge; // verwendet in pkt.c fuer den rotierenden Wartekreisel
volatile uint16_t timer_nmea_timeout; // verwendet in nmea.c
volatile uint16_t abo_timer;
 
uint32_t timer_lcd_off = 0; // LCD aus nach... (der Zaehler muss 32Bit sein)
uint32_t timer_pkt_off = 0; // PKT aus nach... (der Zaehler muss 32Bit sein)
 
volatile uint16_t sound_timer;
volatile uint16_t soundpause_timer;
volatile static unsigned int tim_main;
 
volatile PKTdatetime_t UTCTime;
volatile uint32_t timer_pkt_uptime = 0; // OG: ja, 32 bit muss so sein!
 
uint8_t key_state = 0; // debounced and inverted key state:
// bit = 1: key pressed
uint8_t key_press = 0; // key press detect
uint8_t key_long = 0; // key long press
uint8_t key_rpt = 0; // key repeat
uint8_t key_lrpt = 0; // key long press and repeat
uint8_t key_rpts = 0; // key long press and speed repeat
uint8_t repeat_speed = 0;
 
 
volatile uint8_t Display_on; // LCD Flag Display on/off
 
volatile uint16_t WarnCount = 0; // Zähler der LIPO Warnzeit
volatile uint16_t WarnToggle = 0; // Togglezähler zum blinken
volatile uint16_t WarnTime = 10; // Laenge der LIPO Warnzeit 10 Sek.
volatile uint16_t PoffTime = 15; // Laenge der Wartezeit vor abschalten 15 Sek.
//volatile uint16_t PoffTime = 30; // Laenge der Wartezeit vor abschalten 30 Sek.
 
 
 
unsigned int BeepTime = 0;
unsigned int BeepMuster = 0xffff;
unsigned int BeepPrio = 0;
 
volatile unsigned int CountMilliseconds = 0;
 
 
 
//--------------------------------------------------------------
// System (100Hz)
//--------------------------------------------------------------
void Timer0_Init( void )
{
timer = 0;
 
TCCR0A = (1 << WGM01);
TCCR0B = (1 << CS02) | (1 << CS00);
OCR0A = (F_CPU / (100L * 1024L)) ;
 
TIMSK0 |= (1 << OCIE0A); // enable interrupt for OCR
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
//void Timer1_Init (void) // Timer 1-A
//{
// // löschen
// TCCR1A = 0;
// TCCR1B = 0;
// TIMSK1 = 0;
//
// // setzen
// TCCR1A |= (1 << COM1A1) | (1 << WGM11);
// TCCR1B |= (1 << CS11) | (1 << CS10) | (1 << WGM13) | (1 << WGM12);
//
// ICR1 = (F_CPU / 64) * 20 / 1000;
//
// OCR1A = 470; // ca. Servomitte
//}
 
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
ISR( TIMER2_COMPA_vect )
{
PORTD |= (1 << PD7);
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
ISR( TIMER2_COMPB_vect )
{
PORTD &= ~(1 << PD7);
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Timer2_Init( void )
{
if( Config.HWSound == 1 )
{ // Sound PWM
TCCR2A = 0x00; //stop
ASSR = 0x00; //set async mode
TCNT2 = 0x00; //setup
OCR2A = 0xff;
//Fast PWM 0xFF BOTTOM MAX
//Set OC2A on Compare Match
//clkT2S/8 (From prescaler)
TCCR2A |= (1 << WGM20) | (1 << WGM21) |(1 << COM2A1) | (1 << COM2A0);
TCCR2B |= (1 << CS20);
}
else
{ // Displayhelligkeit
DDRD |= (1 << DDD7); // PD7 output
TCCR2A |= (1 << WGM21) | (1 << WGM20) | (1 << COM2A1); // non invers
TCCR2B |= (1 << CS20); // Prescaler 1/1
TIMSK2 |= (1 << OCIE2A) | (1 << OCIE2B);
OCR2A = 255;
}
}
 
 
 
//--------------------------------------------------------------
// Sound, Timer CTC
//--------------------------------------------------------------
void Timer3_Init( void )
{
TCCR3A = 0x00; // stop
TCNT3H = 0xF8; // set count
TCNT3L = 0x00; // set count
OCR3AH = 0x07; // set compare
OCR3AL = 0xFF; // set compare
TCCR3A |= (1 << WGM31);
TCCR3B |= (1 << CS30);
TIMSK3 |= (1 << OCIE3A); // timer interrupt sources 2=t0 compare
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
#ifdef USE_SOUND
ISR(TIMER3_COMPA_vect) // Sound
{
//void timer0_comp_isr(void){
//was 8 KHz 125usec sampling rate
//now 12 KHz 83usec sampling rate
unsigned char oldfpart;
signed char fullsamp;
signed int tmp;
 
TCNT3 = 0;
 
if( generate )
{
DDRD |= (1<<DDD7); // Port aus Ausgang
oldfpart=waveptfpart; // remember fractional part
waveptfpart+=freqincfpart; // add frac part of freq inc to wave pointer
if( waveptfpart < oldfpart ) // did it walk off the end?
{
waveptipart++; // yes, bump integer part
}
waveptipart+=freqincipart; // add int part of freq increment to wave pointer
fullsamp=sindat[waveptipart]; // get 8 bit sin sample from table (signed)
tmp=fullsamp*iattenfac; // cvt 7 bit x 8 = 15 bit
OCR2A=(tmp >> 8)+128; // cvt 15 bit signed to 8 bit unsigned
}
else
{
DDRD &= ~(1 << DDD7); // Port auf Eingang, sperrt das Rauschen
}
}
#endif
 
 
 
//--------------------------------------------------------------
// Timer-Interrupt (100 Hz)
//--------------------------------------------------------------
ISR( TIMER0_COMPA_vect )
{
static uint8_t ct0 = 0;
static uint8_t ct1 = 0;
static uint8_t k_time_l = 0;
static uint8_t k_time_r = 0;
static uint8_t k_time_lr = 0;
static uint8_t k_time_rs = 0;
uint8_t i;
 
static unsigned char cnt_1ms = 1,cnt = 0;
unsigned char beeper_ein = 0;
 
 
i = key_state ^ ~KEY_PIN; // key changed ?
ct0 = ~(ct0 & i); // reset or count ct0
ct1 = ct0 ^ (ct1 & i); // reset or count ct1
i &= (ct0 & ct1); // count until roll over ?
key_state ^= i; // then toggle debounced state
key_press |= (key_state & i); // 0->1: key press detect
 
 
if( !cnt-- )
{
cnt = 9;
CountMilliseconds++;
cnt_1ms++;
}
 
 
//--------------------------------
// Key pressed -> Timer Reset
//--------------------------------
if( i!=0 ) // eine Taste wurde gedrueckt! -> Timer Rest und weiteres...
{
if( Display_on == 0 ) // ggf. Displaylicht einschalten
set_D_LIGHT();
 
Display_on = 1; // Flag Display on
timer_lcd_off = 0; // Timer Reset
timer_pkt_off = 0; // Timer Reset
}
 
 
//--------------------------------
// LCD off Timeout
// LCD ausschalten nach n Minuten
//--------------------------------
if( (Config.DisplayTimeout > 0) && (Display_on == 1) )
{
timer_lcd_off++;
if( (timer_lcd_off/(100*60)) == Config.DisplayTimeout ) // ISR laeuft mit 100Hz; umgerechnet auf Minuten
{
clr_D_LIGHT(); // Displaylicht ausschalten
Display_on = 0; // Flag Display off
}
}
 
 
//--------------------------------
// PKT off Timeout
// PKT ausschalten nach n Minuten
//--------------------------------
if( Config.PKTOffTimeout > 0 )
{
timer_pkt_off++;
if( (timer_pkt_off/(100*60)) == Config.PKTOffTimeout ) // ISR laeuft mit 100Hz; umgerechnet auf Minuten
{
WriteParameter(); // am Ende alle Parameter sichern
set_beep( 50, 0xffff, BeepNormal ); // ein Mini-Beep zum Abschied (laenger geht nicht, wahrscheinlich wegen der ISR)
clr_V_On(); // Spannung abschalten
}
}
 
 
//--------------------------------
// PKT bei Unterspannung abschalten
//--------------------------------
LipoCheck();
 
 
//--------------------------------
// Beeper
//--------------------------------
if( Config.HWBeeper==1 )
{
if( BeepTime )
{
if( BeepTime > 10 ) BeepTime -= 10;
else BeepTime = 0;
 
if( BeepTime & BeepMuster ) beeper_ein = 1;
else beeper_ein = 0;
}
else
{
beeper_ein = 0;
BeepMuster = 0xffff;
BeepPrio = BeepNormal;
}
 
if( beeper_ein == 1 ) set_BEEP();
else clr_BEEP();
}
 
 
//--------------------------------
// Sound
//--------------------------------
#ifdef USE_SOUND
if (sound_timer > 0) // Ton spielen
{
sound_timer--;
}
else
{
//TIMSK2 &= ~_BV(TOIE2); // Interrupt sperren, verhindert Störgeräusche
//TCCR2A = 0x00; //stop
generate = 0; // Sound aus
tone_handler();
if (soundpause_timer > 0)
{
soundpause_timer --; // Ton pause
}
}
#endif
 
 
//--------------------------------
// Tasten
//--------------------------------
if ((key_state & LONG_MASK) == 0) // check long key function
k_time_l = REPEAT_START; // start delay
 
if (--k_time_l == 0) // long countdown
key_long |= (key_state & LONG_MASK);
 
//------
if ((key_state & REPEAT_MASK) == 0) // check repeat function
k_time_r = 1; // kein delay
 
if (--k_time_r == 0)
{
k_time_r = REPEAT_NEXT; // repeat delay
key_rpt |= (key_state & REPEAT_MASK);
}
 
//------
if ((key_state & LONG_REPEAT_MASK) == 0) // check repeat function
k_time_lr = REPEAT_START; // start delay
 
if (--k_time_lr == 0)
{
k_time_lr = REPEAT_NEXT; // repeat delay
key_lrpt |= (key_state & LONG_REPEAT_MASK);
}
 
//------
if ((key_state & LONG_REPEAT_SP_MASK) == 0) // check repeatX function
k_time_rs = REPEAT_START; // start delay
 
 
if( --k_time_rs == 0 ) // repeat countdown
{
if( repeat_speed == 1 )
{
k_time_rs = REPEAT_SPEED_1;
key_rpts |= (key_state & LONG_REPEAT_SP_MASK);
}
else if( repeat_speed == 2 )
{
k_time_rs = REPEAT_SPEED_2;
key_rpts |= (key_state & LONG_REPEAT_SP_MASK);
}
else if( repeat_speed == 3 )
{
k_time_rs = REPEAT_SPEED_3;
key_rpts |= (key_state & LONG_REPEAT_SP_MASK);
}
}
 
 
//--------------------------------
// generische Timer
//--------------------------------
if( timer > 0 ) timer --;
if( timer1 > 0 ) timer1 --;
if( timer2 > 0 ) timer2 --;
if( timer3 > 0 ) timer3 --;
 
 
//--------------------------------
// spezielle Timer
//--------------------------------
if( timer_osd_refresh > 0 ) timer_osd_refresh--; // Timer fuer OSD-Screenrefresh (verwendet von osd.c)
if( timer_get_bldata > 0 ) timer_get_bldata--; // Timer um BL-Daten zu holen (verwendet von osd.c)
if( timer_get_tidata > 0 ) timer_get_tidata--; // Timer um Datum/Zeit vom MK zu holen (verwendet von osd.c)
if( timer_get_displaydata > 0 ) timer_get_displaydata--; // Timer um Display vom MK zu holen (verwendet von osd.c)
if( timer_mk_timeout > 0 ) timer_mk_timeout--; // verwendet u.a. von osd.c
if( abo_timer > 0 ) abo_timer --; // Timer zum anfordern neuer Abo-Datenpakete wie OSD oder BL-Daten (verwendet u.a. von osd.c)
if( timer_pktupdatecheck > 0 ) timer_pktupdatecheck--; // Timer fuer pkt.c (PKT-Update-Check) - * FUER NICHTS ANDERES! *
if( timer_nmea_timeout > 0 ) timer_nmea_timeout--; // verwendet u.a. von osd.c
 
//--------------------------------
//--------------------------------
if( Gauge_active ) // Gauge_active -> pkt.c
{
if( timer_gauge > 0 ) timer_gauge--;
if( timer_gauge==0 ) PKT_Gauge_Next();
}
 
 
//--------------------------------
// PKT Uptime Timer
//--------------------------------
timer_pkt_uptime++;
 
if( timer_pkt_uptime % 100 == 0 ) // theoretisch muesste noch die Tagesgrenze (0 Uhr) implementiert werden...
UTCTime.seconds++;
 
} // end: ISR(TIMER0_COMPA_vect)
 
 
 
 
 
//--------------------------------------------------------------
// Lowbatpin des Spannungswandlers pruefen
// LBO des LT1308 wechselt zum Ende der Batterielaufzeit haeufig seinen Zustand in der Uebergangsphase zum LowBat
// Die Akkuspannung schwankt auch abhaengig vom momentanen Stromverbrauch
//--------------------------------------------------------------
void LipoCheck( void )
{
uint8_t lcd_xpos_save;
uint8_t lcd_ypos_save;
 
 
if( WarnToggle == 1 ) // Beim ersten Auftreten Warnung ausgeben, Rythmus 5/10 Sekunden
{
set_beep( 1000, 0x0020, BeepNormal);
 
lcd_xpos_save = lcd_xpos; // innerhalb einer ISR -> LCD Screenpos muss gesichert werden!
lcd_ypos_save = lcd_ypos;
 
//lcdx_cls_row( y, mode, yoffs )
lcdx_cls_row( 0, MINVERS ,0 ); // Zeile 0 komplett invers
lcd_printp_at( 0, 0, PSTR(" ** PKT LiPo! ** "), MINVERS); // und Warn-Text ausgeben
 
lcd_xpos = lcd_xpos_save; // lcd Screenpos wieder herstellen
lcd_ypos = lcd_ypos_save;
}
 
 
if( WarnToggle == WarnTime * 100 )
WarnToggle = 0; // erstmal bis hier warnen
 
 
if( WarnToggle > 0 )
WarnToggle++; // weiter hochzaehlen
 
 
if( PINC & (1 << LowBat) ) // Kurzzeitige Unterspannung bearbeiten und Warnung ausgeben
{
WarnCount = 0;
//if (WarnCount > 0)
// WarnCount--; // Bei LIPO OK erstmal runterzaehlen, LT1308 ueberlegt sich noch genauer ob nun ok oder nicht
}
 
 
if( !(PINC & (1 << LowBat)) ) // LT1308 hat Unterspannung erkannt
{
WarnCount++; // solange LBO low ist Zähler hochzählen
if( (WarnCount == 10) && (WarnToggle == 0) ) // mit "10" etwas unempfindlicher gegen kurze Impulse machen
WarnToggle = 1; // Warnhinweis starten
}
 
 
if( WarnCount == (PoffTime * 100) )
{
set_beep( 50, 0xffff, BeepNormal ); // ein Mini-Beep zum Abschied (laenger geht nicht, wahrscheinlich wegen der ISR)
WriteParameter(); // am Ende alle Parameter sichern
clr_V_On(); // Spannung abschalten
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
//void LipoCheck_OLD( void )
//{
// if( WarnToggle == 1 ) // Beim ersten Auftreten Warnung ausgeben, Rythmus 5/10 Sekunden
// {
// set_beep ( 1000, 0x0020, BeepNormal);
// lcd_printp_at (0, 0, PSTR(" LIPO !!Warnung!! "), 2);
// }
//
// if( WarnToggle == WarnTime * 100 )
// WarnToggle = 0; // erstmal bis hier warnen
//
// if( WarnToggle > 0 )
// WarnToggle++; // weiter hochzaehlen
//
// if( PINC & (1 << LowBat) ) // Kurzzeitige Unterspannung bearbeiten und Warnung ausgeben
// {
// WarnCount = 0;
// //if (WarnCount > 0)
// // WarnCount--; // Bei LIPO OK erstmal runterzaehlen, LT1308 ueberlegt sich noch genauer ob nun ok oder nicht
// }
//
// if (!(PINC & (1 << LowBat)) ) // LT1308 hat Unterspannung erkannt
// {
// WarnCount++; // solange LBO low ist Zähler hochzählen
// if( (WarnCount == 10) && (WarnToggle == 0) ) // mit "10" etwas unempfindlicher gegen kurze Impulse machen
// WarnToggle = 1; // Warnhinweis starten
// }
//
// if( WarnCount == (PoffTime * 100) )
// {
// clr_V_On(); // Spannung abschalten
// }
//}
 
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
unsigned int SetDelay( unsigned int t )
{
return( CountMilliseconds + t + 1 );
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
char CheckDelay( unsigned int t )
{
return( ((t - CountMilliseconds) & 0x8000) >> 9 );
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Delay_ms( unsigned int w )
{
unsigned int akt;
akt = SetDelay(w);
while( !CheckDelay(akt) );
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t get_key_press( uint8_t key_mask )
{
uint8_t sreg = SREG;
 
cli(); // disable all interrupts
 
key_mask &= key_press; // read key(s)
key_press ^= key_mask; // clear key(s)
 
SREG = sreg; // restore status register
 
return key_mask;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t get_key_short( uint8_t key_mask )
{
uint8_t ret;
uint8_t sreg = SREG;
 
cli(); // disable all interrupts
 
ret = get_key_press (~key_state & key_mask);
 
SREG = sreg; // restore status register
 
return ret;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t get_key_long( uint8_t key_mask )
{
uint8_t sreg = SREG;
 
cli(); // disable all interrupts
 
key_mask &= key_long; // read key(s)
key_long ^= key_mask; // clear key(s)
 
SREG = sreg; // restore status register
 
return get_key_press (get_key_rpt (key_mask));
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t get_key_rpt( uint8_t key_mask )
{
uint8_t sreg = SREG;
 
cli(); // disable all interrupts
 
key_mask &= key_rpt; // read key(s)
key_rpt ^= key_mask; // clear key(s)
 
SREG = sreg; // restore status register
 
return key_mask;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t get_key_long_rpt( uint8_t key_mask )
{
uint8_t sreg = SREG;
 
cli(); // disable all interrupts
 
key_mask &= key_lrpt; // read key(s)
key_lrpt ^= key_mask; // clear key(s)
 
SREG = sreg; // restore status register
 
return get_key_rpt (~key_press^key_mask);
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t get_key_long_rpt_sp( uint8_t key_mask, uint8_t key_speed )
{
uint8_t sreg = SREG;
 
cli(); // disable all interrupts
 
key_mask &= key_rpts; // read key(s)
key_rpts ^= key_mask; // clear key(s)
 
repeat_speed = key_speed;
 
SREG = sreg; // restore status register
 
return key_mask;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void clear_key_all( void )
{
key_rpt = 0; // clear key(s)
key_rpts = 0; // clear key(s)
key_lrpt = 0; // clear key(s)
key_long = 0; // clear key(s)
key_press = 0; // clear key(s)
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void set_beep( uint16_t Time, uint16_t Muster, uint8_t Prio)
{
if( Config.HWBeeper == 1 )
{
if( (Prio == BeepNormal) && (BeepPrio == BeepNormal) ) // BEEPER: nur setzen wenn keine hohe Prio schon aktiv ist
{
BeepTime = Time;
BeepMuster = Muster;
}
 
if( (Prio == BeepSevere) && (!BeepPrio == BeepSevere) ) // BEEPER: hohe Prio setzen
{
BeepPrio = BeepSevere;
BeepTime = Time;
BeepMuster = Muster;
}
 
if( Prio == BeepOff )
{
BeepPrio = BeepNormal; // BEEPER: Beep hohe Prio aus
BeepTime = 0;
BeepMuster = 0;
}
} // end: if( Config.HWBeeper==1 )
 
#ifdef USE_SOUND
else
{
if( (Prio == BeepNormal) && (BeepPrio == BeepNormal) ) // SOUND: nur setzen wenn keine hohe Prio schon aktiv ist
{
playTone(900,Time/10,0);
}
 
if( (Prio == BeepSevere) && (!BeepPrio == BeepSevere) )
{
playTone(1200,Time/10,0);
playTone(1100,Time/10,0);
}
 
if( Prio == BeepOff )
{
playTone(0,0,0);
}
}
#endif // end: #ifdef USE_SOUND
}
 
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/timer/timer.h
0,0 → 1,170
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* based on the key handling by Peter Dannegger *
* see www.mikrocontroller.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY timer.h
//#
//# 08.08.2015 CB
//# - add: timer_nmea_timeout
//#
//# 24.06.2014 OG
//# - add: timer_gauge
//#
//# 13.06.2014 OG
//# - del: IdleTimer entfernt da nicht verwendet
//#
//# 31.05.2014 OG
//# - chg: 'timer_pktctrl' umbenannt zu 'timer_pktupdatecheck' (exklusiv fuer pkt.c)
//#
//# 25.04.2014 OG
//# - add: timer_get_displaydata
//#
//# 24.04.2014 OG
//# - add: timer1 (generischer Timer)
//# - add: timer3 (generischer Timer)
//# - add: timer_mk_timeout
//# - del: timer_get_erdata
//#
//# 29.03.2014 OG
//# - add: clear_key_all()
//#
//# 07.07.2013 OG
//# - chg: ABO_TIMEOUT verschoben nach main.h
//#
//# 19.05.2013 OG
//# - add: timer_pktctrl - exclusive Verwendung von pkt.c
//############################################################################
 
 
 
#ifndef _TIMER_H
#define _TIMER_H
 
#include "../cpu.h"
#include "../main.h"
 
typedef struct
{
uint32_t seconds; // seconds since nnew day
uint8_t day;
uint8_t month;
uint16_t year;
} PKTdatetime_t;
 
 
#define KEY_ALL ((1 << KEY_PLUS) | (1 << KEY_MINUS) | (1 << KEY_ENTER) | (1 << KEY_ESC))
#define LONG_MASK ((1 << KEY_PLUS) | (1 << KEY_MINUS) | (1 << KEY_ENTER) | (1 << KEY_ESC))
#define REPEAT_MASK ((1 << KEY_PLUS) | (1 << KEY_MINUS) | (1 << KEY_ENTER) | (1 << KEY_ESC))
#define LONG_REPEAT_MASK ((1 << KEY_PLUS) | (1 << KEY_MINUS) | (1 << KEY_ENTER) | (1 << KEY_ESC))
#define LONG_REPEAT_SP_MASK ((1 << KEY_PLUS) | (1 << KEY_MINUS) | (1 << KEY_ENTER) | (1 << KEY_ESC))
 
#define REPEAT_START 70 // after 700ms
#define REPEAT_NEXT 15 // every 150ms
#define REPEAT_SPEED_1 20 // every 200ms
#define REPEAT_SPEED_2 8 // every 80ms
#define REPEAT_SPEED_3 1 // every 10ms
 
#define BeepNormal 0 // Normal Beep
#define BeepSevere 1 // schwerer Fehler, Beep nicht unterbrechbar
#define BeepOff 2 // Beep aus
 
extern volatile uint8_t Display_on;
 
extern volatile PKTdatetime_t UTCTime;
 
//----------------------
// generische Timer
//----------------------
extern volatile uint16_t timer;
extern volatile uint16_t timer1;
extern volatile uint16_t timer2;
extern volatile uint16_t timer3;
 
//----------------------
// spezielle Timer
//----------------------
extern volatile uint32_t timer_pkt_uptime;
extern volatile uint16_t timer_pktupdatecheck; // verwendet von pkt.c (!EXKLUSIV! FUER NICHTS ANDERES!)
extern volatile uint16_t timer_osd_refresh;
extern volatile uint16_t timer_get_bldata;
extern volatile uint16_t timer_get_tidata;
extern volatile uint16_t timer_get_displaydata;
extern volatile uint16_t timer_mk_timeout; // verwendet u.a. in osd.c
extern volatile uint16_t timer_gauge; // verwendet in pkt.c fuer den rotierenden Wartekreisel
extern volatile uint16_t abo_timer;
extern volatile uint16_t timer_nmea_timeout; // verwendet in nmea.c
 
extern volatile uint16_t sound_timer;
extern volatile uint16_t soundpause_timer;
//extern volatile uint16_t WarnCount;
 
 
 
 
//extern volatile unsigned int BeepTime;
extern unsigned int BeepTime;
extern unsigned int BeepMuster;
 
 
/**
* Get the value of the system timer counter.
*
* @return The value of the system timer counter.
*/
uint16_t timer_get_system_count(void);
 
void Timer0_Init (void); // Systeminterrupt
void Timer1_Init (void); // Servotester
void Timer2_Init (void); // Displayhelligkeit
void Timer3_Init (void); // Überwachung
uint8_t get_key_press (uint8_t key_mask); // sofort beim drücken
uint8_t get_key_short (uint8_t key_mask); // erst beim loslassen
uint8_t get_key_long (uint8_t key_mask); // verzögert
uint8_t get_key_rpt (uint8_t key_mask); // mit verzögerung
uint8_t get_key_long_rpt (uint8_t key_mask); //
uint8_t get_key_long_rpt_sp (uint8_t key_mask, uint8_t key_speed); // mit verzögerung und 3 versch. geschw.
void clear_key_all( void );
 
void set_beep ( uint16_t Time, uint16_t Muster, uint8_t Prio);
extern volatile unsigned int CountMilliseconds;
 
 
void Delay_ms(unsigned int);
unsigned int SetDelay (unsigned int t);
char CheckDelay (unsigned int t);
void LipoCheck (void); // Lowbatpin des Spannungswandlers prüfen
 
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/tracking/ng_servo.c
0,0 → 1,236
 
/********************************************************************/
/* */
/* NG-Video 5,8GHz */
/* */
/* Copyright (C) 2011 - gebad */
/* */
/* This code is distributed under the GNU Public License */
/* which can be found at http://www.gnu.org/licenses/gpl.txt */
/* */
/* using */
/*! \file servo.c \brief Interrupt-driven RC Servo function library.*/
/* */
/*File Name : 'servo.c' */
/*Title : Interrupt-driven RC Servo function library */
/*Author : Pascal Stang - Copyright (C) 2002 */
/*Created : 7/31/2002 */
/*Revised : 8/02/2002 */
/*Version : 1.0 */
/*Target MCU : Atmel AVR Series */
/*Editor Tabs : 2 */
/* */
/*This code is distributed under the GNU Public License */
/* which can be found at http://www.gnu.org/licenses/gpl.txt */
/* */
/********************************************************************/
 
//############################################################################
//# HISTORY ng_servo.c
//#
//# 25.08.2013 Cebra
//# - add: #ifdef USE_TRACKING
//#
//# 24.04.2013 OG
//# - chg: umbenannt servo_test(void) nach _servo_test(void)
//# das verursachte in meinem PKT-Projekt Errors weil die Funktion
//# servo_test() ebenfalls ein servo.c vorhanden ist
//############################################################################
 
 
#include <avr/interrupt.h>
#include <avr/io.h>
 
#include "../tracking/ng_servo.h"
#include "../tracking/tracking.h"
#include "../HAL_HW3_9.h"
#include "../eeprom/eeprom.h"
//#include "config.h"
#ifdef USE_TRACKING
// Global variables
uint16_t ServoPosTics;
uint16_t ServoPeriodTics;
 
// servo channel registers
ServoChannelType ServoChannels[SERVO_NUM_CHANNELS];
 
const ServoConst_t ServoConst[2] = {{SERVO_MAX, SERVO_MIN, SERVO_STEPS, SERVO_PRESCALER},
{SERVO_MAX * 4, SERVO_MIN * 4, (SERVO_STEPS + 1) * 4 - 1, SERVO_PRESCALER / 4}};
 
// Servo limits (depend on hardware)
const servo_limit_t servo_limit[2][3] = {{{SERVO_I0_RIGHT_MIN, SERVO_I0_RIGHT_MAX},
{SERVO_I0_LEFT_MIN, SERVO_I0_LEFT_MAX},
{SERVO_I0_MIDDLE_MIN, SERVO_I0_MIDDLE_MAX}},
{{SERVO_I1_RIGHT_MIN, SERVO_I1_RIGHT_MAX},
{SERVO_I1_LEFT_MIN, SERVO_I1_LEFT_MAX},
{SERVO_I1_MIDDLE_MIN, SERVO_I1_MIDDLE_MAX}}};
 
// Servopositionen normiert für 950µs, 2,05ms und 1,5ms ==> Ergebnis Schritte. Da Zeit in µs ist F_CPU*e-1
const steps_pw_t steps_pw[2] = {{(uint64_t)950*F_CPU*1e-6/SERVO_PRESCALER + 0.5, (uint64_t)2050*F_CPU*1e-6/SERVO_PRESCALER + 0.5,(uint64_t)1500*F_CPU*1e-6/SERVO_PRESCALER + 0.5},
{(uint64_t)950*4*F_CPU*1e-6/SERVO_PRESCALER + 0.5, (uint64_t)2050*4*F_CPU*1e-6/SERVO_PRESCALER + 0.5, (uint64_t)1500*4*F_CPU*1e-6/SERVO_PRESCALER + 0.5}};
 
// anzufahrende Servopositionen 0=MIN, 1=MID, 2=MAX
const uint8_t PosIdx[POSIDX_MAX] = {1, 0, 1, 2 };
 
// functions
void _servo_test(void)
{
//Dummy
}
//! initializes software PWM system 16-bit Timer
// normaler Weise wird ein Serv-PWM Signal aller 20ms wiederholt
// Werte: rev, min, max, mid vorher über servoSet...() initialisieren und einmal servoSetPosition(...) ausführen!!!
void servoInit(uint8_t servo_period)
{ uint16_t OCValue; // set initial interrupt time
 
 
 
 
// disble Timer/Counter1, Output Compare A Match Interrupt
TIMSK1 &= ~(1<<OCIE1A);
// set the prescaler for timer1
if (Config.sIdxSteps == STEPS_255) {
TCCR1B &= ~((1<<CS11) | (1<<CS10));
TCCR1B |= (1<<CS12); // prescaler 256, Servo-Schritte 185 bei 180 grd Winkel
}
else {
TCCR1B &= ~(1<<CS12);
TCCR1B |= (1<<CS11) | (1<<CS10); // prescaler 64, Servo-Schritte 740 bei 180 grd Winkel
}
// attach the software PWM service routine to timer1 output compare A
// timerAttach(TIMER1OUTCOMPAREA_INT, servoService);
// enable channels
for(uint8_t channel=0; channel < SERVO_NUM_CHANNELS; channel++) {
// set default pins assignments SERVO2 Pin 4; SERVO1 Pin 5
ServoChannels[channel].pin = (1 << (SERVO2 + channel));
}
ServoPosTics = 0; // set PosTics
// set PeriodTics
ServoPeriodTics = F_CPU / ServoConst[Config.sIdxSteps].prescaler * servo_period * 1e-3;
// read in current value of output compare register OCR1A
OCValue = OCR1AL; // read low byte of OCR1A
OCValue += (OCR1AH << 8); // read high byte of OCR1A
OCValue += ServoPeriodTics; // increment OCR1A value by nextTics
// set future output compare time to this new value
OCR1AH = OCValue >> 8; // write high byte
OCR1AL = OCValue & 0x00FF; // write low byte
TIMSK1 |= (1<<OCIE1A); // enable the timer1 output compare A interrupt
coldstart = 1;
}
 
void servoSetDefaultPos(void)
{
servoSetPosition(SERVO_PAN, ServoSteps()); // Ausgangsstellung SERVO_PAN
servoSetPosition(SERVO_TILT,ServoSteps()); // Ausgangsstellung SERVO_TILT
}
 
uint16_t pw_us(uint16_t Steps)
{
return(Steps * ServoConst[Config.sIdxSteps].prescaler/(F_CPU * 1e-6) + 0.5); // Zeit pro Schritt (Wert * e-1) in µs
}
 
uint16_t ServoSteps(void)
{
return(ServoConst[Config.sIdxSteps].steps);
}
 
void servoSet_rev(uint8_t channel, uint8_t val)
{
ServoChannels[channel].rev = val & 0x01;
}
 
void servoSet_min(uint8_t channel, uint16_t min)
{
ServoChannels[channel].min = ServoConst[Config.sIdxSteps].min + min;
}
 
void servoSet_max(uint8_t channel, uint16_t max)
{
ServoChannels[channel].max = ServoConst[Config.sIdxSteps].max - max;
}
 
void servoSet_mid(uint8_t channel, uint16_t mid)
{
ServoChannels[channel].mid = mid;
// Faktor 16, bzw. 16/2 um mit einer Nachkommastelle zu Rechnen
ServoChannels[channel].mid_scaled = (8 * (ServoChannels[channel].max - ServoChannels[channel].min) + \
(16 * mid - 8 * ServoConst[Config.sIdxSteps].steps))/16 + ServoChannels[channel].min;
}
 
//! turns off software PWM system
void servoOff(void)
{
// disable the timer1 output compare A interrupt
TIMSK1 &= ~(1<<OCIE1A);
}
 
//! set servo position on channel (raw unscaled format)
void servoSetPositionRaw(uint8_t channel, uint16_t position)
{
// bind to limits
if (position < ServoChannels[channel].min) position = ServoChannels[channel].min;
if (position > ServoChannels[channel].max) position = ServoChannels[channel].max;
// set position
ServoChannels[channel].duty = position;
}
 
//! set servo position on channel
// input should be between 0 and ServoSteps() (entspricht Maximalausschlag)
void servoSetPosition(uint8_t channel, uint16_t position)
{ uint16_t pos_scaled;
// calculate scaled position
if (ServoChannels[channel].rev != 0) position = ServoConst[Config.sIdxSteps].steps - position;
if (position < ServoConst[Config.sIdxSteps].steps/2)
//bei Position < Servomittelstellung Position*(Mitte - Min)/(Servoschritte/2)
pos_scaled = ServoChannels[channel].min + ((int32_t)position*2*(ServoChannels[channel].mid_scaled-ServoChannels[channel].min))/ \
ServoConst[Config.sIdxSteps].steps;
else
//bei Position >= Servomittelstellung
pos_scaled = ServoChannels[channel].mid_scaled + (uint32_t)(position - ServoConst[Config.sIdxSteps].steps / 2) \
* 2 * (ServoChannels[channel].max-ServoChannels[channel].mid_scaled)/ServoConst[Config.sIdxSteps].steps;
// set position
servoSetPositionRaw(channel, pos_scaled);
}
 
// Umrechnung Winkel in Servoschritte
void servoSetAngle(uint8_t servo_nr, int16_t angle)
{
servoSetPosition(servo_nr, (uint16_t)((uint32_t)angle * ServoConst[Config.sIdxSteps].steps / 180));
}
 
//Interruptroutine
ISR(TIMER1_COMPA_vect)
{ static uint8_t ServoChannel;
uint16_t nextTics;
uint16_t OCValue; // schedule next interrupt
 
if(ServoChannel < SERVO_NUM_CHANNELS) {
PORTD &= ~ServoChannels[ServoChannel].pin; // turn off current channel
}
ServoChannel++; // next channel
if(ServoChannel != SERVO_NUM_CHANNELS) {
// loop to channel 0 if needed
if(ServoChannel > SERVO_NUM_CHANNELS) ServoChannel = 0;
// turn on new channel
PORTD |= ServoChannels[ServoChannel].pin;
// schedule turn off time
nextTics = ServoChannels[ServoChannel].duty;
}
else {
// ***we could save time by precalculating this
// schedule end-of-period
nextTics = ServoPeriodTics-ServoPosTics;
}
// read in current value of output compare register OCR1A
OCValue = OCR1AL; // read low byte of OCR1A
OCValue += (OCR1AH <<8); // read high byte of OCR1A
OCValue += nextTics; // increment OCR1A value by nextTics
// set future output compare time to this new value
OCR1AH = OCValue >> 8; // write high byte
OCR1AL = OCValue & 0x00FF; // write low byte
 
ServoPosTics += nextTics; // set our new tic position
if(ServoPosTics >= ServoPeriodTics) ServoPosTics = 0;
}
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/tracking/ng_servo.h
0,0 → 1,190
/*********************************************************************/
/* */
/* NG-Video 5,8GHz */
/* */
/* Copyright (C) 2011 - gebad */
/* */
/* This code is distributed under the GNU Public License */
/* which can be found at http://www.gnu.org/licenses/gpl.txt */
/* */
/* using */
/*! \file servo.c \brief Interrupt-driven RC Servo function library. */
/* */
/*File Name : 'servo.c' */
/*Title : Interrupt-driven RC Servo function library */
/*Author : Pascal Stang - Copyright (C) 2002 */
/*Created : 7/31/2002 */
/*Revised : 8/02/2002 */
/*Version : 1.0 */
/*Target MCU : Atmel AVR Series */
/*Editor Tabs : 4 */
/* */
/*ingroup driver_sw */
/*defgroup servo Interrupt-driven RC Servo Function Library (servo.c)*/
/*code #include "servo.h" \endcode */
/*par Overview */
/* */
/*This code is distributed under the GNU Public License */
/*which can be found at http://www.gnu.org/licenses/gpl.txt */
/* */
/*********************************************************************/
 
#ifndef SERVO_H
#define SERVO_H
 
 
/* Servo */
#define SERVO_PAN 0
#define SERVO_TILT 1
#define SERVO_NUM_CHANNELS 2 // Anzahl der angeschlossen Servos max. 2!!!
/* Servokalibrierungen derzeit zu SERVO_STEPS = 255 skaliert */
//prescaler 256
#define SERVO_I0_RIGHT 45 // default Wert, ca. 0,9ms
#define SERVO_I0_RIGHT_MIN 0 // Servokalibrierung Grenze der linken Position
#define SERVO_I0_RIGHT_MAX 100 // SERVO_MIN + SERVO_RIGHT
 
#define SERVO_I0_LEFT 45 // default Wert, ca. 2,1ms
#define SERVO_I0_LEFT_MIN 0 // Servokalibrierung Grenze der rechten Position
#define SERVO_I0_LEFT_MAX 100 // SERVO_MAX - SERVO_LEFT
 
#define SERVO_I0_MIDDLE SERVO_STEPS/2
#define SERVO_I0_MIDDLE_MIN SERVO_STEPS/2 - 25
#define SERVO_I0_MIDDLE_MAX SERVO_STEPS/2 + 25
//prescaler 64
#define SERVO_I1_RIGHT 180 // default Wert, ca. 0,9ms
#define SERVO_I1_RIGHT_MIN 0 // Servokalibrierung Grenze der linken Position
#define SERVO_I1_RIGHT_MAX 400 // SERVO_MIN + SERVO_RIGHT
 
#define SERVO_I1_LEFT 180 // default Wert, ca. 2,1ms
#define SERVO_I1_LEFT_MIN 0 // Servokalibrierung Grenze der rechten Position
#define SERVO_I1_LEFT_MAX 400 // SERVO_MAX - SERVO_LEFT
 
//#define SERVO_I1_MIDDLE ((SERVO_STEPS + 1) * 4 - 1)/2
#define SERVO_I1_MIDDLE_MIN ((SERVO_STEPS + 1) * 4 - 1)/2 - 100
#define SERVO_I1_MIDDLE_MAX ((SERVO_STEPS + 1) * 4 - 1)/2 + 100
 
#define SERVO_REV 0 // kein Reverse
/* Test Servo */
#define SERVO_PERIODE 20 // default Angabe in ms
#define SERVO_PERIODE_MIN 10 // 10ms
#define SERVO_PERIODE_MAX 30 // 30ms
#define SINGLE_STEP 0 // Einzelschritt aus
#define SINGLE_STEP_MIN 0
#define SINGLE_STEP_MAX 20 // bei prescaler 256, sonst * 4 (von links nach rechts in 9 Abschnitte)
// zwischen den Schritten muss Pause > der Servoperiode sein, sonst keine Aktualisierung
 
#define REPEAT 1
#define REPEAT_MIN 1
#define REPEAT_MAX 100
#define PAUSE 10
#define PAUSE_MIN 4 // mindestens 400ms, da mechanischer Servo-Lauf zur Position berücksichtigt werden muss
#define PAUSE_MAX 20 // Pause pro Links-, Mittel- und Rechtsposition 10*100ms
#define PAUSE_STEP 0
#define PAUSE_STEP_MIN 0 // Pause bei jeden Servoschritt in ms
#define PAUSE_STEP_MAX 200
// The numbers below good for parallax servos at an F_CPU of 20.000MHz.
// Da einige Servo's auch eien Winkel von 180 grd zulassen, Wertebereich
// entgegen den sonst üblichen. Einschränkung mit default Kalibrierung
// auf 0,9ms (45) bis 2,1ms(45) gesetzt. Je nach Servo, entspricht einen
// Winkel von etwa 180grd
// Periode default 20ms
 
#define SERVO_MAX 211 // 2,7 ms bei prescaler 256, bei prescaler 64 SERVO_MAX * 4
#define SERVO_MIN 26 // 0,33ms bei prescaler 256, bei prescaler 64 SERVO_MIN * 4
#define SERVO_STEPS 255 // Servo-Schritte von links nach rechts, Anschlagkalibrierung spielt keine Rolle
#define SERVO_PRESCALER 256 // bei prescaler 256, bei prescaler 64 SERVO_PRESCALER / 4
#define STEPS_255 0 // Servo-Schritte von links nach rechts, Anschlagkalibrierung spielt keine Rolle
#define STEPS_1023 1 // Servo-Schritte von links nach rechts, Anschlagkalibrierung spielt keine Rolle
 
typedef struct //Servo-Konstante je nach Prescaler
{
uint16_t max;
uint16_t min;
uint16_t steps;
uint16_t prescaler;
}ServoConst_t;
 
typedef struct //struct_ServoChannel
{
uint8_t pin; // hardware I/O port and pin for this channel
uint16_t duty; // PWM duty setting which corresponds to servo position
uint8_t rev; // Parameter, wie on/off; reverse; range
uint16_t min; // SERVO_MIN + Parameter min
uint16_t max; // SERVO_MAX - Parameter max
uint16_t mid_scaled; // skalierte Servomitte
int16_t mid; // Servomitte = SERVO_STEPS/2 +/- x Schritte; bei Pescaler 256 wird nur uint8_t benötigt aber bei 64
}ServoChannelType;
 
//uint8_t sIdxSteps; // 0 für 255 und 1 für 1023 Schritte; Prescaler 256 oder 64
 
// Define servo limits (depend on hardware)
typedef struct {
uint16_t min;
uint16_t max;
}servo_limit_t;
 
extern const servo_limit_t servo_limit[2][3];
 
// Define servo positions (depend on hardware)
typedef struct {
uint16_t min;
uint16_t max;
uint16_t mid;
}steps_pw_t;
 
 
typedef struct {
uint8_t rev;
uint16_t min;
uint16_t max;
uint16_t mid;
} servo_t;
 
// Servopositionen für 950µs, 2,05ms und 1,5ms ==> Ergebnis Schritte. Da Zeit in µs ist F_CPU*e-1
extern const steps_pw_t steps_pw[2];
 
#define RIGHT 0 // Servopostionen, welche vom Einbau abhängig sind
#define LEFT 1
#define MIDDLE 2
 
#define POSIDX_MAX 4
extern const uint8_t PosIdx[POSIDX_MAX]; // anzufahrende Servopositionen 0=MIN, 1=MID, 2=MAX
 
// functions
 
 
void servoSetDefaultPos(void);
 
// initializes servo system
// You must run this to begin servo control
void servoInit(uint8_t servo_period);
 
// turns off servo system
// This stops controlling the servos and
// returns control of the SERVOPORT to your code
void servoOff(void);
 
// set servo position on a given channel
// servoSetPosition() commands the servo on <channel> to the position you
// desire. The position input must lie between 0 and POSITION_MAX and
// will be automatically scaled to raw positions between SERVO_MIN and
// SERVO_MAX
void servoSetPosition(uint8_t channel, uint16_t position);
 
// set raw servo position on a given channel
// Works like non-raw commands but position is not scaled. Position must
// be between SERVO_MIN and SERVO_MAX
void servoSetPositionRaw(uint8_t channel, uint16_t position);
 
// set servo to a specific angle
void servoSetAngle(uint8_t servo_nr, int16_t angle);
 
// vor servoInit(), oder vor sei() ServoWerte mit servoSet...() initialisieren, einschließlich servoSetPosition(...)!
void servoSet_rev(uint8_t channel, uint8_t val);
void servoSet_min(uint8_t channel, uint16_t min);
void servoSet_max(uint8_t channel, uint16_t max);
void servoSet_mid(uint8_t channel, uint16_t mid);
uint16_t pw_us(uint16_t Steps); // gibt Zeit in µs bei x Servoschritte
uint16_t ServoSteps(void); // gibt "Konstante" derzeitiger Servoschritte zürück
 
#endif /* SERVO_H */
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/tracking/servo_setup.c
0,0 → 1,1577
 
/****************************************************************/
/* */
/* NG-Video 5,8GHz */
/* */
/* Copyright (C) 2011 - gebad */
/* */
/* This code is distributed under the GNU Public License */
/* which can be found at http://www.gnu.org/licenses/gpl.txt */
/* */
/****************************************************************/
 
//############################################################################
//# HISTORY servo_setup.c
//#
//# 27.06.2014 OG
//# - del: #include "tools.h"
//# - del: #include "mymath.h"
//#
//# 30.05.2014 OG
//# - chg: etliche Edit-Anzeigen/Funktionen auf neues Layout umgeschrieben;
//# einige Optimierungen an Aufruffunktionen (unnoetige Menue-
//# Interfacefunktionen entfernt)
//#
//# 13.05.2014 OG
//# - chg: Menu_Test_Start() - Variable 'range' auskommentiert
//# wegen Warning: variable set but not used
//# - chg: Displ_PulseWidth() - Variable 'me' auskommentiert
//# wegen Warning: variable set but not used
//# - chg: Change_Value_plmi() - Variable 'tmp_val' entfernt
//# wegen Warning: variable set but not used
//#
//# 11.05.2014 OG
//# - chg: einge Setup-Menues umgestellt auf MenuCtrl_SetTitleFromParentItem()
//# -> die Menues 'erben' damit ihren Titel vom aufrufenden Menuepunkt
//#
//# 30.03.2014 OG
//# - chg: ein paar englische Texte auf DE gemappt weil der Unterschied unerheblich war
//# - chg: Sprache Hollaendisch vollstaendig entfernt
//# - chg: MenuCtrl_PushML_P() umgestellt auf MenuCtrl_PushML2_P()
//#
//# 25.08.2013 Cebra
//# - add: #ifdef USE_TRACKING
//#
//# 30.05.2013 cebra
//# - chg: doppelte Texte auf #define umgestellt
//#
//# 24.05.2013 OG
//# - chg: Aufrufe von MenuCtrl_Push() umgestellt auf MenuCtrl_PushML_P()
//#
//# 22.05.2013 OG
//# - umgestellt auf menuctrl: Setup_ServoTracking(), Setup_ServoTest(),
//# Setup_ServoTestCont(), Setup_ServoAdjust()
//# - del: include utils/menuold.h
//#
//# 17.05.2013 OG
//# - chg: umgestellt auf utils/menuold.h
//#
//# 16.04.2013 Cebra
//# - chg: PROGMEM angepasst auf neue avr-libc und GCC, prog_char depreciated
//#
//# 04.04.2013 Cebra
//# - chg: Texttuning
//#
//# 03.04.2013 Cebra
//# - chg: Holländische Menütexte
//#
//# 27.03.2013 Cebra
//# - chg: Fehler bei der Men�steuerung behoben
//############################################################################
 
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include "../cpu.h"
#include <util/delay.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include "../main.h"
#include "../timer/timer.h"
#include "servo_setup.h"
#include "tracking.h"
#include "../lcd/lcd.h"
#include "../timer/timer.h"
#include "../menu.h"
#include "../messages.h"
#include "../mk-data-structs.h"
#include "../uart/usart.h"
#include "../osd/osd.h"
#include "../eeprom/eeprom.h"
#include "../setup/setup.h"
#include "../utils/menuctrl.h"
#include "../pkt/pkt.h"
 
 
#ifdef USE_TRACKING
 
 
//#include "ng_usart.h"
//#include "ng_config.h"
//#include "servo.h"
//#include "tools.h"
//#include "mk.h"
//#include "keys.h"
//#include "mymath.h"
//
 
//GPS_Pos_t last5pos[7];
//uint8_t error1 = 0;
//NaviData_t *naviData;
//HomePos_t MK_pos; // Home position of station
//GPS_Pos_t currentPos; // Current position of flying object
//int8_t satsInUse; // Number of satelites currently in use
 
//uint8_t tracking = TRACKING_MIN;
//uint8_t track_hyst = TRACKING_HYSTERESE;
//uint8_t track_tx = 0;
 
//geo_t geo;
//int16_t anglePan, angleTilt; // Servo Winkel
//uint8_t coldstart = 1;
 
uint8_t servo_nr; // zwischen Servo 1 und 2 wird nur mit global servo_nr unterschieden
//uint8_t FCStatusFlags;
 
 
//############################################################################
 
//-----------------------------
// Setup_ServoTracking()
//-----------------------------
#define MSERVO_STEPS 1
#define MSERVO_SERVO1 2
#define MSERVO_SERVO2 3
#define MSERVO_SERVOTEST 4
 
static const char MSERVO_STEPS_de[] PROGMEM = "Servoschritte";
static const char MSERVO_STEPS_en[] PROGMEM = "servo steps";
 
static const char MSERVO_SERVO1_de[] PROGMEM = "Servo 1";
#define MSERVO_SERVO1_en MSERVO_SERVO1_de
 
static const char MSERVO_SERVO2_de[] PROGMEM = "Servo 2";
#define MSERVO_SERVO2_en MSERVO_SERVO2_de
 
static const char MSERVO_SERVOTEST_de[] PROGMEM = "Servotest";
#define MSERVO_SERVOTEST_en MSERVO_SERVOTEST_de
 
 
//############################################################################
 
//-----------------------------
// Setup_ServoTest()
//-----------------------------
#define MSERVOT_PULS 1
#define MSERVOT_CONT 2
#define MSERVOT_SERVO 3
#define MSERVOT_FRAME 4
 
static const char MSERVOT_PULS_de[] PROGMEM = "Test Pulslänge";
static const char MSERVOT_PULS_en[] PROGMEM = "test puls width";
 
static const char MSERVOT_CONT_de[] PROGMEM = "Test Fortlfd.";
static const char MSERVOT_CONT_en[] PROGMEM = "test cont.";
 
static const char MSERVOT_SERVO_de[] PROGMEM = "Servo";
#define MSERVOT_SERVO_en MSERVOT_SERVO_de
 
static const char MSERVOT_FRAME_de[] PROGMEM = "Periode";
static const char MSERVOT_FRAME_en[] PROGMEM = "frame";
 
//############################################################################
 
//-----------------------------
// Setup_ServoTestCont()
//-----------------------------
#define MSERVOTC_START 1
#define MSERVOTC_SINGLE 2
#define MSERVOTC_COUNT 3
#define MSERVOTC_PAUSEEND 4
#define MSERVOTC_PAUSEINC 5
 
static const char MSERVOTC_START_de[] PROGMEM = "Start Test";
static const char MSERVOTC_START_en[] PROGMEM = "start test";
 
static const char MSERVOTC_SINGLE_de[] PROGMEM = "Einzelschritt";
static const char MSERVOTC_SINGLE_en[] PROGMEM = "single step";
 
static const char MSERVOTC_COUNT_de[] PROGMEM = "Anzahl Test";
static const char MSERVOTC_COUNT_en[] PROGMEM = "number of test";
 
static const char MSERVOTC_PAUSEEND_de[] PROGMEM = "Pause Endpos.";
static const char MSERVOTC_PAUSEEND_en[] PROGMEM = "pause end pos";
 
static const char MSERVOTC_PAUSEINC_de[] PROGMEM = "Pause pro Inc.";
static const char MSERVOTC_PAUSEINC_en[] PROGMEM = "pause proc inc.";
 
//############################################################################
 
//-----------------------------
// Setup_ServoAdjust()
//-----------------------------
#define MSERVOADJ_REV 1
#define MSERVOADJ_LEFT 2
#define MSERVOADJ_RIGHT 3
#define MSERVOADJ_MID 4
 
static const char MSERVOADJ_REV_de[] PROGMEM = "Reverse";
static const char MSERVOADJ_REV_en[] PROGMEM = "reverse";
 
static const char MSERVOADJ_LEFT_de[] PROGMEM = "Links";
static const char MSERVOADJ_LEFT_en[] PROGMEM = "left";
 
static const char MSERVOADJ_RIGHT_de[] PROGMEM = "Rechts";
static const char MSERVOADJ_RIGHT_en[] PROGMEM = "right";
 
static const char MSERVOADJ_MID_de[] PROGMEM = "Mitte";
static const char MSERVOADJ_MID_en[] PROGMEM = "middle";
 
//############################################################################
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void draw_input_screen( void )
{
lcd_cls ();
PKT_TitleFromMenuItem( true );
lcdx_printf_at_P( 0, 2, MNORMAL, 0,0, PSTR("%S:"), MenuCtrl_GetItemText() ); // Menuetext muss im PGM sein! (aktuell keine Unterscheidung RAM/PGM)
lcd_printp_at(0, 7, strGet(KEYLINE2), MNORMAL);
}
 
 
 
///************************************************************************************/
///* */
///* �ndern der Werte mit Tasten +,- und Anzeige */
///* z.B. f�r U-Offset, Batterie leer Eingabe ... */
///* */
///* Parameter: */
///* uint16_t val :zu �ndernter Wert */
///* uint16_t min_val, max_val :min, max Grenze Wert �ndern darf */
///* uint8_t posX, posY :Darstellung Wert xPos, YPos auf LCD */
///* Displ_Fnct_t Displ_Fnct :Index um variable Display Funktion aufzurufen */
///* uint8_t cycle :0 begrenzt Anzeige bei man_val, bzw. max_val */
///* :1 springt nach max_val auf min_val und umgedreht */
///* uint8_t vrepeat :beschleunigte Repeat-Funktion aus/ein */
///* uint16_t Change_Value_plmi(...) :R�ckgabe ge�nderter Wert */
///* */
///************************************************************************************/
 
void Servo_tmp_Original(uint8_t track)
{
servoSetDefaultPos();
// tracking = track; // urspr�nglicher Wert Tracking aus, RSSI oder GPS
// NoTracking_ServosOff(); // Servos sind nur zum Tracking oder bei Kalibrierung eingeschaltet
// Jump_Menu(pmenu);
}
 
uint8_t Servo_tmp_on(uint8_t servo_period)
{
// uint8_t tmp_tracking = tracking;
 
// tracking = 0; // Servopositionierung durch tracking abschalten
// if (tracking == TRACKING_MIN) servoInit(servo_period); // falls aus, Servos einschalten
servoInit(servo_period);
// lcdGotoXY(0, 0); // lcd Cursor vorpositionieren
// return(tmp_tracking);
return (0);
}
 
 
void Displ_Off_On(uint16_t val)
{
if (val == 0) lcd_printp_at(17, 2, strGet(OFF), 0); else lcd_printp_at(17, 2, strGet(ON), 0);
}
 
 
 
uint16_t Change_Value_plmi(uint16_t val, uint16_t min_val, uint16_t max_val, uint8_t posX, uint8_t posY,Displ_Fnct_t Displ_Fnct)
{
// >> Menueauswahl nach oben
 
if (get_key_press (1 << KEY_PLUS) || get_key_long_rpt_sp ((1 << KEY_PLUS), 3))
{
if (val < max_val) {
edit = 1;
val++;
 
}
else
{
val = min_val;
}
Displ_Fnct(val); // ge�nderten Wert darstellen, je nach Men�punkt
 
 
}
// >> Menueauswahl nach unten
 
if (get_key_press (1 << KEY_MINUS) || get_key_long_rpt_sp ((1 << KEY_MINUS), 3))
{
if (val > min_val) {
val--;
edit = 1;
 
}
else
{
val = max_val;
}
Displ_Fnct(val); // ge�nderten Wert darstellen, je nach Men�punkt
 
 
}
 
return(val);
}
//
///************************************************************************************/
///* */
///* �ndern der Werte mit Tasten +,- repetierend; (long)Entertaste und Anzeige */
///* z.B. f�r U-Offset, Batterie leer Eingabe ... */
///* */
///* Parameter: */
///* uint16_t *val :zu �ndernter Wert */
///* uint16_t min_val, max_val :min, max Grenze Wert �ndern darf */
///* uint8_t fl_pos :Bit 7 beschleunigte Repeat-Funktion aus/ein */
///* Bit 6 zyklische Werte�nderung aus/ein */
///* Bit 4-5 z.Z. ohne Funktion */
///* Bit 0-3 Wert xPos auf LCD */
///* Displ_Fnct_t Displ_Fnct :Index um variable Display Funktion aufzurufen */
///* uint8_t Change_Value(...) :R�ckgabe ge�ndert ergibt TRUE */
///* */
///************************************************************************************/
//// Bei Bedarf k�nnte einfach innerhalp fl_pos auch noch pos_y (Bit 4-5) �bergeben werden
uint8_t Change_Value(uint16_t *val, uint16_t min_val, uint16_t max_val,Displ_Fnct_t Displ_Fnct)
{
uint16_t tmp_val;
 
tmp_val = *val;
Displ_Fnct(tmp_val); // initiale Wertdarstellung, je nach Men�punkt
while(!get_key_press(1<<KEY_ENTER) && !get_key_press(1<<KEY_ESC))
*val = Change_Value_plmi(*val, min_val, max_val, 16,2, Displ_Fnct);
 
 
if (*val == tmp_val) {
edit = 0;
// lcd_printp_at (0, 5, PSTR("Edit=0"), 0);
// _delay_ms(500);
//// return (*val);
}
//
else
{
edit = 1;
// lcd_printp_at (0, 5, PSTR("Edit=1"), 0);
// _delay_ms(500);
}
 
return (tmp_val != *val);
 
 
}
 
uint16_t calc_range(int16_t PosProzent, int16_t min, int16_t max, int16_t mid)
{ uint16_t range;
 
if (PosProzent < 0) {
range = mid - min;
// if (chrxs == CHRRS) { // falls Richtung ge�ndert, anderen Zeichensatz laden
// chrxs = CHRLS;
//// lcdWriteCGRAM_Array(lcdSpecialChrLs, 5);// LCD-Char mit Rahmensymbole vom Graph
// }
}
else {
range = max - mid;
// if (chrxs == CHRLS) { // falls Richtung ge�ndert, anderen Zeichensatz laden
//// lcdWriteCGRAM_Array(lcdSpecialChrRs, 5);// LCD-Char mit Rahmensymbole vom Graph
// chrxs = CHRRS;
// }
}
return(range);
}
 
 
 
/************************************************************************************/
/* zeigt einen max. 3-stelligen Integerwert auf Display an */
/* Parameter: */
/* uint16_t val :anzuzeigender Wert, */
/* uint16_t wegen Vereinheitlichung f. Funktionsaufrauf */
/* */
/************************************************************************************/
void Displ_Format_Int( uint16_t val )
{
lcdx_printf_at_P( 17, 2, MNORMAL, 0,0, PSTR("%3d"), val );
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Displ_PulseWidth( uint16_t val )
{
int16_t PosProzent, range;
 
servoSetPositionRaw( servo_nr, val);
 
PosProzent = val - steps_pw[Config.sIdxSteps].mid;
range = calc_range(PosProzent, steps_pw[Config.sIdxSteps].min, steps_pw[Config.sIdxSteps].max, steps_pw[Config.sIdxSteps].mid);
PosProzent = (int32_t)1000 * PosProzent / range;
 
lcdx_printf_at_P( 15, 2, MNORMAL, 0,0, PSTR("%4.1d"), PosProzent );
}
 
 
 
/************************************************************************************/
/* zeigt Pausenl�nge der Links-, Mittel- und Rechtsposition auf Display an */
/* Parameter: */
/* uint16_t val : Zeit in 1ms * 100 */
/* */
/************************************************************************************/
void Displ_Pause(uint16_t val)
{
lcdx_printf_at_P( 17, 2, MNORMAL, 0,0, PSTR("%1.1d"), val );
//lcdPuts("s ");
}
 
 
 
/************************************************************************************/
/* zeigt aus oder Integerwert auf Display an */
/* Parameter: */
/* uint16_t val : val = 0 ==> aus, sont Integerwert */
/* */
/************************************************************************************/
void Displ_Off_Format_Int( uint16_t val )
{
if( val == 0 )
{
lcd_printp_at( 17, 2, strGet(OFF), MNORMAL);
}
else
{
Displ_Format_Int( val );
}
}
 
 
 
/************************************************************************************/
/* zeigt aus oder Pausenzeit zwischen 2 Servoschritte auf Display an */
/* Parameter: */
/* uint16_t val : val = 0 ==> aus, sont Integerwert */
/* */
/************************************************************************************/
void Displ_Pause_Step( uint16_t val )
{
Displ_Off_Format_Int( val );
}
 
 
 
/************************************************************************************/
/* zeigt zu testende Servonummer zur Auswahl auf Display an */
/* Parameter: */
/* uint16_t val :0 = Servo 1 oder 1 = Servo 2, */
/* uint16_t wegen Vereinheitlichung f. Funktionsaufrauf */
/* */
/************************************************************************************/
void Displ_ServoNr( uint16_t val )
{
Displ_Format_Int( val+1 );
}
 
 
 
/**************************/
/* */
/* Servos-Tests */
/* */
/**************************/
//void Menu_Servo_Test(void)
//{ uint8_t scr_sub_menu[SCROLL_MAX_6] = {SCROLL_MAX_6 - 2, MSG_RETURN, MSG_PULSE_WIDTH, MSG_CONTINOUS, MSG_SERVO, MSG_FRAME};
//
// Scroll_Menu(scr_sub_menu, m_pkt); // pmenu global
// servo_nr = eeprom_read_byte(&ep_servo_nr);
// Jump_Menu(pmenu);
//}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Menu_Test_Frame( void )
{
uint16_t tmp_val;
 
draw_input_screen();
 
tmp_val = Config.servo_frame;
if( Change_Value( &tmp_val, SERVO_PERIODE_MIN, SERVO_PERIODE_MAX, Displ_Format_Int) )
{
Config.servo_frame = tmp_val;
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Menu_Test_ServoNr( void )
{
uint16_t tmp_val;
 
draw_input_screen();
 
tmp_val = servo_nr;
 
if( Change_Value( &tmp_val, 0, 1, Displ_ServoNr) )
{ // pmenu global; es gibt nur 0=Servo1, 1=Servo2
servo_nr = tmp_val;
}
}
 
 
 
//--------------------------------------------------------------
// Dieser Test im raw-Modus ohne Anschlagkalibrierung (normiert) z.B.: f�r Modelleinstellungen ohne Empf�nger
//--------------------------------------------------------------
void Menu_Test_PulseWidth( void )
{
uint8_t tmp_tracking;
uint16_t tmp_val;
 
draw_input_screen();
 
// 30.05.2014 OG: macht dieser Code Sinn?
// Change_Value() -> 'tmp_val' und 'tmp_val' ist local - was soll mir das sagen?
 
tmp_tracking = Servo_tmp_on(Config.servo_frame);
tmp_val = steps_pw[Config.sIdxSteps].mid;
Change_Value( &tmp_val, steps_pw[Config.sIdxSteps].min, steps_pw[Config.sIdxSteps].max, Displ_PulseWidth); // pmenu global
cli();
servoInit( SERVO_PERIODE );
sei();
Servo_tmp_Original(tmp_tracking);
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Menu_Test_SingleStep(void)
{
uint16_t tmp_val;
 
draw_input_screen();
 
tmp_val = Config.single_step;
 
if( Change_Value( &tmp_val, SINGLE_STEP_MIN, SINGLE_STEP_MAX, Displ_Off_Format_Int) )
{ // pmenu global
Config.single_step = tmp_val;
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Menu_Test_Repeat( void )
{
uint16_t tmp_val;
 
draw_input_screen();
 
tmp_val = Config.repeat;
 
if( Change_Value( &tmp_val, REPEAT_MIN, REPEAT_MAX, Displ_Format_Int) )
{
Config.repeat = tmp_val;
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Menu_Test_Pause( void )
{
uint16_t tmp_val;
 
draw_input_screen();
 
tmp_val = Config.pause;
 
if( Change_Value( &tmp_val, PAUSE_MIN, PAUSE_MAX, Displ_Pause) )
{
Config.pause = tmp_val;
}
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Menu_Test_Pause_Step( void )
{
uint16_t tmp_val;
 
draw_input_screen();
 
tmp_val = Config.pause_step;
 
if( Change_Value( &tmp_val, PAUSE_STEP_MIN, PAUSE_STEP_MAX, Displ_Pause_Step) )
{
Config.pause_step = tmp_val;
}
}
 
 
 
int8_t calc_dir(uint8_t idx, int16_t *Position)
{ uint8_t nextIdx;
int8_t nextDir = 1;
 
nextIdx = idx;
if ((idx + 1) < POSIDX_MAX)
nextIdx++;
else
nextIdx = 0;
if (Position[PosIdx[idx]] > Position[PosIdx[nextIdx]]) nextDir = -1;
return(nextDir);
}
 
 
 
void Displ_LoopCounter( uint8_t val )
{
lcdx_printf_at_P( 16, 2, MNORMAL, 0,0, PSTR("%4d"), val );
//lcd_puts_at(16,2,my_itoa(val, 4, 0, 0),0);
}
 
 
 
 
// Test �ber Scalierung der Servos mit Anschlagkalibrierung
void Menu_Test_Start(void)
{
uint8_t tmp_tracking, idx, rep;
int8_t dir;
int16_t sPos;
int16_t Position[3];
//int16_t range;
 
tmp_tracking = Servo_tmp_on(Config.servo_frame);
// lcdWriteCGRAM_Array(lcdSpecialChrLs, 8); // LCD-Char mit Rahmensymbole vom Graph
// chrxs = CHRLS; // Flag, welche K�stchensymbole geladen
// Displ_Title(MSG_CONTINOUS);
 
lcd_cls ();
PKT_TitleFromMenuItem( true );
lcd_printp_at(0, 7, strGet(KEYLINE2), 0);
 
Displ_LoopCounter(Config.repeat);
Position[0] = 0; // skalierte Servoposition aber unterschiedliche Schrittanzahl m�glich
Position[1] = ServoSteps()/2;
Position[2] = ServoSteps();
// init Einzelschritt
idx = 0;
dir = calc_dir(idx, Position);
sPos = Position[PosIdx[idx]];
idx++;
rep = Config.repeat;
 
// Test bis Ende der Wiederholungen oder irgendein Enter
while(!get_key_press(1<<KEY_ENTER) && !get_key_press(1<<KEY_ESC)) {
calc_range(sPos - Position[1], Position[0], Position[2], Position[1]);
//range = calc_range(sPos - Position[1], Position[0], Position[2], Position[1]);
// draw_bar(sPos - Position[1], range, 1); // eingerahmter Balkengraph auf 2. Display-Zeile
servoSetPosition(servo_nr, sPos);
 
if ( sPos != Position[PosIdx[idx]]) { // Links-, Mittel- oder Rechtsposotion erreicht?
sPos += (Config.single_step * dir); // variable Schrittweite subtrahieren oder addieren
if (((dir < 0) && (sPos < Position[PosIdx[idx]])) || ((dir > 0) && (sPos > Position[PosIdx[idx]])) || !(Config.single_step))
sPos = Position[PosIdx[idx]]; // �berlauf bei variabler Schrittweite ber�cksichtigen oder Einzelschritt
Delay_ms(Config.servo_frame + 1 + Config.pause_step);// Bei Schrittweite um 1 w�rden welche �bersprungen, zus�tzlich pro Servoschritt verz�gert
}
else {
dir = calc_dir(idx, Position); // Richtungs�nderung
if (idx < (POSIDX_MAX - 1)) {
if (idx == 0) {
rep--; // bei jeden vollen Durchlauf Wiederholz�hler verringern
Displ_LoopCounter(rep);
}
idx++; // Index f�r n�chsten Positionswert ==> Array PosIdx[] bestimmt Anschlagreihenfolge
}
else
idx = 0;
 
_delay_ms( Config.pause*100 ); // variable Pause bei Links-, Mittel- und Rechtsposotion Mindestzeit 400ms (Servolauf)
}
}
 
// lcdClear();
// if (pmenu[0] == '\0')
// Displ_Main_Disp();
// else
// return_m_pkt(strlen(pmenu)); // um bei R�cksprung auf urspr�nglichen Men�punkt zeigen oder Displ_Main_Disp()
// lcdWriteCGRAM_Array(lcdSpecialChr, 7); // LCD-Char f�r Bargraph zur�ckschreiben
cli();
servoInit(SERVO_PERIODE);
sei();
Servo_tmp_Original(tmp_tracking);
}
 
 
 
 
 
/********************************************************************************/
/* zeigt Servo-Anschlagposition links auf Display an */
/* mit sofortiger Wirkung auf Servo */
/* Parameter: */
/* uint16_t val :anzuzeigender Wert, */
/* uint16_t wegen Vereinheitlichung f. Funktionsaufrauf */
/* */
/********************************************************************************/
void Displ_Servo_Min(uint16_t val)
{
uint16_t steps = 0;
 
write_ndigit_number_s( 15, 2, val, 5, 0,0);
servoSet_min(servo_nr, val); // Wert setzen damit nachfolgend die
if (Config.servo[servo_nr].rev) steps = ServoSteps();
servoSetPosition(servo_nr, steps); // �nderung direkt am Servo sichtbar ist
}
 
 
/************************************************************************************/
/* zeigt Servo-Anschlagposition rechts auf Display an */
/* mit sofortiger Wirkung auf Servo */
/* Parameter: */
/* uint16_t val :anzuzeigender Wert, */
/* uint16_t wegen Vereinheitlichung f. Funktionsaufrauf */
/* */
/************************************************************************************/
void Displ_Servo_Max(uint16_t val)
{
uint16_t steps = ServoSteps();
 
write_ndigit_number_u( 15, 2, val, 5, 0,0);
servoSet_max(servo_nr, val); // Wert setzen damit nachfolgend die
if (Config.servo[servo_nr].rev) steps = 0;
servoSetPosition(servo_nr, steps); // �nderung direkt am Servo sichtbar ist
}
 
 
 
/************************************************************************************/
/* zeigt Servo-Anschlagposition Mitte auf Display an */
/* mit sofortiger Wirkung auf Servo */
/* Parameter: */
/* uint16_t val :anzuzeigender Wert, */
/* uint16_t wegen Vereinheitlichung f. Funktionsaufrauf */
/* */
/************************************************************************************/
void Displ_Servo_Mid( uint16_t val )
{
int16_t mid_val;
 
mid_val = val - ServoSteps()/2;
 
lcdx_printf_at_P( 17, 2, MNORMAL, 0,0, PSTR("%3d"), mid_val );
 
servoSet_mid(servo_nr, val); // Wert setzen damit nachfolgend die
servoSetPosition(servo_nr, ServoSteps()/2); // �nderung direkt am Servo sichtbar ist
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Servo_rev( void )
{
uint16_t tmp_val;
uint8_t tmp_tracking;
 
draw_input_screen();
 
tmp_tracking = Servo_tmp_on(SERVO_PERIODE);
tmp_val = Config.servo[servo_nr].rev;
 
if( Change_Value(&tmp_val , 0, 1, Displ_Off_On) )
{ //reverse gibt es nur 0=off, 1=on
Config.servo[servo_nr].rev = tmp_val ;
servoSet_rev(servo_nr, tmp_val );
}
Servo_tmp_Original(tmp_tracking);
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Servo_left( void )
{
uint16_t tmp_val;
uint8_t tmp_tracking;
 
draw_input_screen();
 
tmp_tracking = Servo_tmp_on(SERVO_PERIODE);
servoSetPosition(servo_nr, ServoSteps()); // Linkssanschlag um Kalibrierung am Servo zu sehen
tmp_val = Config.servo[servo_nr].max;
 
if( Change_Value(&tmp_val , servo_limit[Config.sIdxSteps][LEFT].min, servo_limit[Config.sIdxSteps][LEFT].max, Displ_Servo_Max) )
{
Config.servo[servo_nr].max = tmp_val;
servoSet_mid(servo_nr, Config.servo[servo_nr].mid); // Mittelposition muss sich bei Ausschlags�nderung verschieben
}
Servo_tmp_Original(tmp_tracking);
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Servo_right( void )
{
uint16_t tmp_val;
uint8_t tmp_tracking;
 
draw_input_screen();
 
tmp_tracking = Servo_tmp_on(SERVO_PERIODE);
servoSetPosition(servo_nr, 0); // Rechtsanschlag um Kalibrierung am Servo zu sehen
tmp_val = Config.servo[servo_nr].min;
 
if( Change_Value(&tmp_val , servo_limit[Config.sIdxSteps][RIGHT].min, servo_limit[Config.sIdxSteps][RIGHT].max, Displ_Servo_Min) )
{
Config.servo[servo_nr].min = tmp_val;
servoSet_mid(servo_nr, Config.servo[servo_nr].mid); // Mittelposition muss sich bei Ausschlags�nderung verschieben
}
Servo_tmp_Original(tmp_tracking);
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Servo_middle( void )
{
uint16_t tmp_val;
uint8_t tmp_tracking;
 
draw_input_screen();
 
tmp_tracking = Servo_tmp_on(SERVO_PERIODE);
servoSetPosition(servo_nr, ServoSteps()/2); // Mittelposition um Kalibrierung am Servo zu sehen
tmp_val = Config.servo[servo_nr].mid;
 
if( Change_Value(&tmp_val , servo_limit[Config.sIdxSteps][MIDDLE].min, servo_limit[Config.sIdxSteps][MIDDLE].max, Displ_Servo_Mid) )
{
Config.servo[servo_nr].mid = tmp_val;
}
Servo_tmp_Original(tmp_tracking);
}
 
 
 
void Servo_NewValues(uint8_t idx_presc)
{
for (uint8_t i = 0; i < SERVO_NUM_CHANNELS; i++) {
if (idx_presc == STEPS_255) { // Werte umrechnen f�r Prescaler = 256
Config.servo[i].min /= 4;
Config.servo[i].max /= 4;
Config.servo[i].mid /= 4;
}
else { // Werte umrechnen f�r Prescaler = 64
Config.servo[i].min *= 4;
Config.servo[i].max *= 4;
Config.servo[i].mid = (Config.servo[i].mid + 1) * 4 - 1;
}
servoSet_min(i, Config.servo[i].min);
servoSet_max(i, Config.servo[i].max);
servoSet_mid(i, Config.servo[i].mid);
// eeprom_write_block(&servo[i],&ep_servo[i],sizeof(servo_t));
}
// Vorberechnung von ServoChannels[channel].duty
servoSetDefaultPos(); // Ausgangsstellung beider Servos
 
}
 
/************************************************************************************/
/* zeigt Servoschritte zur Auswahl auf Display an */
/* Parameter: */
/* uint16_t val :0 = 255 oder 1 = 1023, */
/* uint16_t wegen Vereinheitlichung f. Funktionsaufrauf */
/* */
/************************************************************************************/
void Displ_Servo_Steps(uint16_t val)
{
if (val==0)
lcd_puts_at(16,2,INTERNAT_STEPS_255,0 );
else
lcd_puts_at(16,2,INTERNAT_STEPS_1023,0 );
 
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void Menu_Servo_Steps(void)
{
uint16_t tmp_val;
 
draw_input_screen();
 
tmp_val = Config.sIdxSteps;
 
if( Change_Value( &tmp_val, STEPS_255, STEPS_1023,Displ_Servo_Steps) )
{
cli();
Config.sIdxSteps = tmp_val;
Servo_NewValues( Config.sIdxSteps ); // hier ist der neue Index anzugeben!
servoInit(SERVO_PERIODE);
sei();
 
 
}
}
 
 
 
//--------------------------------------------------------------
// Setup_ServoAdjust()
//--------------------------------------------------------------
void Setup_ServoAdjust( uint8_t servo )
{
servo_nr = servo;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "Servo 1" oder "Servo 1"
//MenuCtrl_SetTitle_P( PSTR("Servo Adjust") );
 
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( MSERVOADJ_REV , MENU_ITEM, &Servo_rev , MSERVOADJ_REV_de , MSERVOADJ_REV_en );
MenuCtrl_PushML2_P( MSERVOADJ_LEFT , MENU_ITEM, &Servo_left , MSERVOADJ_LEFT_de , MSERVOADJ_LEFT_en );
MenuCtrl_PushML2_P( MSERVOADJ_RIGHT , MENU_ITEM, &Servo_right , MSERVOADJ_RIGHT_de , MSERVOADJ_RIGHT_en );
MenuCtrl_PushML2_P( MSERVOADJ_MID , MENU_ITEM, &Servo_middle , MSERVOADJ_MID_de , MSERVOADJ_MID_en );
 
//---------------
// Control
//---------------
MenuCtrl_Control( MENUCTRL_EVENT );
 
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
 
//--------------------------------------------------------------
// Setup_ServoTestCont()
//--------------------------------------------------------------
void Setup_ServoTestCont( void )
{
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "Test fortlfd."
//MenuCtrl_SetTitle_P( PSTR("Servotest Cont.") );
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( MSERVOTC_START , MENU_ITEM, &Menu_Test_Start , MSERVOTC_START_de , MSERVOTC_START_en );
MenuCtrl_PushML2_P( MSERVOTC_SINGLE , MENU_ITEM, &Menu_Test_SingleStep , MSERVOTC_SINGLE_de , MSERVOTC_SINGLE_en );
MenuCtrl_PushML2_P( MSERVOTC_COUNT , MENU_ITEM, &Menu_Test_Repeat , MSERVOTC_COUNT_de , MSERVOTC_COUNT_en );
MenuCtrl_PushML2_P( MSERVOTC_PAUSEEND , MENU_ITEM, &Menu_Test_Pause , MSERVOTC_PAUSEEND_de , MSERVOTC_PAUSEEND_en );
MenuCtrl_PushML2_P( MSERVOTC_PAUSEINC , MENU_ITEM, &Menu_Test_Pause_Step , MSERVOTC_PAUSEINC_de , MSERVOTC_PAUSEINC_en );
 
//---------------
// Control
//---------------
MenuCtrl_Control( MENUCTRL_EVENT );
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
 
//--------------------------------------------------------------
// Setup_ServoTest()
//--------------------------------------------------------------
void Setup_ServoTest( void )
{
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "Servotest"
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( MSERVOT_PULS , MENU_ITEM, &Menu_Test_PulseWidth , MSERVOT_PULS_de , MSERVOT_PULS_en );
MenuCtrl_PushML2_P( MSERVOT_CONT , MENU_SUB , &Setup_ServoTestCont , MSERVOT_CONT_de , MSERVOT_CONT_en );
MenuCtrl_PushML2_P( MSERVOT_SERVO , MENU_ITEM, &Menu_Test_ServoNr , MSERVOT_SERVO_de , MSERVOT_SERVO_en );
MenuCtrl_PushML2_P( MSERVOT_FRAME , MENU_ITEM, &Menu_Test_Frame , MSERVOT_FRAME_de , MSERVOT_FRAME_en );
 
//---------------
// Control
//---------------
MenuCtrl_Control( MENUCTRL_EVENT );
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
 
//--------------------------------------------------------------
// Setup_ServoTracking()
//--------------------------------------------------------------
void Setup_ServoTracking( void )
{
uint8_t itemid;
 
//---------------
// Create
//---------------
MenuCtrl_Create();
MenuCtrl_SetTitleFromParentItem(); // "Tracking"
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( MSERVO_STEPS , MENU_ITEM, &Menu_Servo_Steps , MSERVO_STEPS_de , MSERVO_STEPS_en );
MenuCtrl_PushML2_P( MSERVO_SERVO1 , MENU_SUB , NOFUNC , MSERVO_SERVO1_de , MSERVO_SERVO1_en );
MenuCtrl_PushML2_P( MSERVO_SERVO2 , MENU_SUB , NOFUNC , MSERVO_SERVO2_de , MSERVO_SERVO2_en );
MenuCtrl_PushML2_P( MSERVO_SERVOTEST , MENU_SUB , &Setup_ServoTest , MSERVO_SERVOTEST_de , MSERVO_SERVOTEST_en );
 
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) break; // ENDE
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
 
if( itemid == MSERVO_SERVO1 ) { Setup_ServoAdjust(0); }
if( itemid == MSERVO_SERVO2 ) { Setup_ServoAdjust(1); }
}
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
}
 
 
 
 
//--------------------------------------------------------------
 
//void start_tracking(void)
//{
// #define TIMEOUT 200 // 2 sec
//
// uint16_t old_anglePan = 0;
// uint16_t old_angleTilt = 0;
//
// //uint16_t old_hh = 0;
// uint8_t flag;
// uint8_t tmp_dat;
//
// lcd_cls ();
// //lcd_printpns_at(0, 0, PSTR("start_tracking "), 2);
//
// //lcd_printpns_at(0, 1, PSTR("ab jetzt Tracking"), 0);
//
// lcd_ecircle(22, 35, 16, 1);
// lcd_ecircle(88, 35, 16, 1);
// lcd_putc (10, 1, 0x1e, 0); // degree symbol
// lcd_putc (20, 1, 0x1e, 0); // degree symbol
//// lcd_printp_at (0, 7, PSTR(KEY_LINE_1), 0);
// lcd_puts_at(0, 7, strGet(KEYLINE1), 0);
// SwitchToNC();
//
// mode = 'O';
//
// // disable debug...
// // RS232_request_mk_data (0, 'd', 0);
// tmp_dat = 0;
// SendOutData ('d', ADDRESS_ANY, 1, &tmp_dat, 1);
//
// // request OSD Data from NC every 100ms
// // RS232_request_mk_data (1, 'o', 100);
// tmp_dat = 10;
// SendOutData ('o', ADDRESS_NC, 1, &tmp_dat, 1);
//
// if (rxd_buffer_locked)
// {
// timer = TIMEOUT;
// Decode64 ();
// naviData = (NaviData_t *) pRxData;
//
// if(error1 == 1)
// lcd_cls();
// }
//
// GPS_Pos_t currpos;
// currpos.Latitude = naviData->CurrentPosition.Latitude;
// currpos.Longitude = naviData->CurrentPosition.Longitude;
//
// flag = 0;
// timer = TIMEOUT;
// abo_timer = ABO_TIMEOUT;
//
// coldstart = 1;
//
// do
// {
// if (rxd_buffer_locked)
// {
// timer = TIMEOUT;
// Decode64 ();
// naviData = (NaviData_t *) pRxData;
//
//
////CB uint8_t FCStatusFlag = naviData->FCFlags;
// uint8_t FCStatusFlag = naviData->FCStatusFlags;
// //write_ndigit_number_u (0, 0, FCStatusFlag);
//
// Tracking_GPS();
//
// //uint16_t heading_home = (naviData->HomePositionDeviation.Bearing + 360 - naviData->CompassHeading) % 360;
//
// // alte Linien l�schen
// //lcd_ecirc_line (22, 35, 15, old_hh, 0);
// //old_hh = heading_home;
// lcd_ecirc_line (22, 35, 15, old_anglePan, 0);
// old_anglePan = anglePan;
// lcd_ecirc_line (88, 35, 15, old_angleTilt, 0);
// old_angleTilt = angleTilt;
//
// lcd_ecirc_line (22, 35, 15, anglePan, 1);
// write_ndigit_number_u (7, 1, anglePan, 3, 0,0);
// lcd_ecirc_line (88, 35, 15, angleTilt, 1);
// write_ndigit_number_u (17, 1, angleTilt, 3, 0,0);
//
// rxd_buffer_locked = FALSE;
//
// if (!abo_timer)
// { // renew abo every 3 sec
// // request OSD Data from NC every 100ms
// // RS232_request_mk_data (1, 'o', 100);
// tmp_dat = 10;
// SendOutData ('o', ADDRESS_NC, 1, &tmp_dat, 1);
//
// abo_timer = ABO_TIMEOUT;
// }
// }
//
// if (!timer)
// {
// OSD_Timeout(flag);
// flag = 0;
// }
// }
// while(!get_key_press (1 << KEY_ESC));
//
// //lcd_cls();
// //return;
//}
 
//--------------------------------------------------------------
//
//void conect2at_unit(void)
//{
// lcd_cls ();
// lcd_printpns_at(0, 0, PSTR("conect2at_unit "), 2);
//
// lcd_printpns_at(0, 3, PSTR("work in progress ;)"), 2);
//
//// lcd_printp_at (0, 7, PSTR(KEY_LINE_1), 0);
// lcd_puts_at(0, 7, strGet(KEYLINE1), 0);
//
// while(!get_key_press (1 << KEY_ESC));
//
// lcd_cls();
// return;
//}
//
////--------------------------------------------------------------
//
//void conect2gps_ser (void)
//{
// lcd_cls ();
// lcd_printpns_at(0, 0, PSTR("conect2gps_ser "), 2);
//
// lcd_printpns_at(0, 3, PSTR("work in progress ;)"), 2);
//
//// lcd_printp_at (0, 7, PSTR(KEY_LINE_1), 0);
// lcd_puts_at(0, 7, strGet(KEYLINE1), 0);
// while(!get_key_press (1 << KEY_ESC));
//
// lcd_cls();
// return;
//}
//
////--------------------------------------------------------------
//
//void conect2gps_bt (void)
//{
// lcd_cls ();
// lcd_printpns_at(0, 0, PSTR("conect2gps_bt "), 2);
//
// lcd_printpns_at(0, 3, PSTR("work in progress ;)"), 2);
//
//// lcd_printp_at (0, 7, PSTR(KEY_LINE_1), 0);
// lcd_puts_at(0, 7, strGet(KEYLINE1), 0);
// while(!get_key_press (1 << KEY_ESC));
//
// lcd_cls();
// return;
//}
 
//--------------------------------------------------------------
 
//void conect2gps_menu(void)
//{
// uint8_t ii = 0;
// uint8_t Offset = 0;
// uint8_t size = ITEMS_CONECT_GPS;
// uint8_t dmode = 0;
// uint8_t target_pos = 1;
// uint8_t val = 0;
//
// while(1)
// {
// lcd_cls ();
// lcd_printpns_at(0, 0, PSTR("conect2gps_menu "), 2);
//// lcd_printp_at (0, 7, PSTR(KEY_LINE_1), 0);
// lcd_puts_at(0, 7, strGet(KEYLINE1), 0);
// while(2)
// {
// ii = 0;
// if(Offset > 0)
// {
// lcd_printp_at(1,1, PSTR("\x12"), 0);
// }
// for(ii = 0;ii < 6 ; ii++)
// {
// if((ii+Offset) < size)
// {
// lcd_printp_at(3,ii+1,conect_gps_menuitems[ii+Offset], 0);
// }
// if((ii == 5)&&(ii+Offset < (size-1)))
// {
// lcd_printp_at(1,6, PSTR("\x13"), 0);
// }
// }
// if(dmode == 0)
// {
// if(Offset == 0)
// {
// if(size > 6)
// {
// val = menu_choose2 (1, 5, target_pos,0,1);
// }
// else
// {
// val = menu_choose2 (1, size, target_pos,0,0);
// }
// }
// else
// {
// val = menu_choose2 (2, 5, target_pos,1,1);
// }
// }
// if(dmode == 1)
// {
// if(Offset+7 > size)
// {
// val = menu_choose2 (2, 6, target_pos,1,0);
// }
// else
// {
// val = menu_choose2 (2, 5, target_pos,1,1);
// }
// }
// if(val == 254)
// {
// Offset++;
// dmode = 1;
// target_pos = 5;
// }
// else if(val == 253)
// {
// Offset--;
// dmode = 0;
// target_pos = 2;
// }
// else if(val == 255)
// {
// return;
// }
// else
// {
// break;
// }
// }
// target_pos = val;
//
// if((val+Offset) == 1 )
// conect2gps_ser();
// if((val+Offset) == 2 )
// conect2gps_bt();
// }
//}
//--------------------------------------------------------------
//void tracking_menu(void)
//{
// uint8_t ii = 0;
// uint8_t Offset = 0;
// uint8_t size = ITEMS_AT;
// uint8_t dmode = 0;
// uint8_t target_pos = 1;
// uint8_t val = 0;
//
// while(1)
// {
// lcd_cls ();
// lcd_printpns_at(1, 0, PSTR("Tracking Men\x06 V.01 "), 2);
//// lcd_printp_at (0, 7, PSTR(KEY_LINE_1), 0);
// lcd_puts_at(0, 7, strGet(KEYLINE1), 0);
// while(2)
// {
// ii = 0;
// if(Offset > 0)
// {
// lcd_printp_at(1,1, PSTR("\x12"), 0);
// }
// for(ii = 0;ii < 6 ; ii++)
// {
// if((ii+Offset) < size)
// {
// lcd_printp_at(3,ii+1,at_menuitems[ii+Offset], 0);
// }
// if((ii == 5)&&(ii+Offset < (size-1)))
// {
// lcd_printp_at(1,6, PSTR("\x13"), 0);
// }
// }
// if(dmode == 0)
// {
// if(Offset == 0)
// {
// if(size > 6)
// {
// val = menu_choose2 (1, 5, target_pos,0,1);
// }
// else
// {
// val = menu_choose2 (1, size, target_pos,0,0);
// }
// }
// else
// {
// val = menu_choose2 (2, 5, target_pos,1,1);
// }
// }
// if(dmode == 1)
// {
// if(Offset+7 > size)
// {
// val = menu_choose2 (2, 6, target_pos,1,0);
// }
// else
// {
// val = menu_choose2 (2, 5, target_pos,1,1);
// }
// }
// if(val == 254)
// {
// Offset++;
// dmode = 1;
// target_pos = 5;
// }
// else if(val == 253)
// {
// Offset--;
// dmode = 0;
// target_pos = 2;
// }
// else if(val == 255)
// {
// return;
// }
// else
// {
// break;
// }
// }
// target_pos = val;
//
// if((val+Offset) == 1 )
// test_servo_menu();
// if((val+Offset) == 2 )
// adjust_servo_menu();
// if((val+Offset) == 3 )
// show_angle();
// if((val+Offset) == 4 )
////TODO: start_tracking();
// if((val+Offset) == 5 )
// conect2at_unit();
// if((val+Offset) == 6 )
// conect2gps_menu();
// }
//}
 
//--------------------------------------------------------------
// kapeschi Ant.Treking Funktionen
//--------------------------------------------------------------
 
// Berechnung von Distanz und Winkel aus GPS-Daten home(MK eingeschaltet)
// zur aktuellen Position(nach Motorstart)
//geo_t calc_geo(HomePos_t *home, GPS_Pos_t *pos)
//{ int32_t lat1, lon1, lat2, lon2;
// int32_t d1, dlat;
// geo_t geo;
//
// lon1 = MK_pos.Home_Lon;
// lat1 = MK_pos.Home_Lat;
// lon2 = pos->Longitude;
// lat2 = pos->Latitude;
//
// // Formel verwendet von http://www.kompf.de/gps/distcalc.html
// // 111.3 km = Abstand zweier Breitenkreise und/oder zweier L�ngenkreise am �quator
// // es wird jedoch in dm Meter weiter gerechnet
// // (tlon1 - tlon2)/10) sonst uint32_t-�berlauf bei cos(0) gleich 1
// d1 = (1359 * (int32_t)(c_cos_8192((lat1 + lat2) / 20000000)) * ((lon1 - lon2)/10))/ 10000000;
// dlat = 1113 * (lat1 - lat2) / 10000;
// geo.bearing = (my_atan2(d1, dlat) + 540) % 360; // 360 +180 besserer Vergleich mit MkCockpit
// geo.distance = sqrt32(d1 * d1 + dlat * dlat);
// return(geo);
//}
 
//void do_tracking(void)
//{ //static uint8_t hysteresis = 0;
// // aus MkCockpit http://forum.mikrokopter.de/topic-post216136.html#post216136
// // (4 * (........))/5 ==> Wichtung Luftdruck-H�he zu GPS
// currentPos.Altitude = MK_pos.Home_Alt + (4000 * (int32_t)(naviData->Altimeter) / AltFaktor + currentPos.Altitude - MK_pos.Home_Alt) / 5;
//
// geo = calc_geo(&MK_pos, &currentPos);
// angleTilt = RAD_TO_DEG * (double)atan2((double)(currentPos.Altitude - MK_pos.Home_Alt) / 1000, geo.distance);
// //if (geo.distance < 4 || (geo.distance < 6 && hysteresis)) { // < 4m ==> Pan-Servo in Mittelstellung. Hysterese bis 6m, damit Servo im Grenzbereich nicht wild rumschl�gt
// //geo.bearing = MK_pos.direction;
// //angleTilt = 0;
// //hysteresis = 1;
// //}
// //else {
// //hysteresis = 0;
// //}
////
// //// egal wo der �bergangspunkt 359, 360, 1grd ist => Winkel�bergangspunkt auf 0 bzw. 180grd des Servos bringen
// //// 360 grd negative Winkelwerte als positive
// anglePan = (geo.bearing + 450 - MK_pos.direction) % 360; // 450 = 360 + 90
//
// //if (angleTilt < 0) angleTilt = 0;
// //if (angleTilt > 180) angleTilt = 180;
////
// //if (anglePan >= 180) { // zwecks 360grd-Abdeckung flipt Pan-/Tilt-Servo
// //anglePan = anglePan - 180;
// //angleTilt = 180 - angleTilt;
// //
// //}
////angleTilt = 180;
////angleTilt = 180;
//
//// servoSetAngle(0, anglePan);
//// servoSetAngle(1, angleTilt);
//}
 
 
/****************************************************************/
/* */
/* MK GPS Tracking */
/* */
/****************************************************************/
 
// MK OSD-Daten lesen und verifizieren
//uint8_t OSD_Data_valid(NaviData_t **navi_data)
//{ uint8_t ret = 0;
//char *tx_osd = {"#co?]==EH\r"};
//// char interval[2] = {10, '\0'};
//
//if (rx_line_decode('O')) { // OSD-Datensatz pr�fen/dekodieren
////*navi_data = (NaviData_t*)data_decode; // dekodierte Daten mit Struktur OSD-Daten versehen
//if (rx_timeout < RX_TIME_OLD) { // GPS-Daten nicht zu alt und ok.
//currentPos = (*navi_data)->CurrentPosition;
//if ((*navi_data)->NCFlags & NC_FLAG_GPS_OK)
//ret = 1;
//// aus MkCockpit http://forum.mikrokopter.de/topic-post216136.html#post216136
//// (4 * (........))/5 ==> Wichtung Luftdruck-H�he zu GPS
//currentPos.Altitude = MK_pos.Home_Alt + (4000 * (int32_t)((*navi_data)->Altimeter) / AltFaktor + currentPos.Altitude - MK_pos.Home_Alt) / 5;
//satsInUse = (*navi_data)->SatsInUse;
//}
//}
//// ca. 210ms keine OSD-Daten empfangen ==> sende neue Anforderung an MK
//// if ((track_tx) && (rx_timeout > RX_TIMEOUT)) tx_Mk(NC_ADDRESS, 'o', interval, 1); // 420 * 0.5ms interval
//if ((track_tx) && (rx_timeout > RX_TIMEOUT)) SendOutData(tx_osd); // 420 * 0.5ms interval
//return ret;
//}
//
 
// MK eingeschaltet und GPS-ok, danach Motoren gestartet ==> Berechnung horizontaler/vertikaler Servowinkel
// Hauptprogramm von GPS Antennen-Nachf�hrung
//void Tracking_GPS(void)
//{ //NaviData_t *navidata;
// static uint8_t track_running = 0;
//
// if (!track_running)
// {
// //track_running = 1; // verhindert doppelten Aufruf, wenn in Eingabeschleife Menu_MK_BatteryChangeNr() !!!
// //if (OSD_Data_valid(&naviData)) {
// if (coldstart)
// {
// //// erst nach Neustart NGVideo und beim Motorstart werden Daten vom MK �bernommen
// //if (naviData->FCFlags & FC_FLAG_MOTOR_START)
// //{
// MK_pos.Home_Lon = (double)naviData->HomePosition.Longitude / 10000000.0;
// MK_pos.Home_Lat = (double)naviData->HomePosition.Latitude / 10000000.0;
// MK_pos.Home_Lon7 = naviData->HomePosition.Longitude;
// MK_pos.Home_Lat7 = naviData->HomePosition.Latitude;
// MK_pos.Home_Alt = naviData->HomePosition.Altitude;
// MK_pos.direction = naviData->CompassHeading;
// coldstart = 0;
// //}
// //}
// //else {
// //do_tracking();
// }
// //}
// track_running = 0;
// }
// do_tracking();
//}
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/tracking/servo_setup.h
0,0 → 1,45
#ifndef _TRACKING_H_
#define _TRACKING_H_
 
#define TRACKING_RSSI 1
#define TRACKING_GPS 2
#define TRACKING_MKCOCKPIT 3
#define TRACKING_NMEA 4
 
#define DLEFT 0
#define DRIGHT 1
#define AltFaktor 22.5
 
#define PAN_SERVO_CORRECT 3.125
#define TILT_SERVO_CORRECT 3.125
 
typedef void (*Displ_Fnct_t)( uint16_t );
 
 
//typedef struct {
// int32_t distance;
// int16_t bearing;
//}geo_t;
 
//typedef struct {
// double Home_Lon; // in degrees
// double Home_Lat; // in degrees
// int32_t Home_Lon7; // in 1E-7 degrees
// int32_t Home_Lat7; // in 1E-7 degrees
// int32_t Home_Alt; // in mm
// // ermittelte Konstante aus Mittelposition Antenne geo.bearing - navi_data.CompassHeading
// int16_t direction;
//}__attribute__((packed)) HomePos_t;
 
#define INTERNAT_STEPS_255 "255 "
#define INTERNAT_STEPS_1023 "1023"
 
 
// kapeschi
void Setup_ServoTracking( void );
void Tracking_GPS(void);
void Tracking_NMEA(void);
void Tracking_RSSI(void);
void setNMEAdir(void);
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/tracking/tracking.c
0,0 → 1,648
/*
* tracking.c
*
* Created on: 13.02.2012
* Author: cebra
*/
 
 
//############################################################################
//# HISTORY tracking.c
//#
//# 27.06.2014 OG
//# - umgestellt auf gps/gps_nmea.c
//# - Codeformattierung
//# - chg: auf #include "../gps/mymath.h" angepasst
//# - del: #include "tools.h"
//#
//# 25.06.2014 OG
//# - chg: PKT_tracking() - auskommentierungen um Zugriffe auf Config.gps_UsedGPSMouse
//# zu unterbinden. Anmerkung dazu siehe dort.
//#
//# 22.06.2014 OG
//# - chg: Tracking_NMEA() - do_tracking() auskommentiert (spaeter fuer
//# Tracking wieder geradeziehen)
//# - Variable 'CheckGPS' hinzugefuegt weil aus anderen Sourcen (setup.c) entfernt
//#
//# 18.06.2014 OG
//# - chg: Code-Formattierung
//#
//# 16.06.2014 OG
//# - add: NMEA_GPGGA_counter (zaehlt empfangene GPGGA-Pakete)
//#
//# 01.06.2014 OG
//# - chg: PKT_trackingMK() - verschiedene Anzeigefunktionen auskommentiert und
//# als DEPRICATED Klassifiziert wegen Cleanup der alten OSD Screens
//#
//# 30.05.2014 OG
//# - chg: calc_geo()- my_itoa() ersetzt durch writex_gpspos() und lcdx_printf_at_P()
//# weil my_itoa() nicht mehr vorhanden
//#
//# 13.05.2014 OG
//# - chg: PKT_trackingBT() - Variable 'BT_WhasOn' auskommentiert
//# wegen Warning: variable set but not used
//# - chg: PKT_trackingBT() - Variable 'flag' auskommentiert
//# wegen Warning: variable set but not used
//#
//# 28.04.2014 OG
//# - chg: PKT_trackingBT(), PKT_trackingMK() - OSD_Timeout() entfernt (weil es
//# das nicht mehr gibt) und erstmal durch ein PKT_Message_P() ersetzt
//# * ACHTUNG: UNGETESTET! * (bei Bedarf anpassen, tracking hat niedrige Prio)
//# - add: include "../pkt/pkt.h"
//#
//# 12.02.2014 OG
//# - del: mk_param_struct entfernt
//#
//# 29.08.2013 Cebra
//# - chg: falsche Parameterübergabe bei getLatitude/getLongitude
//#
//# 25.08.2013 Cebra
//# - add: #ifdef USE_TRACKING . NMEA Routinen werden nur noch für BT_NMEA genutzt
//#
//# 26.06.2013 Cebra
//# - chg: Modulumschaltung für WiFlypatch geändert
//#
//############################################################################
 
 
#include "../cpu.h"
#include <string.h>
#include <util/delay.h>
#include <avr/interrupt.h>
#include <stdlib.h>
#include <math.h>
#include "../main.h"
 
 
//++++++++++++++++++++++++++++++++++
#ifdef USE_TRACKING
//++++++++++++++++++++++++++++++++++
 
 
#include "../tracking/tracking.h"
#include "../tracking/ng_servo.h"
#include <avr/pgmspace.h>
#include "../bluetooth/fifo.h"
#include "../bluetooth/bluetooth.h"
#include "../lcd/lcd.h"
 
#include "../mk-data-structs.h"
#include "../messages.h"
#include "../lcd/lcd.h"
#include "../eeprom/eeprom.h"
#include "../timer/timer.h"
#include "../uart/uart1.h"
#include "../uart/usart.h"
#include "../osd/osd.h"
#include "../gps/mymath.h"
#include "../setup/setup.h"
#include "../pkt/pkt.h"
//#include "../gps/gps_nmea.h"
#include "../avr-nmea-gps-library/nmea.h"
 
 
 
uint8_t CheckGPS = true; // Patch 22.06.2014 OG: hier integriert weil ais anseren Sourcen entfernt (u.a. setup.c)
 
char data_decode[RXD_BUFFER_SIZE];
 
 
#define DLEFT 0
#define DRIGHT 1
#define DEG_TO_RAD 0.0174533 // degrees to radians = PI / 180
#define RAD_TO_DEG 57.2957795 // radians to degrees = 180 / PI
#define AltFaktor 22.5
#define TIMEOUT 200 // 2 sec
 
NaviData_t *naviData;
 
 
HomePos_t MK_pos; // Home position of station
GPS_Pos_t currentPos; // Current position of flying object
 
 
uint8_t tracking = TRACKING_MIN;
uint8_t track_hyst = TRACKING_HYSTERESE;
uint8_t track_tx =0;
uint8_t coldstart; // Flag erstmaliger MK-Start(Motore) nur nach GPS-Fix
geo_t geo;
int16_t anglePan, angleTilt;
 
 
 
 
//// Berechnung von Distanz und Winkel aus GPS-Daten home(MK eingeschaltet)
//// zur aktuellen Position(nach Motorstart)
//geo_t calc_geo(HomePos_t *home, GPS_Pos_t *pos)
//{ double lat1, lon1, lat2, lon2, d1, dlat;
// geo_t geo;
//
// lon1 = MK_pos.Home_Lon;
// lat1 = MK_pos.Home_Lat;
// lon2 = (double)pos->Longitude / 10000000.0;
// lat2 = (double)pos->Latitude / 10000000.0;
//
// // Formel verwendet von http://www.kompf.de/gps/distcalc.html
// // 111.3 km = Abstand zweier Breitenkreise und/oder zweier Längenkreise am Äquator
// // es wird jedoch in Meter weiter gerechnet
// d1 = 111300 * (double)cos((double)(lat1 + lat2) / 2 * DEG_TO_RAD) * (lon1 - lon2);
// dlat = 111300 * (double)(lat1 - lat2);
// // returns a value in metres http://www.kompf.de/gps/distcalc.html
// geo.bearing = fmod((RAD_TO_DEG * (double)atan2(d1, dlat)) + 180, 360); // +180 besserer Vergleich mit MkCockpit
// if (geo.bearing > 360) geo.bearing -= 360; // bekam schon Werte über 400
// geo.distance = sqrt(d1 * d1 + dlat * dlat);
// return(geo);
//}
 
// Berechnung von Distanz und Winkel aus GPS-Daten home(MK eingeschaltet)
// zur aktuellen Position(nach Motorstart)
 
//--------------------------------------------------------------
// bei Gelegenheit den Code auf gps/gps.c/gps_Deviation() aendern
//--------------------------------------------------------------
geo_t calc_geo( HomePos_t *home, GPS_Pos_t *pos )
{
int32_t lat1, lon1, lat2, lon2;
int32_t d1, dlat;
geo_t geo;
 
lon1 = home->Home_Lon;
lat1 = home->Home_Lat;
lon2 = pos->Longitude;
lat2 = pos->Latitude;
 
if( !CheckGPS )
{
writex_gpspos( 0, 3, home->Home_Lat , MNORMAL, 0,0); // Anzeige: Breitengrad (Latitude)
writex_gpspos( 11, 3, home->Home_Lon , MNORMAL, 0,0); // Anzeige: Laengengrad (Longitude)
writex_gpspos( 0, 4, pos->Latitude , MNORMAL, 0,0); // Anzeige: Breitengrad (Latitude)
writex_gpspos( 11, 4, pos->Longitude , MNORMAL, 0,0); // Anzeige: Laengengrad (Longitude)
 
//lcd_puts_at (0, 3, my_itoa(home->Home_Lat, 10, 7, 7), 0); // 30.05.2014 OG: my_itoa() gibt es nicht mehr
//lcd_puts_at (11, 3, my_itoa(home->Home_Lon, 10, 7, 7), 0); // 30.05.2014 OG: my_itoa() gibt es nicht mehr
//lcd_puts_at (0, 4, my_itoa(pos->Latitude, 10, 7, 7), 0); // 30.05.2014 OG: my_itoa() gibt es nicht mehr
//lcd_puts_at (11, 4, my_itoa(pos->Longitude, 10, 7, 7), 0); // 30.05.2014 OG: my_itoa() gibt es nicht mehr
}
 
// Formel verwendet von http://www.kompf.de/gps/distcalc.html
// 111.3 km = Abstand zweier Breitenkreise und/oder zweier Langenkreise am Äquator
// es wird jedoch in dm Meter weiter gerechnet
// (tlon1 - tlon2)/10) sonst uint32_t-Überlauf bei cos(0) gleich 1
d1 = (1359 * (int32_t)(c_cos_8192((lat1 + lat2) / 20000000)) * ((lon1 - lon2)/10))/ 10000000;
dlat = 1113 * (lat1 - lat2) / 10000;
geo.bearing = (my_atan2(d1, dlat) + 540) % 360; // 360 +180 besserer Vergleich mit MkCockpit
geo.distance = sqrt32(d1 * d1 + dlat * dlat);
 
if( !CheckGPS )
{
lcd_printp_at (0, 5, PSTR("Bear:"), 0);
 
lcdx_printf_at_P( 5, 5, MNORMAL, 0,0, PSTR("%3d"), geo.bearing );
//lcd_puts_at (5, 5, my_itoa((uint32_t)geo.bearing, 3, 0, 0), 0); // 30.05.2014 OG: my_itoa() gibt es nicht mehr
 
lcd_printp_at (8, 5, PSTR("\x1e"), 0);
lcd_printp_at (9, 5, PSTR("Dist:"), 0);
 
lcdx_printf_at_P( 15, 5, MNORMAL, 0,0, PSTR("%3d"), geo.distance );
//lcd_puts_at (15, 5, my_itoa((uint32_t)geo.distance, 3, 1, 1), 0); // 30.05.2014 OG: my_itoa() gibt es nicht mehr
 
lcd_printp_at (20, 5, PSTR("m"), 0);
}
 
return(geo);
}
 
 
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void do_tracking( void )
{
static uint8_t hysteresis = 0;
 
geo = calc_geo(&MK_pos, &currentPos);
angleTilt = my_atan2((currentPos.Altitude - MK_pos.Home_Alt) / 100, geo.distance);
 
if (geo.distance < 40 || (geo.distance < 60 && hysteresis))
{ // < 4m ==> Pan-Servo in Mittelstellung. Hysterese bis 6m, damit Servo im Grenzbereich nicht wild rumschl�gt
geo.bearing = MK_pos.direction;
if (currentPos.Altitude - MK_pos.Home_Alt < 4000) angleTilt = 0; // man fliegt nicht direkt �ber Kopf
hysteresis = 1;
}
else
{
hysteresis = 0;
}
 
// egal wo der Übergangspunkt 359, 360, 1grd ist => Winkelübergangspunkt auf 0 bzw. 180grd des Servos bringen
// 360 grd negative Winkelwerte als positive
anglePan = (geo.bearing + 450 - MK_pos.direction) % 360; // 450 = 360 + 90
 
if (angleTilt < 0)
angleTilt = 0;
 
if (angleTilt > 180)
angleTilt = 180;
 
if (anglePan >= 180)
{ // zwecks 360grd-Abdeckung flipt Pan-/Tilt-Servo
anglePan = anglePan - 180;
angleTilt = 180 - angleTilt;
}
 
servoSetAngle(0, anglePan);
servoSetAngle(1, angleTilt);
 
if (!CheckGPS)
{
lcd_printp_at (0, 6, PSTR("Pan :"), 0);
write_ndigit_number_u (6, 6, anglePan, 3, 1,0);
lcd_printp_at (11, 6, PSTR("Tilt:"), 0);
write_ndigit_number_u (17, 6, angleTilt, 3, 1,0);
}
 
// write_ndigit_number_u (0, 5, (uint16_t)(currentPos.Altitude/10000000), 2, 0,0);
//// lcd_printp_at (4, 4, PSTR("."), 0);
// write_ndigit_number_u (2, 5, (uint16_t)((currentPos.Altitude/1000) % 10000), 4, 1,0);
// write_ndigit_number_u (6, 5, (uint16_t)((currentPos.Altitude/10) % 100), 2, 1,0);
//
// write_ndigit_number_u (10, 5, (uint16_t)(MK_pos.Home_Alt/10000000), 2, 0,0);
//// lcd_printp_at (4, 4, PSTR("."), 0);
// write_ndigit_number_u (12, 5, (uint16_t)((MK_pos.Home_Alt/1000) % 10000), 4, 1,0);
// write_ndigit_number_u (16, 5, (uint16_t)((MK_pos.Home_Alt/10) % 100), 2, 1,0);
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t PKT_trackingBT( void ) // Tracking mit NMEA-Daten von BT-Maus
{
//uint8_t BT_WhasOn = 0;
uint8_t BT_status;
//uint8_t flag;
uint8_t tmp_dat;
coldstart =1;
 
//lcd_printp_at(0,1, PSTR("try NMEA data from:"), 0);
lcd_puts_at (0, 1,Config.gps_UsedDevName, 0);
//set_BTOn();
set_Modul_On(Bluetooth);
 
//BT_WhasOn = true;
if( Config.BTIsSlave==true )
{
bt_downlink_init();
}
 
lcd_printp_at (18, 1, PSTR(" ?? "), 0);
BT_status = bt_connect(Config.gps_UsedMac);
 
if( BT_status==true )
{
lcd_printp_at (18, 1, PSTR(" OK "), 0);
receiveNMEA = true;
}
else
{
lcd_printp_at (17, 1, PSTR("FAIL"), 2);
}
 
 
if( receiveNMEA==true )
{
lcd_cls_line( 0, 1, 20);
lcd_printp_at( 0, 2, PSTR(" Latitude Longitude"), 2);
lcd_printp_at( 0, 3, PSTR("H"), 0);
lcd_printp_at( 0, 4, PSTR("M"), 0);
 
bt_rx_ready = 0;
 
SwitchToNC();
mode = 'O';
 
// disable debug...
// RS232_request_mk_data (0, 'd', 0);
tmp_dat = 0;
SendOutData( 'd', ADDRESS_ANY, 1, &tmp_dat, 1);
 
// request OSD Data from NC every 100ms
// RS232_request_mk_data (1, 'o', 100);
tmp_dat = 10;
SendOutData( 'o', ADDRESS_NC, 1, &tmp_dat, 1);
 
//OSD_active = true; // benoetigt für Navidata Ausgabe an SV2
//flag = 0;
 
timer = TIMEOUT;
abo_timer = ABO_TIMEOUT;
 
do
{
//bt_rx_ready = 0;
 
// if( !NMEA_receiveBT() )
// break;
if (!NMEA_isdataready())
break;
 
if( rxd_buffer_locked )
{
timer = TIMEOUT;
Decode64 ();
naviData = (NaviData_t *) pRxData;
 
currentPos = naviData->CurrentPosition;
 
//currentPos.Altitude = MK_pos.Home_Alt + (4000 * (int32_t)(naviData->Altimeter) / AltFaktor + currentPos.Altitude - MK_pos.Home_Alt) / 5;
 
 
//-----------------
// MK: Lat / Long
//-----------------
writex_gpspos( 2, 4, currentPos.Latitude , MNORMAL, 0,0 ); // MK: Latitude
writex_gpspos(12, 4, currentPos.Longitude, MNORMAL, 0,0 ); // MK: Longitude
 
 
 
// NMEA_GetNewData(); // neue NMEA GPGGA Daten von der BT GPA-Maus holen
 
 
 
//-----------------
// GPS-Maus: Lat / Long
//-----------------
writex_gpspos( 2, 3, NMEA.Latitude , MNORMAL, 0,0 ); // GPS-Maus: Latitude
writex_gpspos(12, 3, NMEA.Longitude, MNORMAL, 0,0 ); // GPS-Maus: Longitude
 
 
//do_tracking(); // das geht so noch nicht mit einer BT GPS-Maus! do_tracking(); ueberarbeiten!
 
 
if( !CheckGPS )
{
//lcd_printp_at( 0, 2, PSTR("GPS Time: "), 0);
lcd_puts_at( 13, 0, NMEA.Time , 2);
 
lcd_printp_at( 16, 1, PSTR("Sat:"), 0);
write_ndigit_number_u( 19, 1, NMEA.SatsInUse, 2, 1,0);
 
lcd_printp_at( 0, 1, PSTR("Fix:"), 0);
write_ndigit_number_u( 4, 1, NMEA.SatFix, 1, 1,0);
 
lcd_printp_at( 6, 1, PSTR("HDOP:"), 0);
write_ndigit_number_u_10th( 11, 1, NMEA.HDOP, 3, 0,0);
}
 
 
rxd_buffer_locked = FALSE;
 
 
if( !abo_timer )
{
// renew abo every 3 sec
// request OSD Data from NC every 100ms
// RS232_request_mk_data (1, 'o', 100);
tmp_dat = 10;
SendOutData( 'o', ADDRESS_NC, 1, &tmp_dat, 1);
 
abo_timer = ABO_TIMEOUT;
}
 
} // end: if (rxd_buffer_locked)
 
 
 
if( !timer )
{
//OSD_Timeout(flag); // <- 28.04.2014 OG: gibt es nicht mehr - ersetzt durch PKT_Message_P() (ungetestet)
 
//void PKT_Message_P( const char *text, uint8_t error, uint16_t timeout, uint8_t beep, uint8_t clearscreen )
PKT_Message_P( strGet(OSD_ERROR), true, 200, true, true ); // max. 2 Sekunden anzeigen
 
//flag = 0;
error = 1;
}
 
} while( !get_key_press (1 << KEY_ESC) || !receiveNMEA==true || error ==1);
 
 
lcd_cls_line(0,1,21);
lcd_cls_line(0,2,21);
lcd_cls_line(0,3,21);
lcd_cls_line(0,4,21);
lcd_cls_line(0,5,21);
lcd_cls_line(0,6,21);
 
if( !receiveNMEA )
lcd_printp_at (0, 2, PSTR("lost BT data"), 0);
 
 
lcd_printp_at (0, 3, PSTR("GPS trennen"), 0);
 
} // end: if( receiveNMEA==true )
else
{
lcd_printp_at (0, 4, PSTR("Error at connecting"), 0);
lcd_printp_at (0, 5, PSTR("switch on BT Mouse!!"), 0);
while( !get_key_press (1 << KEY_ENTER) );
}
 
receiveNMEA = false;
 
if( !bt_disconnect() )
lcd_printp_at (0, 3, PSTR("Fehler beim Trennen"), 0);
 
//set_BTOff();
set_Modul_On(USB);
return true;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t PKT_trackingMK( void ) // Tracking mit GPS-Daten vom Mikrokopter
{
//uint8_t BT_WhasOn = 0;
//uint8_t BT_status;
uint8_t GPSfix=0;
uint8_t tmp_dat;
uint8_t toggletimer=0;
coldstart = true;
 
 
lcd_printp_at (0, 2, PSTR("S Latitude Longitude"), 2);
 
lcd_cls_line (0,1,20);
 
//lcd_printp_at (0, 3, PSTR("H"), 0);
//lcd_printp_at (0, 4, PSTR("M"), 0);
 
SwitchToNC();
mode = 'O';
 
// disable debug...
// RS232_request_mk_data (0, 'd', 0);
tmp_dat = 0;
SendOutData ('d', ADDRESS_ANY, 1, &tmp_dat, 1);
 
// request OSD Data from NC every 100ms
// RS232_request_mk_data (1, 'o', 100);
tmp_dat = 10;
SendOutData ('o', ADDRESS_NC, 1, &tmp_dat, 1);
timer = TIMEOUT;
abo_timer = ABO_TIMEOUT;
error = 0;
 
do
{
if( rxd_buffer_locked )
{
timer = TIMEOUT;
Decode64 ();
naviData = (NaviData_t *) pRxData;
//OSD_Screen_Element (18, 1, OSD_SATS_IN_USE,1);
//if (GPSfix == true) OSD_Screen_Element (0, 1, OSD_STATUS_FLAGS,1);
 
//---
// 01.06.2014 OG: DEPRICATED (alte Funktionen in osd/osdold_screens.c - nicht mehr verwenden!)
//---
//OSD_Element_SatsInUse( 18, 1, 1);
 
//---
// 01.06.2014 OG: DEPRICATED (alte Funktionen in osd/osdold_screens.c - nicht mehr verwenden!)
//---
//if (GPSfix == true) OSD_Element_StatusFlags( 0, 1);
 
if (!(naviData->NCFlags & NC_FLAG_GPS_OK))
{
toggletimer++;
if (toggletimer == 50) toggletimer = 0;
if (toggletimer == 25) lcd_printp_at(0,1, PSTR("Whait for GPS Fix "), 2);
if (toggletimer == 1) lcd_printp_at(0,1, PSTR("Whait for GPS Fix "), 0);
 
rxd_buffer_locked = false;
GPSfix = false;
}
else GPSfix = true;
 
 
if( GPSfix )
{
if( coldstart )
{
// erst nach Neustart NGVideo und beim Motorstart werden Daten vom MK übernommen
if (naviData->FCStatusFlags & FC_FLAG_MOTOR_START)
{
MK_pos.Home_Lon = naviData->HomePosition.Longitude;
MK_pos.Home_Lat = naviData->HomePosition.Latitude;
MK_pos.Home_Alt = naviData->HomePosition.Altitude;
MK_pos.direction = naviData->CompassHeading;
coldstart = false;
rxd_buffer_locked = false;
lcd_printp_at(0,1, PSTR(" "), 0);
}
else
{
lcd_printp_at(0,1, PSTR("GPS ok, start ok "), 0);
rxd_buffer_locked = false;
}
} // end: if( coldstart )
else
{
//run
currentPos = naviData->CurrentPosition;
currentPos.Altitude = MK_pos.Home_Alt + (4000 * (int32_t)(naviData->Altimeter) / AltFaktor + currentPos.Altitude - MK_pos.Home_Alt) / 5;
do_tracking();
 
//lcd_puts_at (13, 0, NMEAtime, 2);
//lcd_printp_at (16, 1, PSTR("Sat:"), 0);
//write_ndigit_number_u (19, 1, NMEAsatsInUse, 2, 1,0);
//lcd_printp_at (0, 1, PSTR("Fix:"), 0);
//write_ndigit_number_u (4, 1, posfix, 1, 1,0);
//lcd_printp_at (6, 1, PSTR("HDOP:"), 0);
//write_ndigit_number_u_10th (11, 1, HDOP, 3, 0,0);
 
rxd_buffer_locked = FALSE;
} // run
}
 
 
if( !abo_timer )
{
// renew abo every 3 sec
// request OSD Data from NC every 100ms
// RS232_request_mk_data (1, 'o', 100);
tmp_dat = 10;
SendOutData( 'o', ADDRESS_NC, 1, &tmp_dat, 1);
 
abo_timer = ABO_TIMEOUT;
}
 
} // end: if( rxd_buffer_locked )
 
 
if( !timer )
{
//OSD_Timeout(1); // <- 28.04.2014 OG: gibt es nicht mehr - ersetzt durch PKT_Message_P() (ungetestet)
 
//void PKT_Message_P( const char *text, uint8_t error, uint16_t timeout, uint8_t beep, uint8_t clearscreen )
PKT_Message_P( strGet(OSD_ERROR), true, 200, true, true ); // max. 2 Sekunden anzeigen
 
error = 1;
}
 
} while( (!get_key_press (1 << KEY_ENTER)) && (error ==0) );
 
 
lcd_cls_line(0,1,21);
lcd_cls_line(0,2,21);
lcd_cls_line(0,3,21);
lcd_cls_line(0,4,21);
lcd_cls_line(0,5,21);
lcd_cls_line(0,6,21);
 
if (error ==1)
{
lcd_printp_at (0, 2, PSTR("lost Wi.232 data"), 0);
_delay_ms(2000);
}
 
return true;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void PKT_tracking(void)
{
clear_key_all();
lcd_cls ();
 
// 25.06.2014 OG: auskommentiert weil erstmal kein Config.gps_UsedGPSMouse mehr unterstuetzt
// wird. Falls tracking.c mal richtig implementiert wird sollte man sich auf eine BT-GPS-Maus
// konzentrieren bis Tracking einwandfrei laeuft - wenn dann noch immer Bedarf nach MK-GPS ist
// kann man das ja wieder einbauen
//
//if (Config.gps_UsedGPSMouse==GPS_Bluetoothmouse1) lcd_printp_at(0,0, PSTR("Tracking Bluetooth "), 2);
//if (Config.gps_UsedGPSMouse==GPS_Mikrokopter) lcd_printp_at(0,0, PSTR(" Tracking Mikrokopter"), 2);
//if (Config.gps_UsedGPSMouse==GPS_Bluetoothmouse1) PKT_trackingBT();
//if (Config.gps_UsedGPSMouse==GPS_Mikrokopter) PKT_trackingMK();
 
lcd_printp_at( 0,0, PSTR("Tracking Bluetooth "), MINVERS);
lcd_printp_at(12, 7, strGet(ENDE), MNORMAL); // Keyline
PKT_trackingBT();
clear_key_all();
}
 
 
 
 
//++++++++++++++++++++++++++++++++++
#endif // #ifdef USE_TRACKING
//++++++++++++++++++++++++++++++++++
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/tracking/tracking.h
0,0 → 1,77
/*
* tracking.h
*
* Created on: 13.02.2012
* Author: cebra
*/
 
//############################################################################
//# HISTORY tracking.h
//#
//# 27.06.2014 OG
//# - Entkernt: verschiedene Variablen und Funktionen geloescht
//#
//# 16.06.2014 OG
//# - add: NMEA_GPGGA_counter (zaehlt empfangene GPGGA-Pakete)
//# - add: Source-Historie
//############################################################################
 
 
#ifndef TRACKING_H_
#define TRACKING_H_
 
 
#define REPEAT 1
#define REPEAT_MIN 1
#define REPEAT_MAX 100
#define PAUSE 10
#define PAUSE_MIN 4 // mindestens 400ms, da mechanischer Servo-Lauf zur Position berücksichtigt werden muss
#define PAUSE_MAX 20 // Pause pro Links-, Mittel- und Rechtsposition 10*100ms
#define PAUSE_STEP 0
#define PAUSE_STEP_MIN 0 // Pause bei jeden Servoschritt in ms
#define PAUSE_STEP_MAX 200
 
// Antennen-Nachführung
#define TRACKING_MIN 0 // aus, TRACKING_RSSI, TRACKING_GPS, TRACKING_MKCOCKPIT, TRACKING_NMEA
#define TRACKING_MAX 4
 
// Antennen-Nachführung per RSSI
#define TRACKING_HYSTERESE 40 // Hysterese bevor Tracking bei Richtungswechsel anspricht
#define TRACKING_HYST_MIN 0
#define TRACKING_HYST_MAX 100
 
#define FC_FLAG_MOTOR_RUN 0x01
#define FC_FLAG_FLY 0x02
#define FC_FLAG_CALIBRATE 0x04
#define FC_FLAG_MOTOR_START 0x08
 
 
 
typedef struct {
int32_t distance;
int16_t bearing;
} geo_t;
 
 
 
typedef struct {
int32_t Home_Lon; // in 1E-7 degrees
int32_t Home_Lat; // in 1E-7 degrees
int32_t Home_Alt; // in mm
int16_t direction; // ermittelte Konstante aus Mittelposition Antenne geo.bearing - navi_data.CompassHeading
} __attribute__((packed)) HomePos_t;
 
 
 
extern uint8_t coldstart; // Flag erstmaliger MK-Start(Motore) nur nach GPS-Fix
 
 
#ifdef USE_TRACKING
 
void PKT_tracking(void);
 
#endif // #ifdef USE_TRACKING
 
 
 
#endif // TRACKING_H_
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/tracking
Property changes:
Added: svn:ignore
+_doc
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/uart/uart1.c
0,0 → 1,638
/*************************************************************************
Title: Interrupt UART library with receive/transmit circular buffers
Author: Peter Fleury <pfleury@gmx.ch> http://jump.to/fleury
File: $Id: uart.c,v 1.6.2.2 2009/11/29 08:56:12 Peter Exp $
Software: AVR-GCC 4.1, AVR Libc 1.4.6 or higher
Hardware: any AVR with built-in UART,
License: GNU General Public License
 
DESCRIPTION:
An interrupt is generated when the UART has finished transmitting or
receiving a byte. The interrupt handling routines use circular buffers
for buffering received and transmitted data.
 
The UART_RX_BUFFER_SIZE and UART_TX_BUFFER_SIZE variables define
the buffer size in bytes. Note that these variables must be a
power of 2.
 
USAGE:
Refere to the header file uart.h for a description of the routines.
See also example test_uart.c.
 
NOTES:
Based on Atmel Application Note AVR306
 
LICENSE:
Copyright (C) 2006 Peter Fleury
 
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 2 of the License, or
any later version.
 
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
 
*************************************************************************/
 
//############################################################################
//# HISTORY uart1.c
//#
//# 08.08.2015 CB
//# - chg: Umbau ISR(USART1_RX_vect) um Behandlung der NMEA Datensätze
//#
//# 06.08.2015 CB
//# - add: uint8_t receiveNMEA // Flag zur Empfangssteuerung in ISR(USART1_RX_vect)
//# - add: Erweiterung ISR(USART1_RX_vect) um Behandlung der NMEA Datensätze
//#
//# 26.06.2014 OG
//# - del: receiveNMEA
//#
//# 04.07.2013 Cebra
//# - add: neue Funktion uart1_peek
//############################################################################
 
 
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <string.h>
#include <stdbool.h>
#include "uart1.h"
#include "usart.h"
#include "../main.h"
#include "../bluetooth/bluetooth.h"
#include "../tracking/tracking.h"
#include "../avr-nmea-gps-library/nmea.h"
 
//
// constants and macros
//
 
 
// size of RX/TX buffers
#define UART_RX_BUFFER_MASK ( UART_RX_BUFFER_SIZE - 1)
#define UART_TX_BUFFER_MASK ( UART_TX_BUFFER_SIZE - 1)
 
#if ( UART_RX_BUFFER_SIZE & UART_RX_BUFFER_MASK )
#error RX buffer size is not a power of 2
#endif
 
#if ( UART_TX_BUFFER_SIZE & UART_TX_BUFFER_MASK )
#error TX buffer size is not a power of 2
#endif
 
 
// ATmega with two USART
 
#define ATMEGA_USART1
 
#define UART1_STATUS UCSR1A
#define UART1_CONTROL UCSR1B
#define UART1_DATA UDR1
#define UART1_UDRIE UDRIE1
 
 
 
//
// module global variables
//
 
#if defined( ATMEGA_USART1 )
static volatile unsigned char UART1_TxBuf[UART_TX_BUFFER_SIZE];
static volatile unsigned char UART1_RxBuf[UART_RX_BUFFER_SIZE];
static volatile unsigned char UART1_TxHead;
static volatile unsigned char UART1_TxTail;
static volatile unsigned char UART1_RxHead;
static volatile unsigned char UART1_RxTmpHead;
static volatile unsigned char UART1_RxTail;
static volatile unsigned char UART1_LastRxError;
 
static volatile unsigned char UART1_RxTmpHead;;
 
volatile uint16_t UART1_RxError;
 
#endif
 
volatile uint8_t UART1_receiveNMEA = false;
 
 
void SetBaudUart1(uint8_t Baudrate)
{
switch (Baudrate)
{
case Baud_2400: uart1_init( UART_BAUD_SELECT(2400,F_CPU) ); break;
case Baud_4800: uart1_init( UART_BAUD_SELECT(4800,F_CPU) ); break;
// case Baud_9600: uart1_init( UART_BAUD_SELECT(9600,F_CPU) ); break;
case Baud_9600: uart1_init( 129); break;
case Baud_19200: uart1_init( UART_BAUD_SELECT(19200,F_CPU) ); break;
case Baud_38400: uart1_init( UART_BAUD_SELECT(38400,F_CPU) ); break;
case Baud_57600: uart1_init( UART_BAUD_SELECT(57600,F_CPU) ); break;
// case Baud_57600: uart1_init( 21); break;
// case Baud_115200: uart1_init( UART_BAUD_SELECT(115200,F_CPU) ); break;
case Baud_115200: uart1_init( 10 ); break;
}
}
 
//
// these functions are only for ATmegas with two USART
//
 
 
#if defined( ATMEGA_USART1 )
 
#if 0
//--------------------------------------------------------------
// Function: UART1 Receive Complete interrupt
// Purpose: called when the UART1 has received a character
//--------------------------------------------------------------
ISR(USART1_RX_vect)
{
unsigned char tmphead;
unsigned char data;
unsigned char usr;
unsigned char lastRxError;
 
 
// read UART status register and UART data register
usr = UART1_STATUS;
data = UART1_DATA;
 
lastRxError = (usr & (_BV(FE1)|_BV(DOR1)) );
 
// calculate buffer index
tmphead = ( UART1_RxHead + 1) & UART_RX_BUFFER_MASK;
 
if ( tmphead == UART1_RxTail )
{
// error: receive buffer overflow
lastRxError = UART_BUFFER_OVERFLOW >> 8;
UART1_RxError++;
}
else
{
// store new index
UART1_RxHead = tmphead;
// store received data in buffer
UART1_RxBuf[tmphead] = data;
}
UART1_LastRxError = lastRxError;
}
#else
 
#warning Test neue UART ISR für NMEA
 
//--------------------------------------------------------------
// Function: UART1 Receive Complete interrupt, decode NMEA GPGGA
// Purpose: called when the UART1 has received a character
//--------------------------------------------------------------
ISR(USART1_RX_vect)
{
unsigned char tmphead;
unsigned char data;
unsigned char usr;
unsigned char lastRxError;
 
usr = UART1_STATUS;
data = UART1_DATA;
 
lastRxError = (usr & (_BV(FE1)|_BV(DOR1)) );
 
// calculate buffer index
tmphead = ( UART1_RxHead + 1) & UART_RX_BUFFER_MASK;
 
if ( tmphead == UART1_RxTail )
{
// error: receive buffer overflow
lastRxError = UART_BUFFER_OVERFLOW >> 8;
UART1_RxError++;
}
else
{
if (UART1_receiveNMEA)
{
fusedata(data); // NMEA Daten bearbeiten
}
 
else // if (UART1_receiveNMEA)
 
{
// store new index
UART1_RxHead = tmphead;
// store received data in buffer
UART1_RxBuf[tmphead] = data;
}
}
UART1_LastRxError = lastRxError;
}
 
////--------------------------------------------------------------
//// Function: UART1 Receive Complete interrupt, decode NMEA GPGGA
//// Purpose: called when the UART1 has received a character
////--------------------------------------------------------------
//ISR(USART1_RX_vect)
//{
// unsigned char tmphead;
// unsigned char data;
// unsigned char usr;
// unsigned char lastRxError;
//
// static volatile uint8_t GGA;
// static char buffer[6];
// static volatile uint8_t bufferindex;
// static volatile uint8_t NMEAstart,NMEAend = false;
//
// // read UART status register and UART data register
// usr = UART1_STATUS;
// data = UART1_DATA;
//
// lastRxError = (usr & (_BV(FE1)|_BV(DOR1)) );
//
// // calculate buffer index
//
// tmphead = ( UART1_RxHead + 1) & UART_RX_BUFFER_MASK;
//
// if ( tmphead == UART1_RxTail )
// {
// // error: receive buffer overflow
// lastRxError = UART_BUFFER_OVERFLOW >> 8;
// UART1_RxError++;
// }
// else
// {
// if (UART1_receiveNMEA)
// {
// cli();
// switch(data)
// {
// case '$': //start of a packet
//
// if (!NMEAstart && GGA) // falls mitten im Datensatz eine neuer kommt, warum auch immer
// {
// // restore index, war kein GPGGA Datensatz
// UART1_RxHead = UART1_RxTmpHead;
// memset(buffer,0,6);
// bufferindex=0; //wipe all these so they can be reused
// }
// NMEAstart = true;
// NMEAend = false;
// GGA=false;
// bufferindex=0; //wipe all these so they can be reused
//
// UART1_RxTmpHead = tmphead-1; // erstmal sichern, Start des NMEA Datensatzes
// // store new index, erstam in den Buffer schreiben
// UART1_RxHead = tmphead;
// // store received data in buffer
// UART1_RxBuf[tmphead] = data;
//// USART_putc(data);
// sei();
// break;
//
// default: //we have some of the CSV data
// if(bufferindex<6) //dont mess up ! Dont overflow
// {
// buffer[bufferindex]=data; //stick the character in our buffer
// }
//
// if(GGA)
// {
// // store new index, erstam in den Buffer schreiben
// UART1_RxHead = tmphead;
// // store received data in buffer
// UART1_RxBuf[tmphead] = data;
//// USART_putc(data);
//
//
// switch ( data)
// {
// case '\r' :
// GGA = false;
// bufferindex=0; //wipe all these so they can be reused
// NMEAstart = false;
// NMEAend = true;
// UART1_GPGGA++;
// memset(buffer,0,6);
// break; // Ende mit NMEA Datensatz
//
// case '\n' :
// GGA = false;
// bufferindex=0; //wipe all these so they can be reused
// NMEAstart = false;
// NMEAend = true;
// UART1_GPGGA++;
// memset(buffer,0,6);
// break; // Ende mit NMEA Datensatz
// }
//
// }
//
// else if(NMEAstart) //the header, erstes Komma noch nicht gekommen
//
// {
// if(bufferindex<4)
//
// {
// bufferindex++; //increase the position in the buffer
//
// // store new index, erstmal in den Buffer schreiben
// UART1_RxHead = tmphead;
// // store received data in buffer
// UART1_RxBuf[tmphead] = data;
//// USART_putc(data);
//
//
// }
// else
//
// {
//// cli();
// if(!strcmp(buffer,"GPGGA")) //the last character will be a 0(end of string)
//
// {
// GGA=true;
// NMEAstart = false;
// // store new index, erstmal in den Buffer schreiben
// UART1_RxHead = tmphead;
// // store received data in buffer
// UART1_RxBuf[tmphead] = data;
//// USART_putc(data);
//// sei();
// }
//
// else
//
// {
// // restore index, war kein GPGGA Datensatz
//
// UART1_RxHead = UART1_RxTmpHead;
//// commacount=0;
// memset(buffer,0,6);
// bufferindex=0; //wipe all these so they can be reused
// NMEAstart = false;
//// sei();
// }
// }
// }
// else if (!NMEAend && !GGA) UART1_RxHead = UART1_RxTmpHead; // Zeichen verwerfen
//
// } // end switch (data)
// }
//
// else // if (UART1_receiveNMEA)
//
// {
// // store new index
// UART1_RxHead = tmphead;
// // store received data in buffer
// UART1_RxBuf[tmphead] = data;
// }
// }
// UART1_LastRxError = lastRxError;
//}
#endif
 
//--------------------------------------------------------------
// Function: UART1 Data Register Empty interrupt
// Purpose: called when the UART1 is ready to transmit the next byte
//--------------------------------------------------------------
ISR(USART1_UDRE_vect)
{
unsigned char tmptail;
 
 
if ( UART1_TxHead != UART1_TxTail)
{
// calculate and store new buffer index
tmptail = (UART1_TxTail + 1) & UART_TX_BUFFER_MASK;
UART1_TxTail = tmptail;
// get one byte from buffer and write it to UART
UART1_DATA = UART1_TxBuf[tmptail]; // start transmission
}
else
{
// tx buffer empty, disable UDRE interrupt
UART1_CONTROL &= ~_BV(UART1_UDRIE);
}
}
 
 
//--------------------------------------------------------------
// Function: uart1_init()
// Purpose: initialize UART1 and set baudrate
// Input: baudrate using macro UART_BAUD_SELECT()
// Returns: none
//--------------------------------------------------------------
void uart1_init(unsigned int baudrate)
{
UART1_TxHead = 0;
UART1_TxTail = 0;
UART1_RxHead = 0;
UART1_RxTail = 0;
UART1_RxError = 0;
UART1_receiveNMEA = false; //Empfang von NMEA Daten aus
 
 
// Set baud rate
if ( baudrate & 0x8000 )
{
UART1_STATUS = (1<<U2X1); //Enable 2x speed
baudrate &= ~0x8000;
}
UBRR1H = (unsigned char)(baudrate>>8);
UBRR1L = (unsigned char) baudrate;
 
// Enable USART receiver and transmitter and receive complete interrupt
UART1_CONTROL = _BV(RXCIE1)|(1<<RXEN1)|(1<<TXEN1);
 
// Set frame format: asynchronous, 8data, no parity, 1stop bit
#ifdef URSEL1
UCSR1C = (1<<URSEL1)|(3<<UCSZ10);
#else
UCSR1C = (3<<UCSZ10);
// UCSR1C = (1<<UCSZ11) | (1<<UCSZ10); // 8data Bit
#endif
 
 
 
}
 
 
//--------------------------------------------------------------
// Function: uart1_getc()
// Purpose: return byte from ringbuffer
// Returns: lower byte: received byte from ringbuffer
// higher byte: last receive error
//--------------------------------------------------------------
unsigned int uart1_getc(void)
{
unsigned char tmptail;
unsigned char data;
 
 
if ( UART1_RxHead == UART1_RxTail )
{
return UART_NO_DATA; // no data available
}
 
// calculate /store buffer index
tmptail = (UART1_RxTail + 1) & UART_RX_BUFFER_MASK;
UART1_RxTail = tmptail;
 
// get data from receive buffer
data = UART1_RxBuf[tmptail];
 
return (UART1_LastRxError << 8) + data;
 
}/* uart1_getc */
 
 
//--------------------------------------------------------------
// Function: uart1_peek()
// Purpose: Returns the next byte (character) of incoming serial data without removing it from the internal serial buffer
// Returns: lower byte: received byte from ringbuffer
// higher byte: last receive error
//--------------------------------------------------------------
int uart1_peek(void)
{
unsigned char tmptail;
unsigned char data;
 
 
if ( UART1_RxHead == UART1_RxTail )
{
return -1; // no data available
}
 
// calculate /store buffer index
tmptail = (UART1_RxTail + 1) & UART_RX_BUFFER_MASK;
 
// get data from receive buffer
data = UART1_RxBuf[tmptail];
 
return (UART1_LastRxError << 8) + data;
 
}/* uart1_getc */
 
 
//int HardwareSerial::peek(void)
//{
// if (_rx_buffer->head == _rx_buffer->tail) {
// return -1;
// } else {
// return _rx_buffer->buffer[_rx_buffer->tail];
// }
//}
 
 
//--------------------------------------------------------------
// Function: uart1_putc()
// Purpose: write byte to ringbuffer for transmitting via UART
// Input: byte to be transmitted
// Returns: 1 on succes, 0 if remote not ready
//--------------------------------------------------------------
int uart1_putc(unsigned char data)
{
unsigned char tmphead;
 
 
tmphead = (UART1_TxHead + 1) & UART_TX_BUFFER_MASK;
 
while ( tmphead == UART1_TxTail )
{;} // wait for free space in buffer
 
UART1_TxBuf[tmphead] = data;
UART1_TxHead = tmphead;
 
// enable UDRE interrupt
UART1_CONTROL |= _BV(UART1_UDRIE);
return (UART1_LastRxError << 8) + data;
}
 
 
//--------------------------------------------------------------
// Function: uart1_puts()
// Purpose: transmit string to UART1
// Input: string to be transmitted
// Returns: none
//--------------------------------------------------------------
void uart1_puts(const char *s )
{
while (*s)
uart1_putc(*s++);
}
 
 
//--------------------------------------------------------------
// Function: uart1_puts_p()
// Purpose: transmit string from program memory to UART1
// Input: program memory string to be transmitted
// Returns: none
//--------------------------------------------------------------
void uart1_puts_p(const char *progmem_s )
{
register char c;
while ( (c = pgm_read_byte(progmem_s++)) )
uart1_putc(c);
}
 
 
//--------------------------------------------------------------
// Function: uart1_available()
// Purpose: Determine the number of bytes waiting in the receive buffer
// Input: None
// Returns: Integer number of bytes in the receive buffer
//--------------------------------------------------------------
uint16_t uart1_available(void)
{
return (UART_RX_BUFFER_MASK + UART1_RxHead - UART1_RxTail) % UART_RX_BUFFER_MASK;
}
 
 
 
//--------------------------------------------------------------
// Function: uart1_flush()
// Purpose: Flush bytes waiting the receive buffer. Acutally ignores them.
// Input: None
// Returns: None
//--------------------------------------------------------------
void uart1_flush(void)
{
UART1_RxHead = UART1_RxTail;
}
 
 
/*************************************************************************
Function: utoa()
Purpose: convert unsigned integer to ascii
Input: string_buffer, string_buffer_size, unsigned integer value
Returns: first ascii character
**************************************************************************/
char *utoa1(char* buffer, const unsigned int size, unsigned int value)
{
char *p;
 
// p points to last char
p = buffer+size-1;
 
// Set terminating Zero
*p='\0';
 
do
{
*--p = value%10 + '0';
value = value/10;
} while (value!=0 && p>buffer);
 
return p;
}/* utoa */
 
 
 
 
 
 
#endif
//#endif
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/uart/uart1.h
0,0 → 1,194
/************************************************************************
Title: Interrupt UART library with receive/transmit circular buffers
Author: Peter Fleury <pfleury@gmx.ch> http://jump.to/fleury
File: $Id: uart.h,v 1.8.2.1 2007/07/01 11:14:38 peter Exp $
Software: AVR-GCC 4.1, AVR Libc 1.4
Hardware: any AVR with built-in UART, tested on AT90S8515 & ATmega8 at 4 Mhz
License: GNU General Public License
Usage: see Doxygen manual
 
LICENSE:
Copyright (C) 2006 Peter Fleury
 
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 2 of the License, or
any later version.
 
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
 
************************************************************************/
//############################################################################
//# HISTORY uart1.h
//#
//# 06.08.2015 CB
//# - add: uint8_t receiveNMEA // Flag zur Empfangssteuerung in ISR(USART1_RX_vect)
//# - chg: UART_RX_BUFFER_SIZE war 1024, darf aber nur max 256 sein
//#
//# 26.06.2014 OG
//# - del: receiveNMEA
//#
//# 30.03.2013 CB
//# - add: uart1_flush(void); in Headerdatei aufgenommen
//###########################################################################
//
// @defgroup pfleury_uart UART Library
// @code #include <uart.h> @endcode
//
// @brief Interrupt UART library using the built-in UART with transmit and receive circular buffers.
//
// This library can be used to transmit and receive data through the built in UART.
//
// An interrupt is generated when the UART has finished transmitting or
// receiving a byte. The interrupt handling routines use circular buffers
// for buffering received and transmitted data.
//
// The UART_RX_BUFFER_SIZE and UART_TX_BUFFER_SIZE constants define
// the size of the circular buffers in bytes. Note that these constants must be a power of 2.
// You may need to adapt this constants to your target and your application by adding
// CDEFS += -DUART_RX_BUFFER_SIZE=nn -DUART_RX_BUFFER_SIZE=nn to your Makefile.
//
// @note Based on Atmel Application Note AVR306
// @author Peter Fleury pfleury@gmx.ch http://jump.to/fleury
//
 
#ifndef UART_H
#define UART_H
 
#if (__GNUC__ * 100 + __GNUC_MINOR__) < 304
#error "This library requires AVR-GCC 3.4 or later, update to newer AVR-GCC compiler !"
#endif
 
 
// constants and macros
 
 
// @brief UART Baudrate Expression
// @param xtalcpu system clock in Mhz, e.g. 4000000L for 4Mhz
// @param baudrate baudrate in bps, e.g. 1200, 2400, 9600
//
#define UART_BAUD_SELECT(baudRate,xtalCpu) ((xtalCpu)/((baudRate)*16l)-1)
 
// @brief UART Baudrate Expression for ATmega double speed mode
// @param xtalcpu system clock in Mhz, e.g. 4000000L for 4Mhz
// @param baudrate baudrate in bps, e.g. 1200, 2400, 9600
//
#define UART_BAUD_SELECT_DOUBLE_SPEED(baudRate,xtalCpu) (((xtalCpu)/((baudRate)*8l)-1)|0x8000)
 
 
// Size of the circular receive buffer, must be power of 2
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 256 /* 2,4,8,16,32,64,128 or 256 bytes */
#endif
 
// Size of the circular transmit buffer, must be power of 2
#ifndef UART_TX_BUFFER_SIZE
#define UART_TX_BUFFER_SIZE 64 /* 2,4,8,16,32,64,128 or 256 bytes */
#endif
 
// test if the size of the circular buffers fits into SRAM
#if ( (UART_RX_BUFFER_SIZE+UART_TX_BUFFER_SIZE) >= (RAMEND-0x60 ) )
#error "size of UART_RX_BUFFER_SIZE + UART_TX_BUFFER_SIZE larger than size of SRAM"
#endif
 
//global variable
extern volatile uint16_t UART1_RxError;
extern volatile uint8_t UART1_receiveNMEA; // Flag zur Empfangssteuerung in ISR(USART1_RX_vect)
 
 
// high byte error return code of uart_getc()
 
#define UART_FRAME_ERROR 0x0800 // Framing Error by UART
#define UART_OVERRUN_ERROR 0x0400 // Overrun condition by UART
#define UART_BUFFER_OVERFLOW 0x0200 // receive ringbuffer overflow
#define UART_NO_DATA 0x0100 // no receive data available
 
#define TRACKING_RSSI 1
#define TRACKING_GPS 2
#define TRACKING_MKCOCKPIT 3
#define TRACKING_NMEA 4
#define NMEA_receive 5 // Flag zur Empfangssteuerung in ISR(USART1_RX_vect)
//
// function prototypes
//
 
//
// @brief Initialize UART and set baudrate
// @param baudrate Specify baudrate using macro UART_BAUD_SELECT()
// @return none
//
extern void uart_init(unsigned int baudrate);
 
 
//
// @brief Get received byte from ringbuffer
//
// Returns in the lower byte the received character and in the
// higher byte the last receive error.
// UART_NO_DATA is returned when no data is available.
//
// @param void
// @return lower byte: received byte from ringbuffer
// @return higher byte: last receive status
// - \b 0 successfully received data from UART
// - \b UART_NO_DATA
// <br>no receive data available
// - \b UART_BUFFER_OVERFLOW
// <br>Receive ringbuffer overflow.
// We are not reading the receive buffer fast enough,
// one or more received character have been dropped
// - \b UART_OVERRUN_ERROR
// <br>Overrun condition by UART.
// A character already present in the UART UDR register was
// not read by the interrupt handler before the next character arrived,
// one or more received characters have been dropped.
// - \b UART_FRAME_ERROR
// <br>Framing Error by UART
//
extern unsigned int uart_getc(void);
 
 
//
// @brief Put byte to ringbuffer for transmitting via UART
// @param data byte to be transmitted
// @return none
//
 
// @brief Set Baudrate USART1
extern void SetBaudUart1(uint8_t Baudrate);
 
// @brief Initialize USART1 (only available on selected ATmegas) @see uart_init
extern void uart1_init(unsigned int baudrate);
 
// @brief Get received byte of USART1 from ringbuffer. (only available on selected ATmega) @see uart_getc
extern unsigned int uart1_getc(void);
 
// @brief Put byte to ringbuffer for transmitting via USART1 (only available on selected ATmega) @see uart_putc
//extern void uart1_putc(unsigned char data);
extern int uart1_putc(unsigned char data);
 
// @brief Put string to ringbuffer for transmitting via USART1 (only available on selected ATmega) @see uart_puts
extern void uart1_puts(const char *s );
 
// @brief Put string from program memory to ringbuffer for transmitting via USART1 (only available on selected ATmega) @see uart_puts_p
extern void uart1_puts_p(const char *s );
 
// @brief Macro to automatically put a string constant into program memory
#define uart1_puts_P(__s) uart1_puts_p(PSTR(__s))
 
extern char *utoa1(char* buffer, const unsigned int size, unsigned int value);
 
extern uint16_t uart1_available(void);
 
extern int uart1_peek(void);
 
// @brief Flush bytes waiting the receive buffer. Acutally ignores them.
extern void uart1_flush(void);
 
 
#endif // UART_H
 
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/uart/usart.c
0,0 → 1,732
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY usart.c
//#
//# 3.04.2015 Cebra
//# - chg: 2 weitere /r am Ende des gesendeten Strings angefügt, damit Funktion gleich wie im MK-Tool
//#
//# 24.01.2014 OG
//# - add: Debug-Code fuer die ISR-RX Funktion
//# schaltbar via define DEBUG_FC_COMMUNICATION in main.h - der Code
//# kann somit drin bleiben
//# - add: Source-History
//############################################################################
 
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <avr/wdt.h>
#include "../cpu.h"
#include <util/delay.h>
#include <stdarg.h>
 
#include "../main.h"
#include "usart.h"
#include "../lcd/lcd.h"
#include "../timer/timer.h"
#include "uart1.h"
#include "../eeprom/eeprom.h"
#include "../osd/osd.h"
 
 
uint8_t buffer[30];
 
volatile uint8_t txd_buffer[TXD_BUFFER_LEN];
volatile uint8_t txd_complete = TRUE;
 
volatile uint8_t rxd_buffer[RXD_BUFFER_LEN];
volatile uint8_t rxd_buffer_locked = FALSE;
volatile uint8_t ReceivedBytes = 0;
volatile uint8_t *pRxData = 0;
volatile uint8_t RxDataLen = 0;
 
volatile uint16_t stat_crc_error = 0;
volatile uint16_t stat_overflow_error = 0;
 
volatile uint8_t rx_byte;
volatile uint8_t rxFlag = 0;
 
 
#define UART_RXBUFSIZE 64
#define UART_NO_DATA 0x0100 /* no receive data available */
 
volatile static uint8_t rxbuf[UART_RXBUFSIZE];
volatile static uint8_t *volatile rxhead, *volatile rxtail;
 
 
#ifdef DEBUG_FC_COMMUNICATION
char *tmp = (char *)" ";
#endif
 
 
 
/*
 
//-----------------------------------------------------------------------------
// USART1 transmitter ISR
ISR (USART1_TX_vect)
{
static uint16_t ptr_txd1_buffer = 0;
uint8_t tmp_tx1;
 
if(!txd1_complete) // transmission not completed
{
ptr_txd1_buffer++; // [0] was already sent
tmp_tx1 = txd1_buffer[ptr_txd1_buffer];
// if terminating character or end of txd buffer was reached
if((tmp_tx1 == '\r') || (ptr_txd1_buffer == TXD_BUFFER_LEN))
{
ptr_txd1_buffer = 0; // reset txd pointer
txd1_complete = TRUE; // stop transmission
}
UDR1 = tmp_tx1; // send current byte will trigger this ISR again
}
// transmission completed
else ptr_txd1_buffer = 0;
}
 
*/
 
 
#ifdef USART_INT
//-----------------------------------------------------------------------------
// USART0 transmitter ISR
ISR (USART_TX_vect)
{
static uint16_t ptr_txd_buffer = 0;
uint8_t tmp_tx;
 
if(!txd_complete) // transmission not completed
{
ptr_txd_buffer++; // [0] was already sent
tmp_tx = txd_buffer[ptr_txd_buffer];
// if terminating character or end of txd buffer was reached
if((tmp_tx == '\r') || (ptr_txd_buffer == TXD_BUFFER_LEN))
{
ptr_txd_buffer = 0; // reset txd pointer
txd_complete = TRUE; // stop transmission
}
UDR = tmp_tx; // send current byte will trigger this ISR again
}
// transmission completed
else ptr_txd_buffer = 0;
}
#endif
 
 
void SetBaudUart0(uint8_t Baudrate)
{
switch (Baudrate)
{
case Baud_2400: USART_Init( UART_BAUD_SELECT(2400,F_CPU) ); break;
case Baud_4800: USART_Init( UART_BAUD_SELECT(4800,F_CPU) ); break;
case Baud_9600: USART_Init( UART_BAUD_SELECT(9600,F_CPU) ); break;
case Baud_19200: USART_Init( UART_BAUD_SELECT(19200,F_CPU) ); break;
case Baud_38400: USART_Init( UART_BAUD_SELECT(38400,F_CPU) ); break;
case Baud_57600: USART_Init( UART_BAUD_SELECT(57600,F_CPU) ); break;
// case Baud_115200: USART_Init( UART_BAUD_SELECT(115200,F_CPU) ); break;
// Macro erechnet falschen Wert (9,85 = 9) für 115200 Baud mit 20Mhz Quarz, zu grosse Abweichung
 
//#warning "Baurate prüfen wenn kein 20 Mhz Quarz verwendet wird"
 
case Baud_115200: USART_Init( 10 ); break;
}
}
 
 
//-----------------------------------------------------------------------------
//
 
//
//uint8_t uart_getc_nb(uint8_t *c)
//{
// if (rxhead==rxtail) return 0;
// *c = *rxtail;
// if (++rxtail == (rxbuf + UART_RXBUFSIZE)) rxtail = rxbuf;
// return 1;
//}
 
 
 
 
ISR (USART0_RX_vect)
{
static uint16_t crc;
static uint8_t ptr_rxd_buffer = 0;
uint8_t crc1, crc2;
uint8_t c;
// IdleTimer = 0;
 
 
 
if (current_hardware == Wi232)
{
// rx_byte = c;
// rxFlag = 1;
int diff;
uint8_t c;
c=UDR;
diff = rxhead - rxtail;
if (diff < 0) diff += UART_RXBUFSIZE;
if (diff < UART_RXBUFSIZE -1)
{
*rxhead = c;
++rxhead;
if (rxhead == (rxbuf + UART_RXBUFSIZE)) rxhead = rxbuf;
};
// USART_putc (c);
return;
}
 
 
if (current_hardware == MKGPS)
{
// rx_byte = c;
// rxFlag = 1;
int diff;
uint8_t c;
c=UDR;
diff = rxhead - rxtail;
if (diff < 0) diff += UART_RXBUFSIZE;
if (diff < UART_RXBUFSIZE -1)
{
*rxhead = c;
++rxhead;
if (rxhead == (rxbuf + UART_RXBUFSIZE)) rxhead = rxbuf;
};
 
return;
}
 
 
 
c = UDR; // catch the received byte
if (OSD_active && Config.OSD_SendOSD) // Daten an SV2 senden
uart1_putc(c);
 
 
if (rxd_buffer_locked)
return; // if rxd buffer is locked immediately return
 
// the rxd buffer is unlocked
if ((ptr_rxd_buffer == 0) && (c == '#')) // if rxd buffer is empty and syncronisation character is received
{
// OG DEBUG: DEBUG_FC_COMMUNICATION (einstellbar in main.h)
#ifdef DEBUG_FC_COMMUNICATION
lcd_print( "#", MNORMAL ); // OG DEBUG
#endif
rxd_buffer[ptr_rxd_buffer++] = c; // copy 1st byte to buffer
crc = c; // init crc
}
else if (ptr_rxd_buffer < RXD_BUFFER_LEN) // collect incomming bytes
{
if(c != '\r') // no termination character
{
rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer
crc += c; // update crc
}
else // termination character was received
{
// the last 2 bytes are no subject for checksum calculation
// they are the checksum itself
crc -= rxd_buffer[ptr_rxd_buffer-2];
crc -= rxd_buffer[ptr_rxd_buffer-1];
// calculate checksum from transmitted data
crc %= 4096;
crc1 = '=' + crc / 64;
crc2 = '=' + crc % 64;
// compare checksum to transmitted checksum bytes
if((crc1 == rxd_buffer[ptr_rxd_buffer-2]) && (crc2 == rxd_buffer[ptr_rxd_buffer-1]))
{ // checksum valid
 
// OG DEBUG: DEBUG_FC_COMMUNICATION (einstellbar in main.h)
#ifdef DEBUG_FC_COMMUNICATION
*tmp = rxd_buffer[2];
lcd_print( tmp, MNORMAL );
lcd_putc( 0,0, '[', MNORMAL );
lcd_putc( 1,0, rxd_buffer[2], MNORMAL );
lcd_putc( 2,0, ']', MNORMAL ); x
if( rxd_buffer[2] != 'k' ) set_beep( 13, 0x0001, BeepNormal);
if( rxd_buffer[2] == 'Q' ) set_beep( 150, 0x0080, BeepNormal);
#endif
rxd_buffer[ptr_rxd_buffer] = '\r'; // set termination character
ReceivedBytes = ptr_rxd_buffer + 1;// store number of received bytes
if (mode == rxd_buffer[2])
{
rxd_buffer_locked = TRUE; // lock the rxd buffer
// if 2nd byte is an 'R' enable watchdog that will result in an reset
if(rxd_buffer[2] == 'R') {wdt_enable(WDTO_250MS);} // Reset-Commando
}
}
else
{ // checksum invalid
stat_crc_error++;
rxd_buffer_locked = FALSE; // unlock rxd buffer
}
ptr_rxd_buffer = 0; // reset rxd buffer pointer
}
}
else // rxd buffer overrun
{
stat_overflow_error++;
ptr_rxd_buffer = 0; // reset rxd buffer
rxd_buffer_locked = FALSE; // unlock rxd buffer
}
}
 
 
//-----------------------------------------------------------------------------
// Function: uart0_getc()
// Purpose: return byte from ringbuffer
// Returns: lower byte: received byte from ringbuffer
// higher byte: last receive error
//-----------------------------------------------------------------------------
char USART_getc(void)
{
char val;
 
// while(rxhead==rxtail) ;
if (rxhead==rxtail)
return val=0;
// IdleTimer = 0;
val = *rxtail;
if (++rxtail == (rxbuf + UART_RXBUFSIZE))
rxtail = rxbuf;
 
return val;
}
 
 
uint8_t uart_getc_nb(uint8_t *c)
{
if (rxhead==rxtail)
return 0;
// IdleTimer = 0;
*c = *rxtail;
if (++rxtail == (rxbuf + UART_RXBUFSIZE))
rxtail = rxbuf;
return 1;
}
//-----------------------------------------------------------------------------
//
 
 
 
 
 
//-----------------------------------------------------------------------------
//
void USART_Init (unsigned int baudrate)
{
// set clock divider
// #undef BAUD
// #define BAUD baudrate
// #include <util/setbaud.h>
// UBRRH = UBRRH_VALUE;
// UBRRL = UBRRL_VALUE;
 
//#ifndef F_CPU
///* In neueren Version der WinAVR/Mfile Makefile-Vorlage kann
// F_CPU im Makefile definiert werden, eine nochmalige Definition
// hier wuerde zu einer Compilerwarnung fuehren. Daher "Schutz" durch
// #ifndef/#endif
//
// Dieser "Schutz" kann zu Debugsessions führen, wenn AVRStudio
// verwendet wird und dort eine andere, nicht zur Hardware passende
// Taktrate eingestellt ist: Dann wird die folgende Definition
// nicht verwendet, sondern stattdessen der Defaultwert (8 MHz?)
// von AVRStudio - daher Ausgabe einer Warnung falls F_CPU
// noch nicht definiert: */
//#warning "F_CPU war noch nicht definiert, wird nun nachgeholt mit 4000000"
//#define F_CPU 18432000UL // Systemtakt in Hz - Definition als unsigned long beachten
// Ohne ergeben sich unten Fehler in der Berechnung
//#endif
//#define BAUD 115200UL // Baudrate
//
//// Berechnungen
//#define UBRR_VAL ((F_CPU+BAUD*8)/(BAUD*16)-1) // clever runden
//#define BAUD_REAL (F_CPU/(16*(UBRR_VAL+1))) // Reale Baudrate
//#define BAUD_ERROR ((BAUD_REAL*1000)/BAUD) // Fehler in Promille, 1000 = kein Fehler.
//
//
//#if ((BAUD_ERROR<990) || (BAUD_ERROR>1010))
// #error "Systematischer Fehler der Baudrate grösser 1% und damit zu hoch!"
//#endif
 
 
UBRRH = (unsigned char)(baudrate>>8);
UBRRL = (unsigned char) baudrate;
// UBRRH = (unsigned char)(BAUD_REAL>>8);
// UBRRL = (unsigned char) BAUD_REAL;
 
#if USE_2X
UCSRA |= (1 << U2X); // enable double speed operation
#else
UCSRA &= ~(1 << U2X); // disable double speed operation
#endif
 
// set 8N1
#if defined (__AVR_ATmega8__) || defined (__AVR_ATmega32__)
UCSRC = (1 << URSEL) | (1 << UCSZ1) | (1 << UCSZ0);
#else
UCSRC = (1 << UCSZ1) | (1 << UCSZ0);
#endif
UCSRB &= ~(1 << UCSZ2);
 
// flush receive buffer
while ( UCSRA & (1 << RXC) ) UDR;
 
UCSRB |= (1 << RXEN) | (1 << TXEN);
#ifdef USART_INT
UCSRB |= (1 << RXCIE) | (1 << TXCIE);
#else
UCSRB |= (1 << RXCIE);
#endif
 
rxhead = rxtail = rxbuf;
 
}
 
 
 
 
 
//-----------------------------------------------------------------------------
// disable the txd pin of usart
void USART_DisableTXD (void)
{
#ifdef USART_INT
UCSRB &= ~(1 << TXCIE); // disable TX-Interrupt
#endif
UCSRB &= ~(1 << TXEN); // disable TX in USART
DDRB &= ~(1 << DDB3); // set TXD pin as input
PORTB &= ~(1 << PORTB3); // disable pullup on TXD pin
}
 
//-----------------------------------------------------------------------------
// enable the txd pin of usart
void USART_EnableTXD (void)
{
DDRB |= (1 << DDB3); // set TXD pin as output
PORTB &= ~(1 << PORTB3); // disable pullup on TXD pin
UCSRB |= (1 << TXEN); // enable TX in USART
#ifdef USART_INT
UCSRB |= (1 << TXCIE); // enable TX-Interrupt
#endif
}
 
//-----------------------------------------------------------------------------
// short script to directly send a request thorugh usart including en- and disabling it
// where <address> is the address of the receipient, <label> is which data set to request
// and <ms> represents the milliseconds delay between data
void USART_request_mk_data (uint8_t cmd, uint8_t addr, uint8_t ms)
{
USART_EnableTXD (); // re-enable TXD pin
 
unsigned char mstenth = ms/10;
SendOutData(cmd, addr, 1, &mstenth, 1);
// wait until command transmitted
while (txd_complete == FALSE);
 
USART_DisableTXD (); // disable TXD pin again
}
 
//-----------------------------------------------------------------------------
//
void USART_putc (char c)
{
#ifdef USART_INT
#else
loop_until_bit_is_set(UCSRA, UDRE);
UDR = c;
#endif
}
 
 
 
//-----------------------------------------------------------------------------
//
void USART_puts (char *s)
{
#ifdef USART_INT
#else
while (*s)
{
USART_putc (*s);
s++;
}
#endif
}
 
//-----------------------------------------------------------------------------
//
void USART_puts_p (const char *s)
{
#ifdef USART_INT
#else
while (pgm_read_byte(s))
{
USART_putc (pgm_read_byte(s));
s++;
}
#endif
}
 
//-----------------------------------------------------------------------------
//
void SendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...) // uint8_t *pdata, uint8_t len, ...
{
va_list ap;
uint16_t pt = 0;
uint8_t a,b,c;
uint8_t ptr = 0;
uint16_t tmpCRC = 0;
 
uint8_t *pdata = 0;
int len = 0;
 
txd_buffer[pt++] = '#'; // Start character
txd_buffer[pt++] = 'a' + addr; // Address (a=0; b=1,...)
txd_buffer[pt++] = cmd; // Command
 
va_start(ap, numofbuffers);
if(numofbuffers)
{
pdata = va_arg (ap, uint8_t*);
len = va_arg (ap, int);
ptr = 0;
numofbuffers--;
}
 
while(len)
{
if(len)
{
a = pdata[ptr++];
len--;
if((!len) && numofbuffers)
{
pdata = va_arg(ap, uint8_t*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else
a = 0;
 
if(len)
{
b = pdata[ptr++];
len--;
if((!len) && numofbuffers)
{
pdata = va_arg(ap, uint8_t*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else
b = 0;
 
if(len)
{
c = pdata[ptr++];
len--;
if((!len) && numofbuffers)
{
pdata = va_arg(ap, uint8_t*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else
c = 0;
 
txd_buffer[pt++] = '=' + (a >> 2);
txd_buffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4));
txd_buffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6));
txd_buffer[pt++] = '=' + ( c & 0x3f);
}
va_end(ap);
 
for(a = 0; a < pt; a++)
{
tmpCRC += txd_buffer[a];
}
tmpCRC %= 4096;
txd_buffer[pt++] = '=' + tmpCRC / 64;
txd_buffer[pt++] = '=' + tmpCRC % 64;
txd_buffer[pt++] = '\r';
txd_buffer[pt++] = '\r'; // Add 3.4.2015 Cebra
txd_buffer[pt++] = '\r'; // Add 3.4.2015 Cebra
 
txd_complete = FALSE;
#ifdef USART_INT
UDR = txd_buffer[0]; // initiates the transmittion (continued in the TXD ISR)
#else
for(a = 0; a < pt; a++)
{
loop_until_bit_is_set(UCSRA, UDRE);
UDR = txd_buffer[a];
}
txd_complete = TRUE;
#endif
}
 
//-----------------------------------------------------------------------------
//
void Decode64 (void)
{
uint8_t a,b,c,d;
uint8_t ptrIn = 3;
uint8_t ptrOut = 3;
uint8_t len = ReceivedBytes - 6;
 
while (len)
{
a = rxd_buffer[ptrIn++] - '=';
b = rxd_buffer[ptrIn++] - '=';
c = rxd_buffer[ptrIn++] - '=';
d = rxd_buffer[ptrIn++] - '=';
//if(ptrIn > ReceivedBytes - 3) break;
 
if (len--)
rxd_buffer[ptrOut++] = (a << 2) | (b >> 4);
else
break;
 
if (len--)
rxd_buffer[ptrOut++] = ((b & 0x0f) << 4) | (c >> 2);
else
break;
 
if (len--)
rxd_buffer[ptrOut++] = ((c & 0x03) << 6) | d;
else
break;
}
pRxData = &rxd_buffer[3];
RxDataLen = ptrOut - 3;
}
 
 
//-----------------------------------------------------------------------------
//
void SwitchToNC (void)
{
 
if(hardware == NC)
{
// switch to NC
USART_putc (0x1b);
USART_putc (0x1b);
USART_putc (0x55);
USART_putc (0xaa);
USART_putc (0x00);
current_hardware = NC;
_delay_ms (50);
}
}
 
//-----------------------------------------------------------------------------
//
 
 
//-----------------------------------------------------------------------------
//
void SwitchToWi232 (void)
{
 
// if(hardware == NC)
{
// switch to Wi232
current_hardware = Wi232;
_delay_ms (50);
}
}
 
//-----------------------------------------------------------------------------
//
void SwitchToFC (void)
{
uint8_t cmd;
 
if (current_hardware == NC)
{
// switch to FC
cmd = 0x00; // 0 = FC, 1 = MK3MAG, 2 = MKGPS
SendOutData('u', ADDRESS_NC, 1, &cmd, 1);
current_hardware = FC;
_delay_ms (50);
}
}
 
//-----------------------------------------------------------------------------
//
void SwitchToMAG (void)
{
uint8_t cmd;
 
if (current_hardware == NC)
{
// switch to MK3MAG
cmd = 0x01; // 0 = FC, 1 = MK3MAG, 2 = MKGPS
SendOutData('u', ADDRESS_NC, 1, &cmd, 1);
current_hardware = MK3MAG;
_delay_ms (50);
}
}
 
//-----------------------------------------------------------------------------
//
void SwitchToGPS (void)
{
uint8_t cmd;
if (current_hardware == NC)
{
// switch to MKGPS
cmd = 0x02; // 0 = FC, 1 = MK3MAG, 2 = MKGPS
SendOutData('u', ADDRESS_NC, 1, &cmd, 1);
current_hardware = MKGPS;
_delay_ms (50);
}
}
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/uart/usart.h
0,0 → 1,162
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY usart.h
//#
//# 24.01.2014 OG
//# - fix: RXD_BUFFER_LEN und TXD_BUFFER_LEN vergroessert 180 auf 230 wegen
//# neuer FC-Version (FC v2.03)
//# - add: Source-History
//############################################################################
 
 
#ifndef _USART_H
#define _USART_H
 
//--------------------------------------------------------------
//
#ifndef FALSE
#define FALSE 0
#endif
#ifndef TRUE
#define TRUE 1
#endif
 
// addresses
#define ADDRESS_ANY 0
#define ADDRESS_FC 1
#define ADDRESS_NC 2
#define ADDRESS_MAG 3
 
// must be at least 4('#'+Addr+'CmdID'+'\r')+ (80 * 4)/3 = 111 bytes
//#define TXD_BUFFER_LEN 180
//#define RXD_BUFFER_LEN 180
 
#define TXD_BUFFER_LEN 230
#define RXD_BUFFER_LEN 230
 
// Baud rate of the USART
#define USART_BAUD 57600
//#define USART_BAUD 125000
 
//--------------------------------------------------------------
//
extern uint8_t buffer[30];
 
extern volatile uint8_t txd_buffer[TXD_BUFFER_LEN];
extern volatile uint8_t txd_complete;
extern volatile uint8_t txd1_buffer[TXD_BUFFER_LEN];
extern volatile uint8_t txd1_complete;
extern volatile uint8_t rxd_buffer[RXD_BUFFER_LEN];
extern volatile uint8_t rxd_buffer_locked;
extern volatile uint8_t ReceivedBytes;
extern volatile uint8_t *pRxData;
extern volatile uint8_t RxDataLen;
 
extern volatile uint16_t stat_crc_error;
extern volatile uint16_t stat_overflow_error;
 
extern volatile uint8_t rxFlag;
extern volatile uint8_t rx_byte;
 
//--------------------------------------------------------------
//
void SetBaudUart0(uint8_t Baudrate);
void USART_Init (unsigned int baudrate);
void USART_DisableTXD (void);
void USART_EnableTXD (void);
void USART_request_mk_data (uint8_t cmd, uint8_t addr, uint8_t ms);
 
void USART_putc (char c);
void USART_puts (char *s);
void USART_puts_p (const char *s);
 
 
extern char USART_getc(void);
void SendOutData (uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...); // uint8_t *pdata, uint8_t len, ...
//void SendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, uint8_t *pdata, uint8_t len); // uint8_t *pdata, uint8_t len, ...
void Decode64 (void);
 
void SwitchToNC (void);
void SwitchToFC (void);
void SwitchToMAG (void);
void SwitchToGPS (void);
void SwitchToWi232 (void);
void debug1(void);
 
uint8_t uart_getc_nb(uint8_t*);
 
//--------------------------------------------------------------
//Anpassen der seriellen Schnittstellen Register
#define USART_RXC_vect USART0_RX_vect
//--------------------------------------------------------------
#define UCSRA UCSR0A
#define UCSRB UCSR0B
#define UCSRC UCSR0C
#define UDR UDR0
#define UBRRL UBRR0L
#define UBRRH UBRR0H
 
// UCSRA
#define RXC RXC0
#define TXC TXC0
#define UDRE UDRE0
#define FE FE0
#define UPE UPE0
#define U2X U2X0
#define MPCM MPCM0
 
// UCSRB
#define RXCIE RXCIE0
#define TXCIE TXCIE0
#define UDRIE UDRIE0
#define TXEN TXEN0
#define RXEN RXEN0
#define UCSZ2 UCSZ02
#define RXB8 RXB80
#define TXB8 TXB80
 
// UCSRC
#define UMSEL1 UMSEL01
#define UMSEL0 UMSEL00
#define UPM1 UPM01
#define UPM0 UPM00
#define USBS USBS0
#define UCSZ1 UCSZ01
#define UCSZ0 UCSZ00
#define UCPOL UCPOL0
 
 
#endif
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/utils/i2cmaster.h
0,0 → 1,178
#ifndef _I2CMASTER_H
#define _I2CMASTER_H 1
/*************************************************************************
* Title: C include file for the I2C master interface
* (i2cmaster.S or twimaster.c)
* Author: Peter Fleury <pfleury@gmx.ch> http://jump.to/fleury
* File: $Id: i2cmaster.h,v 1.10 2005/03/06 22:39:57 Peter Exp $
* Software: AVR-GCC 3.4.3 / avr-libc 1.2.3
* Target: any AVR device
* Usage: see Doxygen manual
**************************************************************************/
 
#ifdef DOXYGEN
/**
@defgroup pfleury_ic2master I2C Master library
@code #include <i2cmaster.h> @endcode
@brief I2C (TWI) Master Software Library
 
Basic routines for communicating with I2C slave devices. This single master
implementation is limited to one bus master on the I2C bus.
 
This I2c library is implemented as a compact assembler software implementation of the I2C protocol
which runs on any AVR (i2cmaster.S) and as a TWI hardware interface for all AVR with built-in TWI hardware (twimaster.c).
Since the API for these two implementations is exactly the same, an application can be linked either against the
software I2C implementation or the hardware I2C implementation.
 
Use 4.7k pull-up resistor on the SDA and SCL pin.
Adapt the SCL and SDA port and pin definitions and eventually the delay routine in the module
i2cmaster.S to your target when using the software I2C implementation !
Adjust the CPU clock frequence F_CPU in twimaster.c or in the Makfile when using the TWI hardware implementaion.
 
@note
The module i2cmaster.S is based on the Atmel Application Note AVR300, corrected and adapted
to GNU assembler and AVR-GCC C call interface.
Replaced the incorrect quarter period delays found in AVR300 with
half period delays.
@author Peter Fleury pfleury@gmx.ch http://jump.to/fleury
 
@par API Usage Example
The following code shows typical usage of this library, see example test_i2cmaster.c
 
@code
 
#include <i2cmaster.h>
 
 
#define Dev24C02 0xA2 // device address of EEPROM 24C02, see datasheet
 
int main(void)
{
unsigned char ret;
 
i2c_init(); // initialize I2C library
 
// write 0x75 to EEPROM address 5 (Byte Write)
i2c_start_wait(Dev24C02+I2C_WRITE); // set device address and write mode
i2c_write(0x05); // write address = 5
i2c_write(0x75); // write value 0x75 to EEPROM
i2c_stop(); // set stop conditon = release bus
 
 
// read previously written value back from EEPROM address 5
i2c_start_wait(Dev24C02+I2C_WRITE); // set device address and write mode
 
i2c_write(0x05); // write address = 5
i2c_rep_start(Dev24C02+I2C_READ); // set device address and read mode
 
ret = i2c_readNak(); // read one byte from EEPROM
i2c_stop();
 
for(;;);
}
@endcode
 
*/
#endif /* DOXYGEN */
 
/**@{*/
 
#if (__GNUC__ * 100 + __GNUC_MINOR__) < 304
#error "This library requires AVR-GCC 3.4 or later, update to newer AVR-GCC compiler !"
#endif
 
#include <avr/io.h>
 
/** defines the data direction (reading from I2C device) in i2c_start(),i2c_rep_start() */
#define I2C_READ 1
 
/** defines the data direction (writing to I2C device) in i2c_start(),i2c_rep_start() */
#define I2C_WRITE 0
 
 
/**
@brief initialize the I2C master interace. Need to be called only once
@param void
@return none
*/
extern void i2c_init(void);
 
 
/**
@brief Terminates the data transfer and releases the I2C bus
@param void
@return none
*/
extern void i2c_stop(void);
 
 
/**
@brief Issues a start condition and sends address and transfer direction
@param addr address and transfer direction of I2C device
@retval 0 device accessible
@retval 1 failed to access device
*/
extern unsigned char i2c_start(unsigned char addr);
 
 
/**
@brief Issues a repeated start condition and sends address and transfer direction
 
@param addr address and transfer direction of I2C device
@retval 0 device accessible
@retval 1 failed to access device
*/
extern unsigned char i2c_rep_start(unsigned char addr);
 
 
/**
@brief Issues a start condition and sends address and transfer direction
If device is busy, use ack polling to wait until device ready
@param addr address and transfer direction of I2C device
@return none
*/
extern void i2c_start_wait(unsigned char addr);
 
/**
@brief Send one byte to I2C device
@param data byte to be transfered
@retval 0 write successful
@retval 1 write failed
*/
extern unsigned char i2c_write(unsigned char data);
 
 
/**
@brief read one byte from the I2C device, request more data from device
@return byte read from I2C device
*/
extern unsigned char i2c_readAck(void);
 
/**
@brief read one byte from the I2C device, read is followed by a stop condition
@return byte read from I2C device
*/
extern unsigned char i2c_readNak(void);
 
/**
@brief read one byte from the I2C device
Implemented as a macro, which calls either i2c_readAck or i2c_readNak
@param ack 1 send ack, request more data from device<br>
0 send nak, read is followed by a stop condition
@return byte read from I2C device
*/
extern unsigned char i2c_read(unsigned char ack);
#define i2c_read(ack) (ack) ? i2c_readAck() : i2c_readNak();
 
 
/**@}*/
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/utils/menuctrl.c
0,0 → 1,1501
/*****************************************************************************
* Copyright (C) 2013 Oliver Gemesi *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
*****************************************************************************/
 
//############################################################################
//# HISTORY menuctrl.c
//#
//# 11.06.2014 OG
//# - add: MenuCtrl_GetMenuIndex()
//#
//# 31.05.2014 OG
//# - chg: MenuCtrl_Refresh() - umgestellt auf PKT_KeylineUpDown()
//#
//# 14.05.2014 OG
//# - chg: include "../mk/paramset.h" geaendert auf "../mksettings/paramset.h"
//# - chg: include "../mk/mkparameters.h" geaendert auf "../mksettings/mkparameters.h"
//#
//# 11.05.2014 OG
//# - add: MenuCtrl_SetTitleFromParentItem()
//# - add: MenuCtrl_GetItemText(), MenuCtrl_IsItemTextPGM()
//# - chg: _MenuCtrl_Error() - auf PKT_Popup_P() umgestellt, Layout geaendert und
//# einen neuen Fehler (NOPARENTMENU) hinzugefuegt
//#
//# 09.05.2014 OG
//# - fix: MenuCtrl_Refresh() Anzeige von deaktivierten MK-Parametern (Favoriten)
//# Wenn MK-Paramketer-Menueeintraege deaktiviert sind werden sie vom
//# aktuellen MK-Parameterset nicht unterstuetzt - dennoch wurde der
//# aktuelle Wert des MK-Parameters im Menuepunkt (ganz rechts) angezeigt.
//# Das ist jetzt behoben - es wird kein Wert angezeigt (stattdessen "***")
//# und auch keine entsprechende editParam-Funktionen aufgerufen.
//#
//# 07.05.2014 OG
//# - add: MenuCtrl_PushSeparatorID()
//#
//# 06.05.2014 OG
//# - chg: MenuCtrl_Refresh() Keyline leicht angepasst
//# - chg: 'not possible' Anzeige (bei deaktiviertem Item) umgestellt auf
//# PKT_Popup_P()
//# - add: MenuCtrl_GetItemIdByIndex(), MenuCtrl_GetItemCount()
//#
//# 05.05.2014 OG
//# - chg: MenuCtrl_Control()
//# -> Unterstuetzung fuer: MenuCtrl_SetMove() - Menueeintraege verschieben
//# - chg: MenuCtrl_Refresh() - Anpassung Slider fuer MenuCtrl_SetDelete()
//# - add: MenuCtrl_SetDelete(), MenuCtrl_SetMove()
//# - add: _MenuCtrl_SwapItem()
//# - add: die Datenstruktur vom Menue wurde erweitert um die Eigenschaften
//# canMove und canDelete
//#
//# 17.04.2014 OG
//# - chg: MENUCTRL_MAXITEMS von 22 auf 28 erhoeht
//#
//# 30.03.2014 OG
//# - del: MenuCtrl_PushML_P(), MenuCtrl_PushML() (Umstellung Sprachen abgeschlossen)
//# - add: MenuCtrl_PushML2(), MenuCtrl_PushML2_P() fuer Umstellung von 3 auf 2 Sprachen
//#
//# 29.03.2014 OG
//# - chg: default MENUDEFAULT_SHOWBATT auf true umgestellt (=PKT-Batterie anzeigen)
//# - chg: MenuCtrl_Control() umgestellt auf clear_key_all()
//#
//# 24.03.2014 OG
//# - add: MenuCtrl_PushSeparator() - fuegt eine Trennlinie im Menue ein
//# - chg: MenuCtrl_Refresh() Codeoptimierung bzgl. topspace/Zeile loeschen/Slider
//# - fix: MenuCtrl_Control() es wurde zuoft ein Screen-Refresh durchgefuehrt
//#
//# 23.03.2014 OG
//# - add: Unterstuetzung fuer MK-Parameter-Edit (mkparameters.c)
//# - chg: MenuCtrl_Refresh() Unterstuetzung fuer MENU_PARAMEDIT
//# - add: MenuCtrl_PushParamEdit()
//# - add: paramset.h und mkparameters.h
//#
//# 04.03.2014 OG
//# - fix: MenuCtrl_Refresh() bei einem blauen Display (das ist wohl schneller
//# in der Anzeige als das S/W-Display) flackerte der Menue-Slider
//#
//# 17.02.2014 OG
//# - add: MenuCtrl_SetTopSpace()
//# - chg: MenuCtrl_Refresh() angepasst auf MenuCtrl_SetTopSpace()
//#
//# 15.02.2014 OG
//# - add: MenuCtrl_ItemSelect()
//#
//# 01.02.2014 OG
//# - chg: MENUCTRL_MAXITEMS von 16 auf 22 fuer MK_parameters
//# - fix: _MenuCtrl_Error() Anzeigezeit von Menu-Errors auf 8 Sekunden verlaengert
//# und Anzeige von "menuctrl.c"
//#
//# 07.07.2013 OG
//# - add: MenuCtrl_ItemMarkR() - Markiert einen Menueeintrag mit einem Haken am ENDE (Rechts)
//#
//# 24.05.2013 OG
//# - chg: MenuCtrl_Push... Funktionen vereinheitlicht mit internen Aenderungen
//# betrifft externe Funktionsaufrufe die geändert wurden
//# - chg: MenuCtrl_Refresh() Anpassungen und Optimierung
//# - add: MenuCtrl_ItemMark()
//# - del: MenuCtrl_PushSimple_P(), MenuCtrl_PushSimple()
//#
//# 23.05.2013 OG
//# - add: MenuCtrl_PushSimple_P(), MenuCtrl_PushSimple()
//# - fix: MenuCtrl_Control() Eventcode Rueckgabe bei KEY_ENTER
//#
//# 22.05.2013 OG
//# - fix: nach Aufruf einer Menuefunktion in MenuCtrl_Control() jetzt
//# get_key_press(KEY_ALL)
//#
//# 21.05.2013 OG
//# - add: MenuCtrl_ShowLevel()
//#
//# 20.05.2013 OG
//# - chg: MenuCtrl_Control() wieder mit get_key_press(KEY_ALL) ergaenzt
//# wenn aufgerufen mit MENUCTRL_EVENT oder erster Aufruf mit RETURN
//#
//# 20.05.2013 OG
//# - chg: Space am Anfang der Titelanzeige
//#
//# 19.05.2013 OG
//# - add: define MENU_SHOWLEVEL mit dem der aktuelle Menuelevel in der
//# Titelzeile angezeigt werden kann
//# - fix: Redraw-Logik bei MENUCTRL_RETURN
//# - chg: MenuCtrl_Control() erweitert um PKT_Update()
//#
//# 18.05.2013 OG - NEU
//############################################################################
 
#include "../cpu.h"
#include <avr/io.h>
#include <inttypes.h>
#include <stdlib.h>
#include <avr/pgmspace.h>
#include <avr/wdt.h>
#include <util/delay.h>
#include <string.h> // memset
#include <stdarg.h>
 
#include "../main.h"
#include "../lcd/lcd.h"
#include "../eeprom/eeprom.h"
#include "../messages.h"
#include "../lipo/lipo.h"
#include "../menu.h"
#include "../pkt/pkt.h"
#include "../mksettings/paramset.h"
#include "../mksettings/mkparameters.h"
#include "menuctrl.h"
 
 
//#############################################################################################
//# internal defines & structs
//#############################################################################################
 
#define MENU_SHOWLEVEL false // Anzeige der Menue-Verschachtelungstiefe in der Titelzeile
// zeigt dem Benutzer wie weit er wieder zurueckspringen muss
// um in das Hauptmenue zu kommen
 
#define MENUDEFAULT_CYCLE false // cycle: wenn Menue am Ende dann wieder zum Anfang
#define MENUDEFAULT_SHOWBATT true // showbatt: zeigt PKT-Batterie im Menuetitel ganz rechts
#define MENUDEFAULT_BEEP true // beep: wenn Cursor ueber Ende/Anfang
 
 
#define MENUCTRL_MAXMENUES 6 // Anzahl max. verschachlteter Menues
//#define MENUCTRL_MAXITEMS 22 // Anzahl max. Menu-Items pro Menue (verbraucht Speicher)
//#define MENUCTRL_MAXITEMS 28 // Anzahl max. Menu-Items pro Menue (verbraucht Speicher)
#define MENUCTRL_MAXITEMS 34 // Anzahl max. Menu-Items pro Menue (verbraucht Speicher)
#define ERROR_NOMENU 1 // Errorcode
#define ERROR_MAXMENU 2 // Errorcode
#define ERROR_MAXITEM 3 // Errorcode
#define ERROR_NOITEM 4 // Errorcode
#define ERROR_NOPARENTMENU 5 // Errorcode
 
//-----------------------------------------------------------
// typedef: scrollbox_key_t
//-----------------------------------------------------------
typedef struct
{
uint8_t active; // Taste aktiv? (true/false)
const char *text; // Tastentext
void (*func)(void); // ggf. Funktions-Pointer (0=keine Funktion)
} menue_key_t;
 
 
//---------------------------
// typedef: einzelnes Menueitem
//---------------------------
typedef struct
{
uint8_t id;
uint8_t type; // MENU_ITEM, MENU_SUB, MENU_PARAMEDIT
uint8_t disabled; // true / false (deaktiviert einen Menuepunkt)
uint8_t mark; // true / false (markiert einen Menuepunkt Links '*')
uint8_t markR; // true / false (markiert einen Menuepunkt Rechts)
uint8_t textPGM; // true / false (true = text in PROGMEN; false = text im RAM)
uint8_t textcount; // 1 .. NUM_LANG
const char *text[NUM_LANG]; // de, en, nl (NUM_LANG aus messages.h)
void (*func)(void);
} menue_item_t;
 
 
//---------------------------
// typedef: Menueitem Liste
//---------------------------
typedef struct
{
uint8_t active; // aktives item
uint8_t itemcount; // Anzahl Items
uint8_t scroll_pos; // aktuelle obere Anzeigezeile
uint8_t display_pos; // aktuelle obere Anzeigezeile
uint8_t topspace; // obere Leerzeilen - default=0 (Vorsicht! ggf. nur bedingt einsetzbar bei Menues die ohne scrollen auskommen!)
uint8_t firstredraw; // true / false (flag fuer ein erstes redraw bei MENUCTRL_RETURN)
uint8_t cycle; // true / false
uint8_t showbatt; // true / false
uint8_t beep; // true / false
uint8_t canMove; // true / false
uint8_t canDelete; // false/0 = kein entfernen; true/1 = entfernen mit Nachfrage; 2 = entfernen ohne Nachfrage
uint8_t titlePGM; // true / false
const char *title; // Menuetitel (oberste Zeile) (ggf. Multisprache machen?)
uint8_t lastkey; // verwendet von GetKey()
menue_key_t key_enter;
menue_key_t key_enter_long;
menue_key_t key_esc;
menue_key_t key_esc_long;
menue_item_t item[MENUCTRL_MAXITEMS];
} menue_t;
 
uint8_t showlevel = MENU_SHOWLEVEL; // Anzeige Menulevel in der Titelanzeige
int8_t midx = -1; // aktives Menue; -1 = kein Menue
menue_t menu[MENUCTRL_MAXMENUES]; // Stack fuer n geschachltete Menues
 
 
 
//#############################################################################################
//# PRIVAT funcs
//#############################################################################################
 
 
//--------------------------------------------------------------
// INTERN
//--------------------------------------------------------------
void _MenuCtrl_Error( uint8_t error )
{
const char *pStr = NULL;
 
switch( error )
{
case ERROR_NOMENU: pStr = PSTR("NOMENU"); break;
case ERROR_MAXMENU: pStr = PSTR("MAXMENU"); break;
case ERROR_MAXITEM: pStr = PSTR("MAXITEM"); break;
case ERROR_NOITEM: pStr = PSTR("NOITEM"); break;
case ERROR_NOPARENTMENU: pStr = PSTR("NOPARENTMENU"); break;
}
 
set_beep( 1000, 0x000f, BeepNormal); // Beep Error
PKT_Popup_P( 10000, PSTR("menuctrl.c"), 0, PSTR("* ERROR *"), pStr ); // 10000 = max. 100 Sekunden anzeigen
}
 
 
//--------------------------------------------------------------
// INTERN
//--------------------------------------------------------------
int8_t _MenuCtrl_FindItem( uint8_t itemid )
{
int8_t i;
 
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return -1; }
 
for( i=0; i<menu[midx].itemcount; i++)
{
if( itemid == menu[midx].item[i].id )
{
return i; // found: return index
}
}
return -1; // not found
}
 
 
//--------------------------------------------------------------
// INTERN
//--------------------------------------------------------------
void _MenuCtrl_CalcDisplayPos( void )
{
int8_t i;
 
i = menu[midx].active - menu[midx].display_pos;
 
if( i < 0 )
menu[midx].display_pos = menu[midx].active;
else if( i > 5 )
menu[midx].display_pos = (menu[midx].active - 5);
}
 
 
//--------------------------------------------------------------
// INTERN
//--------------------------------------------------------------
void _MenuCtrl_Beep( void )
{
if( menu[midx].beep )
set_beep( 25, 0xffff, BeepNormal );
}
 
 
//--------------------------------------------------------------
// INTERN
// Dreieckstausch von zwei Menuepunkten.
// Wird verwendet um Menueitems zu verschieben.
//--------------------------------------------------------------
void _MenuCtrl_SwapItem( uint8_t itemindex_1, uint8_t itemindex_2 )
{
menue_item_t tmpItem;
 
memcpy( &tmpItem , &menu[midx].item[itemindex_1], sizeof(menue_item_t) );
memcpy( &menu[midx].item[itemindex_1] , &menu[midx].item[itemindex_2], sizeof(menue_item_t) );
memcpy( &menu[midx].item[itemindex_2] , &tmpItem, sizeof(menue_item_t) );
}
 
 
 
//#############################################################################################
//# PUBLIC funcs
//#############################################################################################
 
 
//--------------------------------------------------------------
// MenuCtrl_Create()
//--------------------------------------------------------------
void MenuCtrl_Create( void )
{
if( midx >= MENUCTRL_MAXMENUES) { _MenuCtrl_Error( ERROR_MAXMENU ); return; }
 
midx++;
memset( &menu[midx], 0, sizeof(menue_t) );
menu[midx].cycle = MENUDEFAULT_CYCLE;
menu[midx].showbatt = MENUDEFAULT_SHOWBATT;
menu[midx].beep = MENUDEFAULT_BEEP;
}
 
 
//--------------------------------------------------------------
// MenuCtrl_Destroy()
//--------------------------------------------------------------
void MenuCtrl_Destroy( void )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return; }
 
midx--;
}
 
 
//--------------------------------------------------------------
// MenuCtrl_ShowLevel( value )
//
// Diese Einstellung ist Global und wirkt sich direkt auf alle
// Menues aus!
// Man kann das also nicht fuer einzelne Menues ein-/ausschalten.
//
// Parameter:
// value: true / false
//--------------------------------------------------------------
void MenuCtrl_ShowLevel( uint8_t value )
{
showlevel = value;
}
 
 
//--------------------------------------------------------------
// MenuCtrl_SetTitle_P( *title )
//
// Parameter:
// title: Menuetitel; Zeiger auf String PROGMEM
//--------------------------------------------------------------
void MenuCtrl_SetTitle_P( const char *title )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return; }
 
menu[midx].title = title;
menu[midx].titlePGM = true;
}
 
 
//--------------------------------------------------------------
// MenuCtrl_SetTitle( *title )
//
// Parameter:
// title: Menuetitel; Zeiger auf String im RAM
//--------------------------------------------------------------
void MenuCtrl_SetTitle( const char *title )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return; }
 
menu[midx].title = title;
menu[midx].titlePGM = false;
}
 
 
 
//--------------------------------------------------------------
// MenuCtrl_SetTitleFromParentItem()
//
// setzte anhand des uebergeordneten Menuepunktes (dem aufrufenden
// Menuepunkt) den Titel des neuen Menues
//
// wird u.a. verwendet in setup.c
//--------------------------------------------------------------
void MenuCtrl_SetTitleFromParentItem( void )
{
uint8_t lang;
const char *pStr;
uint8_t mparent;
 
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return; }
if( midx < 1) { _MenuCtrl_Error( ERROR_NOPARENTMENU ); return; }
 
mparent = midx-1;
 
//--------------------------
// Sprache: Multilanguage oder 0 wenn wenn nur ein Text
//--------------------------
lang = (menu[mparent].item[ menu[mparent].active ].textcount == 1) ? 0 : Config.DisplayLanguage;
 
//--------------------------
// Text vom uebergeordneten Menuepunkt
//--------------------------
pStr = menu[mparent].item[ menu[mparent].active ].text[lang];
 
//--------------------------
// Titel setzen
//--------------------------
if( menu[mparent].item[ menu[mparent].active ].textPGM )
{
MenuCtrl_SetTitle_P( pStr );
}
else
{
MenuCtrl_SetTitle( pStr );
}
}
 
 
 
//--------------------------------------------------------------
// MenuCtrl_SetCycle( value )
//
// Parameter:
// value: true / false
//--------------------------------------------------------------
void MenuCtrl_SetCycle( uint8_t value )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return; }
 
menu[midx].cycle = value;
}
 
 
 
//--------------------------------------------------------------
// MenuCtrl_SetBeep( value )
//
// Parameter:
// value: true / false
//--------------------------------------------------------------
void MenuCtrl_SetBeep( uint8_t value )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return; }
 
menu[midx].beep = value;
}
 
 
 
//--------------------------------------------------------------
// MenuCtrl_SetMove( value )
//
// Schaltet in einem Menue die Moeglichkeit ein Menueeintraege nach
// oben oder nach unten zu verschieben.
// Zum verschieden eines Menueeintrages muessen die PLUS/MINUS Tasten
// lange gedrueckt werden.
//
// Parameter:
// value: true / false (Default: false)
//--------------------------------------------------------------
void MenuCtrl_SetMove( uint8_t value )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return; }
 
menu[midx].canMove = value;
}
 
 
//--------------------------------------------------------------
// MenuCtrl_SetDelete( value )
//
// Schaltet in einem Menue die Moeglichkeit ein Menueeintraege zu loeschen.
// Zum loeschen eines Menueeintrages muss dann die ganz rechte 'OK' Taste
// lange gedrueckt werden.
//
// Parameter:
// value: true / false (Default: false)
//--------------------------------------------------------------
void MenuCtrl_SetDelete( uint8_t value )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return; }
 
menu[midx].canDelete = value;
}
 
 
//--------------------------------------------------------------
// MenuCtrl_SetShowBatt( value )
//
// Parameter:
// value: true / false
//--------------------------------------------------------------
void MenuCtrl_SetShowBatt( uint8_t value )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return; }
 
menu[midx].showbatt = value;
}
 
 
 
//--------------------------------------------------------------
// MenuCtrl_SetTopSpace( n )
//
// fuegt oben im Menue n Leerzeichen ein um Abstand vom Menuetitel
// zu erhalten
//
// ACHTUNG! Das funktioniert nur mit Menues die nicht Scrollen!
// -> also weniger als 6 Eintraege haben (je nach Anzahl von TopSpace)
//
// ACHTUNG! Keine Absicherung bzgl. obigem Warnpunkt! Das kann man
// zwar machen - ist aber aktuell nicht so!
//
// Parameter:
// value: 0..n Anzahl der Leerzeilen ueber dem Menue
//--------------------------------------------------------------
void MenuCtrl_SetTopSpace( uint8_t n )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return; }
 
menu[midx].topspace = n;
}
 
 
 
//--------------------------------------------------------------
// MenuCtrl_SetKey( key, *keytext, *keyfunc )
//
// Parameter:
// key : KEY_ENTER, KEY_ENTER_LONG, KEY_ESC, KEY_ESC_LONG
// keytext: Pointer auf Text PROGMEM oder NOTEXT (=0)
// keyfunc: Pointer auf Funktion oder NOFUNC (=0)
//--------------------------------------------------------------
void MenuCtrl_SetKey( uint8_t key, const char *keytext, void (*keyfunc)(void) )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return; } // kein aktives Menue
 
if( key == KEY_ENTER )
{
menu[midx].key_enter.active = true;
menu[midx].key_enter.text = keytext;
menu[midx].key_enter.func = keyfunc;
}
 
if( key == KEY_ENTER_LONG )
{
menu[midx].key_enter_long.active = true;
menu[midx].key_enter_long.text = keytext;
menu[midx].key_enter_long.func = keyfunc;
}
 
if( key == KEY_ESC )
{
menu[midx].key_esc.active = true;
menu[midx].key_esc.text = keytext;
menu[midx].key_esc.func = keyfunc;
}
 
if( key == KEY_ESC_LONG )
{
menu[midx].key_esc_long.active = true;
menu[midx].key_esc_long.text = keytext;
menu[midx].key_esc_long.func = keyfunc;
}
}
 
 
//--------------------------------------------------------------
// key = MenuCtrl_GetKey()
//
// Rueckgabe:
// key: z.B. KEY_ENTER oder KEY_ENTER_LONG
//--------------------------------------------------------------
uint8_t MenuCtrl_GetKey( void )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return 0; } // kein aktives Menue
 
return menu[midx].lastkey;
}
 
 
 
//--------------------------------------------------------------
// menuindex = MenuCtrl_GetMenuIndex()
//
// gibt den aktuellen Menuindex zurueck
//
// Rueckgabe:
// menuindex: <0 = keine Menue (-1)
// =0 = Hauptmenue (Toplevel)
// >0 = Untermenue Level
//--------------------------------------------------------------
int8_t MenuCtrl_GetMenuIndex( void )
{
return midx;
}
 
 
 
//--------------------------------------------------------------
// itemid = MenuCtrl_GetItemId()
//
// gibt die itemID des aktuell angewaehlten Menuepunktes zurueck
//
// Rueckgabe:
// itemid:
//--------------------------------------------------------------
uint8_t MenuCtrl_GetItemId( void )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return 0; } // kein aktives Menue
 
return menu[midx].item[ menu[midx].active ].id;
}
 
 
 
//--------------------------------------------------------------
// itemid = MenuCtrl_GetItemIdByIndex( index )
//
// damit koennen die aktuell vorhanden itemID's der Menuepunkte
// ermittelt wenn im Menue via SetMove oder SetDelete Menuepunkte
// durch den Benutzer verschoben oder geloescht wurden.
//
// Parameter:
// index: von 0..itemcount-1
//--------------------------------------------------------------
uint8_t MenuCtrl_GetItemIdByIndex( uint8_t index )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return 0; } // kein aktives Menue
 
if( (menu[midx].itemcount == 0) || (index > menu[midx].itemcount-1) ) return 0; // index ausserhalb aktiver Menuepunkte
 
return menu[midx].item[ index ].id;
}
 
 
 
//--------------------------------------------------------------
// num = MenuCtrl_GetItemCount()
//
// gibt die Anzahl der Menuepunkte zurueck
//
// Rueckgabe:
// num: Anzahl der Menuepunkte
//--------------------------------------------------------------
uint8_t MenuCtrl_GetItemCount( void )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return 0; } // kein aktives Menue
 
return menu[midx].itemcount;
}
 
 
//--------------------------------------------------------------
// textPtr = MenuCtrl_GetItemText()
//
// gibt einen Pointer auf den Text des aktuellen Menuepunktes zurueck
//
// ACHTUNG! Der Pointer kann auf RAM oder auch auf PGM zeigen!
//
// Um herauszufinden auf welchen Bereich der Pointer zeigt kann
// MenuCtrl_IsItemTextPGM() verwendet werden.
//
// Rueckgabe:
// textPtr: in RAM oder PGM
//--------------------------------------------------------------
const char * MenuCtrl_GetItemText( void )
{
uint8_t lang;
 
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return 0; } // kein aktives Menue
 
//--------------------------
// Sprache: Multilanguage oder 0 wenn wenn nur ein Text
//--------------------------
lang = (menu[midx].item[ menu[midx].active ].textcount == 1) ? 0 : Config.DisplayLanguage;
 
return menu[midx].item[ menu[midx].active ].text[lang];
}
 
 
 
//--------------------------------------------------------------
// isPGM = MenuCtrl_IsItemTextPGM()
//
// gibt true/false zurueck je nachdem der Text von MenuCtrl_GetItemText()
// im Progmem (=true) oder im RAM (=false) ist
//
// Rueckgabe:
// isPGM: true / false (true = text in PROGMEN; false = text im RAM)
//--------------------------------------------------------------
uint8_t MenuCtrl_IsItemTextPGM( void )
{
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return 0; } // kein aktives Menue
 
return menu[midx].item[ menu[midx].active ].textPGM;
}
 
 
 
//--------------------------------------------------------------
// MenuCtrl_ItemSelect( itemid )
//
// aktiviert einen Menuepunkt / setzt den Menue-Cursor darauf
//
// die Funktion ist nicht durchgetestet, funktioniert aber
// in MKSettings_Menu() / mkparameters.c
//
// es kann sein das es zu Problemen kommt wenn das Menue
// scrollt (mehr als 6 Menueeintraege)
//
// Parameter:
// itemid: ID des Menuitems
//--------------------------------------------------------------
void MenuCtrl_ItemSelect( uint8_t itemid )
{
int8_t i;
 
i = _MenuCtrl_FindItem( itemid );
 
if( i >= 0 )
{
menu[midx].active = i;
}
}
 
 
//--------------------------------------------------------------
// MenuCtrl_ItemActive( itemid, value )
//
// Parameter:
// itemid: ID des Menuitems
// value : true / false
//--------------------------------------------------------------
void MenuCtrl_ItemActive( uint8_t itemid, uint8_t value )
{
int8_t i;
 
i = _MenuCtrl_FindItem( itemid );
 
if( i >= 0 )
{
menu[midx].item[i].disabled = !value;
}
}
 
 
//--------------------------------------------------------------
// MenuCtrl_ItemMark( itemid, value )
//
// Markiert einen Menueeintrag mit einem '*' am Anfang (Links).
// Wird u.a. von BT_SelectDevice() (setup.c) verwendet
//
// Parameter:
// itemid: ID des Menuitems
// value : true / false
//--------------------------------------------------------------
void MenuCtrl_ItemMark( uint8_t itemid, uint8_t value )
{
int8_t i;
 
i = _MenuCtrl_FindItem( itemid );
 
if( i >= 0 )
{
menu[midx].item[i].mark = value;
}
}
 
 
//--------------------------------------------------------------
// MenuCtrl_ItemMarkR( itemid, value )
//
// Markiert einen Menueeintrag mit einem Haken am ENDE (Rechts).
// Wird u.a. von ... (setup.c) verwendet
//
// Parameter:
// itemid: ID des Menuitems
// value : true / false
//--------------------------------------------------------------
void MenuCtrl_ItemMarkR( uint8_t itemid, uint8_t value )
{
int8_t i;
 
i = _MenuCtrl_FindItem( itemid );
 
if( i >= 0 )
{
menu[midx].item[i].markR = value;
}
}
 
 
//--------------------------------------------------------------
// INTERN
//
// fuer: MenuCtrl_PushML_P(), MenuCtrl_Push()
//--------------------------------------------------------------
void _MenuCtrl_Push( uint8_t useprogmem, uint8_t numlang, uint8_t itemid, uint8_t itemtype, void (*menufunc)(void), ... )
{
va_list ap;
uint8_t idx;
uint8_t i;
 
if( midx < 0 ) { _MenuCtrl_Error( ERROR_NOMENU ); return; }
if( menu[midx].itemcount >= MENUCTRL_MAXITEMS ) { _MenuCtrl_Error( ERROR_MAXITEM ); return; }
//if( numlang > NUM_LANG ) { _MenuCtrl_Error( ERROR_MAXLANG ); return; }
 
idx = menu[midx].itemcount;
 
menu[midx].item[idx].id = itemid;
menu[midx].item[idx].type = itemtype; // MENU_ITEM, MENU_SUB
menu[midx].item[idx].mark = false;
menu[midx].item[idx].func = menufunc;
menu[midx].item[idx].textPGM = useprogmem;
menu[midx].item[idx].textcount= numlang;
 
va_start(ap, menufunc);
 
for( i=0; i<numlang; i++)
{
menu[midx].item[idx].text[i] = va_arg( ap, const char *);
}
 
va_end(ap);
 
menu[midx].itemcount++;
}
 
 
//--------------------------------------------------------------
// MenuCtrl_PushML2_P( itemid, itemtype, *menufunc, *text_de, *text_en, *text_nl )
//
// MultiLanguage Texte fuer 2 Sprachen (DE, EN)
// PROGMEN Version
//
// Parameter:
// itemid : ID des Menueitems
// itemtype: MENU_ITEM oder MENU_SUB (bei MENU_SUB wird noch ein ">" angezeigt)
// menufunc: Pointer auf Funktion oder NOFUNC (=0) wenn keine Funktion
// texte : alles Zeiger auf PROGMEM
//--------------------------------------------------------------
void MenuCtrl_PushML2_P( uint8_t itemid, uint8_t itemtype, void (*menufunc)(void), const char *text_de, const char *text_en )
{
//_MenuCtrl_Push( useprogmem, numlang, itemid, itemtype, void (*menufunc)(void), ... )
_MenuCtrl_Push( true, NUM_LANG, itemid, itemtype, menufunc, text_de, text_en );
}
 
 
//--------------------------------------------------------------
// MenuCtrl_PushML2( itemid, itemtype, *menufunc, *text_de, *text_en, *text_nl )
//
// MultiLanguage Texte fuer 2 Sprachen (DE, EN)
// RAM Version
//
// Parameter:
// itemid : ID des Menueitems
// itemtype: MENU_ITEM oder MENU_SUB (bei MENU_SUB wird noch ein ">" angezeigt)
// menufunc: Pointer auf Funktion oder NOFUNC (=0) wenn keine Funktion
// texte : alles Zeiger auf RAM
//--------------------------------------------------------------
void MenuCtrl_PushML2( uint8_t itemid, uint8_t itemtype, void (*menufunc)(void), const char *text_de, const char *text_en )
{
//_MenuCtrl_Push( useprogmem, numlang, itemid, itemtype, void (*menufunc)(void), ... )
_MenuCtrl_Push( false, NUM_LANG, itemid, itemtype, menufunc, text_de, text_en );
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void MenuCtrl_Push_P( uint8_t itemid, uint8_t itemtype, void (*menufunc)(void), const char *text )
{
//_MenuCtrl_Push( useprogmem, numlang, itemid, itemtype, void (*menufunc)(void), ... )
_MenuCtrl_Push( true, 1, itemid, itemtype, menufunc, text );
}
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void MenuCtrl_Push( uint8_t itemid, uint8_t itemtype, void (*menufunc)(void), const char *text )
{
//_MenuCtrl_Push( useprogmem, numlang, itemid, itemtype, void (*menufunc)(void), ... )
_MenuCtrl_Push( false, 1, itemid, itemtype, menufunc, text );
}
 
 
//--------------------------------------------------------------
// Spezialfunktion fuer mkparameters.c !
//
// -> siehe: mkparameters.c / Menu_EditCategory()
//
// ACHTUNG!
// Die externe Variable paramEditItem muss in mkparameters.c
// vor Aufruf dieser Funktion richtig initialisiert sein!
// Ich habe darauf verzichtet hier nochmal ein find_paramEditItem()
// aufzurufen um Speicherplatz zu sparen.
//--------------------------------------------------------------
void MenuCtrl_PushParamEdit( uint8_t paramID )
{
//_MenuCtrl_Push( useprogmem, numlang, itemid, itemtype, void (*menufunc)(void), ... )
_MenuCtrl_Push( true, 2, paramID, MENU_PARAMEDIT, NOFUNC, paramEditItem.title_de, paramEditItem.title_en );
}
 
 
 
//--------------------------------------------------------------
// MenuCtrl_PushSeparator()
//
// fuegt eine Trennlinie im Menue ein
// (die itemID ist dabei 0)
//--------------------------------------------------------------
void MenuCtrl_PushSeparator( void )
{
//_MenuCtrl_Push( useprogmem, numlang, itemid, itemtype, void (*menufunc)(void), ... )
_MenuCtrl_Push( true, 0, 0, MENU_SEPARATOR, NOFUNC );
}
 
 
 
//--------------------------------------------------------------
// MenuCtrl_PushSeparatorID( itemId )
//
// fuegt eine Trennlinie im Menue ein mit einer eigenen itemID
//--------------------------------------------------------------
void MenuCtrl_PushSeparatorID( uint8_t itemid )
{
//_MenuCtrl_Push( useprogmem, numlang, itemid, itemtype, void (*menufunc)(void), ... )
_MenuCtrl_Push( true, 0, itemid, MENU_SEPARATOR, NOFUNC );
}
 
 
 
//--------------------------------------------------------------
// MenuCtrl_Refresh( mode )
//
// Parameter:
// mode: MENU_REDRAW || MENU_REFRESH
//--------------------------------------------------------------
void MenuCtrl_Refresh( uint8_t mode )
{
uint8_t y;
uint8_t item;
uint8_t sh;
uint8_t sy;
uint8_t actchar;
uint8_t markchar;
uint8_t markcharR;
uint8_t lang;
 
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return; } // kein Menue vorhanden
 
if( mode == MENU_REDRAW )
{
//--------------------------
// Clear
//--------------------------
lcd_frect( 0, 8, 6, 47, 0); // Clear: ganz linke Spalte des Sliders
lcd_frect( 127-2, 0, 2, 63, 0); // Clear: ganz rechts 2 Pixel
 
//--------------------------
// Titel
//--------------------------
if( menu[midx].title != 0 )
{
if( showlevel )
{
if( menu[midx].titlePGM )
lcdx_printf_at_P( 0, 0, MINVERS, 0,0 , PSTR(" %19S"), menu[midx].title );
else
lcdx_printf_at_P( 0, 0, MINVERS, 0,0 , PSTR(" %19s"), menu[midx].title );
 
writex_ndigit_number_u( 0, 0, midx, 1, 0, MINVERS, 1,0); // Menuelevel zeigen
}
else
{
if( menu[midx].titlePGM )
lcdx_printf_at_P( 0, 0, MINVERS, 0,0 , PSTR(" %20S"), menu[midx].title );
else
lcdx_printf_at_P( 0, 0, MINVERS, 0,0 , PSTR(" %20s"), menu[midx].title );
}
}
else
lcd_frect( 0, 0, 128, 7, 1); // Titel: Leerzeile
 
 
//--------------------------
// Keyline Beschriftung
//--------------------------
lcdx_cls_row( 7, MNORMAL, 0);
PKT_KeylineUpDown( 1, 7, 0,0);
lcd_printp_at( 12, 7, strGet(KEYLINE4), MNORMAL);
 
 
// Taste: KEY_ENTER
if( menu[midx].key_enter.active && menu[midx].key_enter.text != 0 )
{
lcdx_printf_at_P( 17, 7, MNORMAL, 0,0 , PSTR("%4S"), menu[midx].key_enter.text );
}
 
// Taste: KEY_ESC
if( menu[midx].key_esc.active && menu[midx].key_esc.text != 0 )
{
lcdx_printf_at_P( 12, 7, MNORMAL, 0,0 , PSTR("%5S"), menu[midx].key_esc.text );
}
}
 
 
//--------------------------
// PKT Batterie Anzeige
//--------------------------
if( menu[midx].showbatt )
{
show_Lipo();
}
 
 
//--------------------------
// Zeilen
//--------------------------
for( y=0; y<6; y++)
{
item = y + menu[midx].display_pos;
 
if( item < menu[midx].itemcount )
{
//--------------------------
// char: aktuelle Auswahl
//--------------------------
actchar = ' ';
if( item == menu[midx].active )
{
if( menu[midx].item[item].disabled ) actchar = 0x15; // aktuelle Auswahl: Pfeil disabled
else actchar = 0x1d; // aktuelle Auswahl: Pfeil
}
 
//--------------------------
// char: markiert
//--------------------------
markchar = ' ';
if( menu[midx].item[item].mark ) markchar = '*';
 
//--------------------------
// char: markiert RECHTS
//--------------------------
markcharR = ' ';
if( menu[midx].item[item].type == MENU_SUB ) markcharR = 0x1d;
if( menu[midx].item[item].markR ) markcharR = SYMBOL_CHECK;
 
//--------------------------
// Sprache: Multilanguage oder 0 wenn wenn nur ein Text
//--------------------------
lang = (menu[midx].item[item].textcount == 1) ? 0 : Config.DisplayLanguage;
 
//--------------------------
// Ausgabe: RAM oder PROGMEM
//--------------------------
if( MENU_SEPARATOR == menu[midx].item[item].type )
{
lcdx_printf_at_P( 1, y+1+menu[midx].topspace, MNORMAL, 0,0 , PSTR("%c%c%18S") , actchar, markchar, PSTR("") );
lcd_frect( 6*3, ((y+1)*8)+3, 124-(6*3), 0, 1); // Trennlinie
}
else if( MENU_PARAMEDIT == menu[midx].item[item].type )
{
// SPEZIELL fuer mkparameters.c - zeigt die paramID-Bezeichnung inkl. dem aktuellen WERT an!
strcpy_P( mkparam_strValueBuffer, PSTR("***")); // Vorbelegung von mkparam_strValueBuffer
if( !menu[midx].item[item].disabled ) // nur wenn Menuepunkt nicht deaktiviert (disabled = paramID nicht vorhanden)
{ // -> ermittle den aktuellen Wert der paramID fuer Anzeige
find_paramEditItem( menu[midx].item[item].id ); // paramID suchen (Ergebnis in Variable 'paramEditItem')
paramEditItem.editfunc( paramEditItem.paramID, MKPARAM_SHORTVALUE ); // Wert von paramID in mkparam_strValueBuffer darstellen
}
lcdx_printf_at_P( 1, y+1+menu[midx].topspace, MNORMAL, 0,0 , PSTR("%c%c%14S %3s") , actchar, markchar, menu[midx].item[item].text[lang], mkparam_strValueBuffer );
}
else
{
// Anmerkung zu menu[midx].topspace: NUR fuer Menues OHNE scrollen!!
if( menu[midx].item[item].textPGM )
{
// String im PGM
if( menu[midx].item[item].type == MENU_SUB || menu[midx].item[item].markR )
lcdx_printf_at_P( 1, y+1+menu[midx].topspace, MNORMAL, 0,0 , PSTR("%c%c%16S%c "), actchar, markchar, menu[midx].item[item].text[lang], markcharR );
else
lcdx_printf_at_P( 1, y+1+menu[midx].topspace, MNORMAL, 0,0 , PSTR("%c%c%17S ") , actchar, markchar, menu[midx].item[item].text[lang] );
}
else
{
// String im RAM
if( menu[midx].item[item].type == MENU_SUB || menu[midx].item[item].markR )
lcdx_printf_at_P( 1, y+1+menu[midx].topspace, MNORMAL, 0,0 , PSTR("%c%c%16s%c "), actchar, markchar, menu[midx].item[item].text[lang], markcharR );
else
lcdx_printf_at_P( 1, y+1+menu[midx].topspace, MNORMAL, 0,0 , PSTR("%c%c%17s ") , actchar, markchar, menu[midx].item[item].text[lang] );
}
}
 
} // end: if( item < menu[midx].itemcount )
 
 
//--------------------------
// evtl. Leerzeile loeschen
//--------------------------
if( (y < menu[midx].topspace) || (item >= menu[midx].itemcount+menu[midx].topspace) )
{
lcd_frect( 6, (y+1)*8, 128-6, 7, 0); // Zeile loeschen
}
 
}
 
 
//--------------------------
// Slider
//--------------------------
#define SLIDERH 45 // Finetuning der Slider-Hoehe
 
lcd_frect( 0, 8+1, 1, SLIDERH, 0); // Slider: full Clear
 
if( menu[midx].itemcount > 6 ) // Slider nur bei mehr als 6 Menueitems
{
// Slider: 7 zeilen * 8 pixel = 56 pixel
sh = (SLIDERH * 6) / menu[midx].itemcount; // Slider: Hoehe
sh = (sh > SLIDERH) ? SLIDERH : sh;
 
sy = 8+(menu[midx].display_pos * (SLIDERH-sh)) / (menu[midx].itemcount-6); // Slider: Position
 
//lcd_frect( 0, 8+1, 1, SLIDERH, 0); // Slider: full Clear (flackert auf blauen Display!)
//lcd_frect( 0, 8+1, 1, sy-(8), 0); // Slider: Clear / oben (nicht mehr notwendig da Aenderung am Refresh)
//lcd_frect( 0, sy+1+sh+1, 1, SLIDERH-(sh-sy+1), 0); // Slider: Clear / unten (nicht mehr notwendig da Aenderung am Refresh)
lcd_frect( 0, sy+1, 1, sh, 1); // Slider: Draw
}
}
 
 
 
//--------------------------------------------------------------
// event = MenuCtrl_Control( ctrlmode )
//
// Parameter:
// ctrlmode: MENUCTRL_EVENT || MENUCTRL_RETURN
//
// Rueckgabe:
// event: MENUEVENT_NONE || MENUEVENT_ITEM || MENUEVENT_KEY
//--------------------------------------------------------------
uint8_t MenuCtrl_Control( uint8_t ctrlmode )
{
uint8_t menu_event;
uint8_t refreshmode;
uint8_t item;
uint8_t wahl;
uint8_t i;
uint8_t goUp = false;
uint8_t goDown = false;
 
if( midx < 0) { _MenuCtrl_Error( ERROR_NOMENU ); return 0; } // kein Menue vorhanden
if( menu[midx].itemcount == 0) { _MenuCtrl_Error( ERROR_NOITEM ); return 0; } // kein Menueitem vorhanden
 
 
// bei MENUCTRL_RETURN muss man ggf. selber fuer ein Redraw sorgen
// (beim ersten Aufruf wird es jedoch dennoch erzwungen)
if( ctrlmode == MENUCTRL_EVENT || !menu[midx].firstredraw )
{
MenuCtrl_Refresh( MENU_REDRAW );
menu[midx].firstredraw = true;
}
 
clear_key_all();
 
do
{
menu_event = MENUEVENT_NONE;
menu[midx].lastkey = KEY_NONE;
refreshmode = false;
 
//--------------------------
// Pruefe PKT Update oder
// andere PKT-Aktion
//--------------------------
if( PKT_CtrlHook() ) // Update vom Updatetool angefordert?
{
refreshmode = MENU_REDRAW;
}
 
//--------------------------
// PKT Batterie Anzeige
//--------------------------
if( menu[midx].showbatt )
{
show_Lipo();
}
 
 
//--------------------------
// Cursor: nach oben (UP)
//--------------------------
//+++++
// UP - Verschiebemodus AKTIV
//+++++
if( menu[midx].canMove )
{
if( get_key_long(1 << KEY_MINUS) )
{
if( (menu[midx].active > 0) && (menu[midx].itemcount > 0) )
{
_MenuCtrl_SwapItem( menu[midx].active, menu[midx].active-1 );
goUp = true;
}
else _MenuCtrl_Beep(); // am oberen Ende angelangt
}
 
if( get_key_short(1 << KEY_MINUS) ) // up
{
goUp = true;
}
} // end: UP - Verschiebemodus AKTIV
 
 
//+++++
// UP - Verschiebemodus NICHT aktiv
//+++++
if( !menu[midx].canMove ) // up
{
if( get_key_press(1 << KEY_MINUS) || get_key_long_rpt_sp((1 << KEY_MINUS),2) ) // up
{
goUp = true;
}
} // end: UP - Verschiebemodus NICHT aktiv
 
 
//+++++
// UP - goUp
//+++++
if( goUp ) // up
{
refreshmode = MENU_REFRESH;
if( (menu[midx].active > 0) && (menu[midx].itemcount > 0) )
{
menu[midx].active--;
}
else if( menu[midx].cycle )
{
menu[midx].active = menu[midx].itemcount-1;
}
else
{
_MenuCtrl_Beep(); // am oberen Ende angelangt
}
_MenuCtrl_CalcDisplayPos();
}
 
 
//--------------------------
// Cursor: nach unten (DOWN)
//--------------------------
//+++++
// DOWN - Verschiebemodus AKTIV
//+++++
if( menu[midx].canMove )
{
if( get_key_long(1 << KEY_PLUS) )
{
if( menu[midx].active < menu[midx].itemcount-1 )
{
_MenuCtrl_SwapItem( menu[midx].active, menu[midx].active+1 );
goDown = true;
}
else _MenuCtrl_Beep(); // am unteren Ende angelangt
}
 
if( get_key_short(1 << KEY_PLUS) ) // up
{
goDown = true;
}
} // end: DOWN - Verschiebemodus AKTIV
 
 
//+++++
// DOWN - Verschiebemodus NICHT aktiv
//+++++
if( !menu[midx].canMove ) // up
{
if( get_key_press(1 << KEY_PLUS) || get_key_long_rpt_sp((1 << KEY_PLUS),2) ) // up
{
goDown = true;
}
} // end: DOWN - Verschiebemodus NICHT aktiv
 
 
//+++++
// DOWN - goDown
//+++++
if( goDown ) // down
{
refreshmode = MENU_REFRESH;
if( menu[midx].active < menu[midx].itemcount-1 )
{
menu[midx].active++;
}
else if( menu[midx].cycle )
{
menu[midx].active = 0;
}
else
{
_MenuCtrl_Beep(); // am unteren Ende angelangt
}
_MenuCtrl_CalcDisplayPos();
}
 
 
//--------------------------
//--------------------------
item = menu[midx].active;
goUp = false;
goDown = false;
 
 
//--------------------------
// KEY_ENTER
//--------------------------
if( get_key_short(1 << KEY_ENTER) )
{
refreshmode = MENU_REFRESH;
// todo: keyfunc
if( menu[midx].item[item].type == MENU_SEPARATOR )
{
// do nothing
}
else if( menu[midx].item[item].disabled )
{
set_beep( 200, 0x00ff, BeepNormal); // Beep
PKT_Popup_P( 200, strGet(STR_MENUCTRL_NOTPOSSIBLE),0,0,0); // "nicht möglich!"
refreshmode = MENU_REDRAW;
}
else if( menu[midx].item[item].func != NOFUNC )
{
menu[midx].item[item].func();
refreshmode = MENU_REDRAW;
}
else if( menu[midx].key_enter.func != NOFUNC )
{
menu[midx].key_enter.func();
refreshmode = MENU_REDRAW;
}
else
{
menu[midx].lastkey = KEY_ENTER;
menu_event = MENUEVENT_ITEM;
}
}
 
 
//--------------------------
// KEY_ENTER_LONG (Deletemodus AKTIV)
//
// loescht einen Menueeintrag
//--------------------------
if( menu[midx].canDelete && get_key_long(1 << KEY_ENTER) && (menu[midx].itemcount > 0) )
{
wahl = 1;
if( menu[midx].canDelete == 1 ) // ==1 -> mit Nachfrage
{
set_beep( 200, 0xffff, BeepNormal); // Beep
PKT_Popup_P( 0, strGet(STR_MENUCTRL_DELASK),PSTR(""),0,0); // "Eintrag entfernen?"
lcd_printp_at( 12, 7, strGet(YESNO), MINVERS);
 
wahl = 0;
while( !wahl )
{
if( get_key_short(1<<KEY_ESC) ) wahl = 1; // "Ja"
if( get_key_short(1<<KEY_ENTER) ) wahl = 2; // "Nein"
}
refreshmode = MENU_REDRAW;
}
 
if( wahl==1 )
{
for( i=menu[midx].active; i<menu[midx].itemcount-1; i++)
{
_MenuCtrl_SwapItem( i, i+1 );
}
menu[midx].itemcount--;
 
if( (menu[midx].display_pos > 0) && (menu[midx].display_pos+6 > menu[midx].itemcount) )
{
menu[midx].display_pos--;
menu[midx].active--;
}
 
if( menu[midx].active >= menu[midx].itemcount )
menu[midx].active = menu[midx].itemcount-1;
 
_MenuCtrl_CalcDisplayPos();
refreshmode = MENU_REDRAW;
 
if( menu[midx].canDelete == 2 ) // ==2 -> direkt loeschen, ohne Nachfrage
{
set_beep( 200, 0xffff, BeepNormal); // Beep
PKT_Popup_P( 200, strGet(STR_MENUCTRL_DELITEM),0,0,0); // "Eintrag entfernt!"
}
}
}
 
 
//--------------------------
// KEY_ENTER_LONG (NICHT Deletemodus)
//--------------------------
if( !menu[midx].canDelete && menu[midx].key_enter_long.active && get_key_long(1 << KEY_ENTER) )
{
refreshmode = MENU_REFRESH;
if( menu[midx].key_enter_long.func != NOFUNC )
{
menu[midx].key_enter_long.func();
refreshmode = MENU_REDRAW;
}
else
{
menu_event = MENUEVENT_KEY;
menu[midx].lastkey = KEY_ENTER_LONG;
}
}
 
 
//--------------------------
// KEY_ESC_LONG
//--------------------------
if( menu[midx].key_esc_long.active && get_key_long(1 << KEY_ESC) )
{
refreshmode = MENU_REFRESH;
if( menu[midx].key_esc_long.func != NOFUNC )
{
menu[midx].key_esc_long.func();
refreshmode = MENU_REDRAW;
}
else
{
menu_event = MENUEVENT_KEY;
menu[midx].lastkey = KEY_ESC_LONG;
}
}
 
 
//--------------------------
// KEY_ESC
//--------------------------
if( get_key_short(1 << KEY_ESC) )
{
refreshmode = MENU_REFRESH;
if( menu[midx].key_esc.func != NOFUNC )
{
menu[midx].key_esc.func();
refreshmode = MENU_REDRAW;
}
else
{
menu_event = MENUEVENT_KEY;
menu[midx].lastkey = KEY_ESC;
}
}
 
if( refreshmode )
{
MenuCtrl_Refresh( refreshmode );
clear_key_all();
}
}
while ( menu_event == MENUEVENT_NONE && ctrlmode == MENUCTRL_EVENT );
 
return menu_event;
}
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/utils/menuctrl.h
0,0 → 1,138
/*****************************************************************************
* Copyright (C) 2013 Oliver Gemesi *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
*****************************************************************************/
 
//############################################################################
//# HISTORY menuctrl.h
//#
//# 11.06.2014 OG
//# - add: MenuCtrl_GetMenuIndex()
//#
//# 11.05.2014 OG
//# - add: MenuCtrl_SetTitleFromParentItem()
//# - add: MenuCtrl_GetItemText(), MenuCtrl_IsItemTextPGM()
//#
//# 07.05.2014 OG
//# - add: MenuCtrl_PushSeparatorID()
//#
//# 06.05.2014 OG
//# - add: MenuCtrl_GetItemIdByIndex(), MenuCtrl_GetItemCount()
//#
//# 05.05.2014 OG
//# - add: MenuCtrl_SetDelete(), MenuCtrl_SetMove()
//#
//# 30.03.2014 OG
//# - del: MenuCtrl_PushML_P(), MenuCtrl_PushML() (Umstellung Sprachen abgeschlossen)
//# - add: MenuCtrl_PushML2(), MenuCtrl_PushML2_P() fuer Umstellung von 3 auf 2 Sprachen
//#
//# 24.03.2014 OG
//# - add: MenuCtrl_PushSeparator()
//# - add: MENU_SEPARATOR
//# - chg: Wert von MENU_REFRESH und MENU_REDRAW
//#
//# 23.03.2014 OG
//# - add: Unterstuetzung fuer MK-Parameter-Edit (mkparameters.c)
//# - add: MenuCtrl_PushParamEdit()
//# - add: define MENU_PARAMEDIT
//#
//# 17.02.2014 OG
//# - add: MenuCtrl_SetTopSpace()
//#
//# 15.02.2014 OG
//# - add: MenuCtrl_ItemSelect()
//#
//# 07.07.2013 OG
//# - add: MenuCtrl_ItemMarkR()
//#
//# 24.05.2013 OG
//# - chg: MenuCtrl_Push... Funktionen vereinheitlicht mit internen Aenderungen
//# betrifft externe Funktionsaufrufe die geändert wurden
//# - del: MenuCtrl_PushSimple_P(), MenuCtrl_PushSimple()
//# - add: MenuCtrl_ItemMark()
//#
//# 23.05.2013 OG
//# - add: MenuCtrl_PushSimple_P(), MenuCtrl_PushSimple()
//#
//# 21.05.2013 OG
//# - add: MenuCtrl_ShowLevel()
//#
//# 17.05.2013 OG - NEU
//############################################################################
 
#ifndef MENUCTRL_H
#define MENUCTRL_H
 
#define MENU_ITEM 1 // Typ des Menueitems: normaler Eintrag ohne ">" am Ende
#define MENU_SUB 2 // Typ des Menueitems: Submenue - es wird noch ein ">" angezeigt
#define MENU_SEPARATOR 3 // nur fuer MenuCtrl_PushSeparator() fuer (verwendet von mkparameters.c)
#define MENU_PARAMEDIT 4 // nur fuer MenuCtrl_PushParamEdit() fuer (verwendet von mkparameters.c)
 
#define NOFUNC 0 // keine Funktion uebergeben
#define NOTEXT 0 // kein Text uebergeben
 
#define MENUEVENT_NONE 0 // wird von MenuCtrl_Ctrl() zurueckgegeben
#define MENUEVENT_ITEM 1 // wird von MenuCtrl_Ctrl() zurueckgegeben
#define MENUEVENT_KEY 2 // wird von MenuCtrl_Ctrl() zurueckgegeben
 
#define MENUCTRL_EVENT 0 // Parameter fuer MenuCtrl_Ctrl() - Ruecksprung nur bei einem Event
#define MENUCTRL_RETURN 1 // Parameter fuer MenuCtrl_Ctrl() - Ruecksprung immer
 
 
#define MENU_REFRESH 1 // MenuCtrl_Refresh()
#define MENU_REDRAW 2 // MenuCtrl_Refresh()
 
 
void MenuCtrl_Create( void );
void MenuCtrl_Destroy( void );
void MenuCtrl_ShowLevel( uint8_t value );
 
void MenuCtrl_SetTitle( const char *title );
void MenuCtrl_SetTitle_P( const char *title );
void MenuCtrl_SetTitleFromParentItem( void );
void MenuCtrl_SetCycle( uint8_t value );
void MenuCtrl_SetShowBatt( uint8_t value );
void MenuCtrl_SetBeep( uint8_t value );
void MenuCtrl_SetKey( uint8_t key, const char *keytext, void (*keyfunc)(void) );
void MenuCtrl_SetTopSpace( uint8_t value );
void MenuCtrl_SetMove( uint8_t value );
void MenuCtrl_SetDelete( uint8_t value );
 
int8_t MenuCtrl_GetMenuIndex( void );
uint8_t MenuCtrl_GetItemId( void );
uint8_t MenuCtrl_GetKey( void );
uint8_t MenuCtrl_GetItemIdByIndex( uint8_t index );
uint8_t MenuCtrl_GetItemCount( void );
const char * MenuCtrl_GetItemText( void );
uint8_t MenuCtrl_IsItemTextPGM( void );
 
void MenuCtrl_ItemSelect( uint8_t itemid );
void MenuCtrl_ItemActive( uint8_t itemid, uint8_t value );
void MenuCtrl_ItemMark( uint8_t itemid, uint8_t value );
void MenuCtrl_ItemMarkR( uint8_t itemid, uint8_t value );
 
void MenuCtrl_PushML2_P( uint8_t itemid, uint8_t itemtype, void (*menufunc)(void), const char *text_de, const char *text_en );
void MenuCtrl_PushML2( uint8_t itemid, uint8_t itemtype, void (*menufunc)(void), const char *text_de, const char *text_en );
void MenuCtrl_Push_P( uint8_t itemid, uint8_t itemtype, void (*menufunc)(void), const char *text );
void MenuCtrl_Push( uint8_t itemid, uint8_t itemtype, void (*menufunc)(void), const char *text );
void MenuCtrl_PushParamEdit( uint8_t itemid );
void MenuCtrl_PushSeparator( void );
void MenuCtrl_PushSeparatorID( uint8_t itemid );
 
void MenuCtrl_Refresh( uint8_t mode );
uint8_t MenuCtrl_Control( uint8_t ctrlmode );
 
#endif // MENUCTRL_H
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/utils/scrollbox.c
0,0 → 1,570
/*****************************************************************************
* Copyright (C) 2013 Oliver Gemesi *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
*****************************************************************************/
 
//############################################################################
//# HISTORY scrollbox.c
//#
//# 31.05.2014 OG
//# - chg: ScrollBox_Refresh() - umgestellt auf PKT_KeylineUpDown()
//#
//# 29.03.2014 OG
//# - chg: ScrollBox_Show() umgestellt auf clear_key_all()
//#
//# 22.05.2013 OG
//# - fix: include pkt/pkt.h
//#
//# 19.05.2013 OG
//# - chg: ScrollBox_Show() erweitert um PKT_CtrlHook() um u.a. PKT-Updates
//# zu ermoeglichen
//#
//# 04.05.2013 OG
//# - chg: angepasst auf xutils.c
//#
//# 28.04.2013 OG
//# - add: ScrollBox_Push() - Variante fuer 'format' im RAM
//# - chg: ScrollBox_Push_P() -> keine Rueckgabe mehr (void)
//# - chg: auf xprintf umgestellt (siehe utils/xstring.c)
//# - add: verschiedene Beschreibungen ueber Funktionen
//#
//# 20.04.2013 OG - NEU
//############################################################################
 
//#define USE_SCROLLBOX_DEBUG // Debug-Funktionen einkompilieren/aktivieren (gesendet wird an uart1)
 
#include "../cpu.h"
#include <avr/pgmspace.h>
#include <stdio.h>
#include <stdarg.h>
#include <string.h>
#include <stdlib.h>
 
#include "../main.h"
#include "../lcd/lcd.h"
#include "../eeprom/eeprom.h"
#include "../messages.h"
#include "../pkt/pkt.h"
#include "../utils/xutils.h" // xprintf
#include "scrollbox.h"
 
// Debug
#ifdef USE_SCROLLBOX_DEBUG
#include "../uart/uart1.h"
#include <util/delay.h>
#endif
 
#define SCROLLBOX_ALLOC_MEM // dynamische RAM-Belegen (malloc) verwenden? (Standardeinstellung: ja)
 
#define SCROLLBOX_LINESIZE 20+1 // Ausgabezeile der ScrollBox (20 Chars + 0x00)
#define SCROLLBOX_KEYSIZE 4+1 // Textlabel einer Taste (4 Chars + 0x00)
 
#define SCROLLBOX_W 20 // Textbreite
#define SCROLLBOX_H 7 // Textzeilen
#define MSBLINE 10 // drawmode-code fuer: Linie
 
 
 
 
//-----------------------------------------------------------
// statischer Speicher wenn nicht SCROLLBOX_ALLOC_MEM
// verwendet wird
//-----------------------------------------------------------
#ifndef SCROLLBOX_ALLOC_MEM
#define SCROLLBOX_BUFFER_SIZE 2048 // 2 KByte - ram-size in bytes
char scrollbox_buffer[SCROLLBOX_BUFFER_SIZE];
#endif
 
 
//-----------------------------------------------------------
// typedef: scrollbox_key_t
//-----------------------------------------------------------
typedef struct
{
uint8_t active; // Taste aktiv? (true/false)
char text[SCROLLBOX_KEYSIZE]; // Tastentext
} scrollbox_key_t;
 
 
//-----------------------------------------------------------
// typedef: scrollbox_line_t
//-----------------------------------------------------------
typedef struct
{
uint8_t mode; // drawmode: MNORMAL, MINVERSE oder MSBLINE
char line[SCROLLBOX_LINESIZE]; // malloc: lines * 21 bytes (20 chars + 0)
} scrollbox_line_t;
 
 
//-----------------------------------------------------------
// typedef: scrollbox_t
//-----------------------------------------------------------
typedef struct
{
scrollbox_line_t *buffer; // malloc: lines * 22 bytes (21 chars + 0)
uint8_t maxlines; // max. reservierte Lines (malloc buffer)
uint8_t lines; // Anzahl gepushte lines
uint8_t display_pos; // aktuelle obere Anzeigezeile
scrollbox_key_t key_enter;
scrollbox_key_t key_enter_long;
} scrollbox_t;
 
 
//-----------------------------------------------------------
// Buffer & Co.
//-----------------------------------------------------------
scrollbox_t scrollbox;
char buffer_sbline[SCROLLBOX_LINESIZE];
 
 
//#############################################################################################
//#############################################################################################
 
 
 
//xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx
#ifdef USE_SCROLLBOX_DEBUG
//xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx
//--------------------------------------------------------------
// nur wenn define: USE_SCROLLBOX_DEBUG
//--------------------------------------------------------------
void ScrollBox_Debug( void )
{
char s[33];
uint8_t i,j;
char *p;
scrollbox_line_t *sboxp;
uint32_t h;
 
uart1_puts_p( PSTR("\r\nScrollBox_Debug: BEGIN\r\n\r\n") );
 
ltoa( scrollbox.buffer, s, 16);
uart1_puts_p( PSTR("address: buffer = 0x") );
uart1_puts( s );
ltoa( scrollbox.buffer, s, 10);
uart1_puts( " (" );
uart1_puts( s );
uart1_puts( ")\r\n" );
 
ltoa( scrollbox_buffer, s, 16);
uart1_puts_p( PSTR("address: scrollbox_buffer = 0x") );
uart1_puts( s );
ltoa( scrollbox.buffer, s, 10);
uart1_puts( " (" );
uart1_puts( s );
uart1_puts( ")\r\n" );
 
 
itoa( sizeof(scrollbox_line_t), s, 10);
uart1_puts_p( PSTR("sizeof(scrollbox_line_t) = ") );
uart1_puts( s );
uart1_puts( "\r\n" );
 
uart1_puts( "\r\n" );
 
itoa( scrollbox.lines, s, 10);
uart1_puts_p( PSTR("scrollbox.lines = ") );
uart1_puts( s );
uart1_puts( "\r\n" );
 
itoa( scrollbox.maxlines, s, 10);
uart1_puts_p( PSTR("scrollbox.maxlines = ") );
uart1_puts( s );
uart1_puts( "\r\n" );
 
itoa( scrollbox.display_pos, s, 10);
uart1_puts_p( PSTR("scrollbox.display_pos = ") );
uart1_puts( s );
uart1_puts( "\r\n" );
 
uart1_puts( "\r\n" );
 
for(i=0; i<scrollbox.lines; i++)
{
itoa( i, s, 10);
if( strlen(s)<2 ) uart1_puts( " " );
uart1_puts( s );
uart1_puts( ": " );
 
//sboxp = scrollbox.buffer + sizeof(scrollbox_line_t)*i;
sboxp = scrollbox.buffer + i;
 
ltoa( sboxp, s, 16); // hex
uart1_puts( "[0x" );
uart1_puts( s );
uart1_puts( "]" );
 
ltoa( sboxp, s, 10); // dec
uart1_puts( "[" );
uart1_puts( s );
uart1_puts( "] " );
 
itoa( sboxp->mode, s, 10);
if( strlen(s)<2 ) uart1_puts( " " );
uart1_puts( s );
uart1_puts( ": " );
 
p = sboxp->line;
 
if( sboxp->mode != 10 )
{
uart1_puts( p );
}
 
uart1_puts( "|\r\n" );
}
 
//--------------------------------------------------------------
// Hier wird fuer eine gewisse Zeit (insgesamt 2500 mal) permanent die Zeile 23 ausgegeben.
// Wenn ich das richtig sehe schreibe ich hierbei nicht ;-)
// Aber was sagt das Empfangsterminal....
//--------------------------------------------------------------
sboxp = scrollbox.buffer + 23;
for( h=0; h<10; h++)
{
itoa( h, s, 10);
uart1_puts( s );
uart1_puts( "# " );
 
uart1_puts( sboxp->line );
uart1_puts( "|\r\n" );
_delay_ms(10);
}
//--------------------------------------------------------------
 
uart1_puts_p( PSTR("\r\nScrollBox_Debug: END\r\n") );
uart1_puts( "##########################################\r\n\r\n" );
}
//xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx
#endif // USER_SCROLLBOX_DEBUG
//xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx
 
 
 
//--------------------------------------------------------------
// ok = ScrollBox_Create( uint8_t maxlines )
//
// Rueckgabe:
// true = ok
// false = kein Speicher
//
// - reserviert speicher fuer max. maxlines
// - initialisiert scrollbox-Datenstruktur
//--------------------------------------------------------------
uint8_t ScrollBox_Create( uint8_t maxlines )
{
scrollbox.buffer = 0;
 
#ifdef SCROLLBOX_ALLOC_MEM
scrollbox.buffer = malloc( maxlines * sizeof(scrollbox_line_t));
//scrollbox.buffer = calloc( maxlines, sizeof(scrollbox_line_t) );
#else
scrollbox.buffer = (scrollbox_line_t *) scrollbox_buffer;
#endif
 
if( !scrollbox.buffer ) // kein RAM mehr
{
lcd_cls();
lcd_printp_at( 1, 3, PSTR("Error: ScrollBox"), MNORMAL);
lcd_printp_at( 1, 4, PSTR("No more RAM"), MNORMAL);
set_beep ( 500, 0x3333, BeepNormal);
while (!get_key_short (1 << KEY_ESC));
return false;
}
 
scrollbox.maxlines = maxlines;
scrollbox.lines = 0;
scrollbox.display_pos = 0;
 
scrollbox.key_enter.active = false;
scrollbox.key_enter_long.active = false;
return true;
}
 
 
 
//--------------------------------------------------------------
// ScrollBox_Destroy()
//
// gibt reservierten Speicher wieder frei
// Wichtig! Da malloc verwendet wird!
//--------------------------------------------------------------
void ScrollBox_Destroy( void )
{
if( scrollbox.buffer )
{
#ifdef SCROLLBOX_ALLOC_MEM
free( scrollbox.buffer );
#endif
}
scrollbox.buffer = 0;
}
 
 
//--------------------------------------------------------------
// ScrollBox_PushLine()
//
// fuegt eine Trennlinie hinzu
//--------------------------------------------------------------
void ScrollBox_PushLine( void )
{
scrollbox_line_t *sboxp;
 
if( scrollbox.lines < scrollbox.maxlines )
{
sboxp = scrollbox.buffer + scrollbox.lines;
sboxp->mode = MSBLINE;
scrollbox.lines++;
}
}
 
 
 
//--------------------------------------------------------------
// _scrollbox_push(...)
//
// intern fuer: ScrollBox_Push_P(), ScrollBox_Push()
// Beschreibung siehe dort
//--------------------------------------------------------------
void _scrollbox_push( uint8_t useprogmem, uint8_t mode, const char *format, va_list ap )
{
scrollbox_line_t *sboxp;
 
if( scrollbox.lines < scrollbox.maxlines )
{
sboxp = scrollbox.buffer + scrollbox.lines;
 
_xvsnprintf( useprogmem, buffer_sbline, SCROLLBOX_LINESIZE, format, ap);
 
strncpyfill( sboxp->line, buffer_sbline, SCROLLBOX_LINESIZE); // copy: buffer_sbline zur scrollbox
sboxp->mode = mode;
 
scrollbox.lines++;
}
}
 
 
 
//--------------------------------------------------------------
// ScrollBox_Push_P( mode, format, ...)
//
// Textzeile hinzufuegen - 'format' ist im PROGMEM.
//
// Parameter:
// mode : MNORMAL, MINVERS
// format : siehe xprint-Doku in utils/xstring.c
// ... : Parameterliste fuer 'format'
//--------------------------------------------------------------
void ScrollBox_Push_P( uint8_t mode, const char *format, ... )
{
va_list ap;
 
va_start(ap, format);
_scrollbox_push( true, mode, format, ap);
va_end(ap);
}
 
 
//--------------------------------------------------------------
// ScrollBox_Push( mode, format, ...)
//
// Textzeile hinzufuegen - 'format' ist im RAM.
//
// Parameter:
// mode : MNORMAL, MINVERS
// format : siehe xprint-Doku in utils/xstring.c
// ... : Parameterliste fuer 'format'
//--------------------------------------------------------------
void ScrollBox_Push( uint8_t mode, const char *format, ... )
{
va_list ap;
 
va_start(ap, format);
_scrollbox_push( false, mode, format, ap);
va_end(ap);
}
 
 
//--------------------------------------------------------------
// key: KEY_ENTER, KEY_ENTER_LONG (keine weiteren bisher!)
//--------------------------------------------------------------
void ScrollBox_SetKey( uint8_t key, const char *keytext )
{
if( key == KEY_ENTER )
{
scrollbox.key_enter.active = true;
strncpyfill( scrollbox.key_enter.text, keytext, SCROLLBOX_KEYSIZE);
}
 
if( key == KEY_ENTER_LONG )
{
scrollbox.key_enter_long.active = true;
strncpyfill( scrollbox.key_enter_long.text, keytext, SCROLLBOX_KEYSIZE);
}
}
 
 
 
//--------------------------------------------------------------
// ScrollBox_Refresh()
//
// zeigt die ScrollBox - wird normalerweise von ScrollBox_Show()
// automatisch durchgefuehrt
//--------------------------------------------------------------
void ScrollBox_Refresh( void )
{
uint8_t y;
uint8_t sh;
uint8_t sy;
scrollbox_line_t *sboxp;
 
//--------------------------
// Text
//--------------------------
for( y=0; y<7; y++)
{
sboxp = scrollbox.buffer + (scrollbox.display_pos + y);
 
if( y + scrollbox.display_pos < scrollbox.lines )
{
 
if( sboxp->mode == MSBLINE )
{
lcd_frect( (21-SCROLLBOX_W)*6, (y*8), (SCROLLBOX_W*6), 7, 0); // clear
lcd_line ( (21-SCROLLBOX_W)*6, (y*8)+3, 125, (y*8)+3, 1); // line
}
else
{
lcd_puts_at( 21-SCROLLBOX_W, y, sboxp->line, sboxp->mode);
}
//p += sizeof(scrollbox_line_t);
}
else // clear
{
lcd_frect( (21-SCROLLBOX_W)*6, (y*8), (SCROLLBOX_W*6), 7, 0); // clear
}
}
 
 
//--------------------------
// Slider
//--------------------------
#define SLIDERH 55 // Finetuning der Slider-Hoehe
 
// Slider: 7 zeilen * 8 pixel = 56 pixel
sh = (SLIDERH * 7) / scrollbox.lines; // Slider: Hoehe
sh = (sh > SLIDERH) ? SLIDERH : sh;
 
sy = (scrollbox.display_pos * (SLIDERH-sh)) / (scrollbox.lines-7); // Slider: Position
 
lcd_frect( 0, 0, 1, SLIDERH, 0); // Slider: Clear
lcd_frect( 0, sy, 1, sh, 1); // Slider: draw // Slider: Draw
 
 
//--------------------------
// Keyline
//--------------------------
PKT_KeylineUpDown( 1, 7, 0,0); // Keyline: Up / Down
lcd_printp_at( 12, 7, strGet(ENDE), MNORMAL); // Keyline: Ende
 
if( scrollbox.key_enter.active ) lcd_print_at (17, 7, (uint8_t *)scrollbox.key_enter.text , MNORMAL);
else if ( scrollbox.key_enter_long.active ) lcd_print_at (17, 7, (uint8_t *)scrollbox.key_enter_long.text, MNORMAL);
else lcd_printp_at(17, 7, PSTR(" ") , MNORMAL);
 
//ScrollBox_Debug();
}
 
 
//--------------------------------------------------------------
// key = ScrollBox_Show()
//
//--------------------------------------------------------------
uint8_t ScrollBox_Show( void )
{
uint8_t keyexit = 0;
 
clear_key_all();
 
if( scrollbox.buffer )
{
ScrollBox_Refresh();
 
do
{
//--------------------------
// Pruefe auf PKT-Update und
// andere interne PKT-Aktionen
//--------------------------
if( PKT_CtrlHook() ) // Update vom Updatetool angefordert?
{
lcd_cls();
ScrollBox_Refresh();
}
 
//--------------------------
// scrollen: nach unten
//--------------------------
if( get_key_press(1 << KEY_PLUS) || get_key_long_rpt_sp( (1 << KEY_PLUS),2 )) // down
{
if( scrollbox.display_pos < ( scrollbox.lines - SCROLLBOX_H) )
{
scrollbox.display_pos++;
ScrollBox_Refresh();
}
else
{
set_beep ( 25, 0xffff, BeepNormal); // am unteren Ende angelangt
}
}
 
//--------------------------
// scrollen: nach oben
//--------------------------
if( get_key_press(1 << KEY_MINUS) || get_key_long_rpt_sp( (1 << KEY_MINUS),2 )) // up
{
if( scrollbox.display_pos > 0 )
{
scrollbox.display_pos--;
ScrollBox_Refresh();
}
else
{
set_beep ( 25, 0xffff, BeepNormal); // am oberen Ende angelangt
}
}
 
//--------------------------
//--------------------------
if( scrollbox.key_enter.active && get_key_short(1 << KEY_ENTER) )
{
keyexit = KEY_ENTER;
}
 
//--------------------------
//--------------------------
if( scrollbox.key_enter_long.active && get_key_long(1 << KEY_ENTER) )
{
keyexit = KEY_ENTER_LONG;
}
 
} while( !get_key_press(1 << KEY_ESC) && (keyexit == 0) );
}
 
//get_key_press(KEY_ALL); // ersetzt durch obiges clear_key_all()
 
return keyexit;
}
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/utils/scrollbox.h
0,0 → 1,49
/*****************************************************************************
* Copyright (C) 2013 Oliver Gemesi *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
*****************************************************************************/
 
//############################################################################
//# HISTORY scrollbox.h
//#
//# 17.05.2013 OG
//# - del: defines KEY_xyz_LONG verschoben nach HAL_HW3_9.h
//#
//# 28.04.2013 OG
//# - add: ScrollBox_Push()
//# - chg: ScrollBox_Push_P() (keine Rueckgabe mehr)
//# - add: include <stdarg.h>
//#
//# 20.04.2013 OG - NEU
//############################################################################
 
#ifndef _SCROLLBOX_H
#define _SCROLLBOX_H
 
#include <stdarg.h> // Notwendig! (OG)
 
 
uint8_t ScrollBox_Create( uint8_t maxlines );
void ScrollBox_Destroy( void );
void ScrollBox_PushLine( void );
void ScrollBox_Push_P( uint8_t mode, const char *format, ... );
void ScrollBox_Push( uint8_t mode, const char *format, ... );
void ScrollBox_SetKey( uint8_t key, const char *keytext );
void ScrollBox_Refresh( void );
uint8_t ScrollBox_Show( void );
//void ScrollBox_Debug( void );
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/utils/twi_slave.c
0,0 → 1,373
/*****************************************************************************
*
* Atmel Corporation
*
* File : TWI_Slave.c
* Compiler : IAR EWAAVR 2.28a/3.10c
* Revision : $Revision: 2475 $
* Date : $Date: 2007-09-20 12:00:43 +0200 (to, 20 sep 2007) $
* Updated by : $Author: mlarsson $
*
* Support mail : avr@atmel.com
*
* Supported devices : All devices with a TWI module can be used.
* The example is written for the ATmega16
*
* AppNote : AVR311 - TWI Slave Implementation
*
* Description : This is sample driver to AVRs TWI module.
* It is interupt driveren. All functionality is controlled through
* passing information to and from functions. Se main.c for samples
* of how to use the driver.
*
****************************************************************************/
/*! \page MISRA
*
* General disabling of MISRA rules:
* * (MISRA C rule 1) compiler is configured to allow extensions
* * (MISRA C rule 111) bit fields shall only be defined to be of type unsigned int or signed int
* * (MISRA C rule 37) bitwise operations shall not be performed on signed integer types
* As it does not work well with 8bit architecture and/or IAR
 
* Other disabled MISRA rules
* * (MISRA C rule 109) use of union - overlapping storage shall not be used
* * (MISRA C rule 61) every non-empty case clause in a switch statement shall be terminated with a break statement
*/
 
#if defined(__ICCAVR__)
#include "ioavr.h"
#include "inavr.h"
#else
#include <avr/io.h>
#include <avr/interrupt.h>
#endif
#include "twi_slave.h"
 
// Emulate GCC ISR() statement in IAR
#if defined(__ICCAVR__)
#define PRAGMA(x) _Pragma( #x )
#define ISR(vec) PRAGMA( vector=vec ) __interrupt void handler_##vec(void)
#endif
 
static unsigned char TWI_buf[TWI_BUFFER_SIZE]; // Transceiver buffer. Set the size in the header file
static unsigned char TWI_msgSize = 0; // Number of bytes to be transmitted.
static unsigned char TWI_state = TWI_NO_STATE; // State byte. Default set to TWI_NO_STATE.
 
// This is true when the TWI is in the middle of a transfer
// and set to false when all bytes have been transmitted/received
// Also used to determine how deep we can sleep.
static volatile unsigned char TWI_busy = 0;
 
union TWI_statusReg_t TWI_statusReg = {0}; // TWI_statusReg is defined in TWI_Slave.h
 
/****************************************************************************
Call this function to set up the TWI slave to its initial standby state.
Remember to enable interrupts from the main application after initializing the TWI.
Pass both the slave address and the requrements for triggering on a general call in the
same byte. Use e.g. this notation when calling this function:
TWI_Slave_Initialise( (TWI_slaveAddress<<TWI_ADR_BITS) | (TRUE<<TWI_GEN_BIT) );
The TWI module is configured to NACK on any requests. Use a TWI_Start_Transceiver function to
start the TWI.
****************************************************************************/
void twi_slave_init( unsigned char TWI_ownAddress )
{
TWAR = TWI_ownAddress; // Set own TWI slave address. Accept TWI General Calls.
TWCR = (1<<TWEN)| // Enable TWI-interface and release TWI pins.
(0<<TWIE)|(0<<TWINT)| // Disable TWI Interupt.
(0<<TWEA)|(0<<TWSTA)|(0<<TWSTO)| // Do not ACK on any requests, yet.
(0<<TWWC); //
TWI_busy = 0;
}
/****************************************************************************
Call this function to test if the TWI_ISR is busy transmitting.
****************************************************************************/
unsigned char twi_slave_busy( void )
{
return TWI_busy;
}
 
/****************************************************************************
Call this function to fetch the state information of the previous operation. The function will hold execution (loop)
until the TWI_ISR has completed with the previous operation. If there was an error, then the function
will return the TWI State code.
****************************************************************************/
unsigned char twi_slave_get_status( void )
{
while ( twi_slave_busy() ) {} // Wait until TWI has completed the transmission.
return ( TWI_state ); // Return error state.
}
 
/****************************************************************************
Call this function to send a prepared message, or start the Transceiver for reception. Include
a pointer to the data to be sent if a SLA+W is received. The data will be copied to the TWI buffer.
Also include how many bytes that should be sent. Note that unlike the similar Master function, the
Address byte is not included in the message buffers.
The function will hold execution (loop) until the TWI_ISR has completed with the previous operation,
then initialize the next operation and return.
****************************************************************************/
void twi_slave_start_with_data( unsigned char *msg, unsigned char msgSize )
{
unsigned char temp;
 
while ( twi_slave_busy() ) {} // Wait until TWI is ready for next transmission.
 
TWI_msgSize = msgSize; // Number of data to transmit.
for ( temp = 0; temp < msgSize; temp++ ) // Copy data that may be transmitted if the TWI Master requests data.
{
TWI_buf[ temp ] = msg[ temp ];
}
TWI_statusReg.all = 0;
TWI_state = TWI_NO_STATE ;
TWCR = (1<<TWEN)| // TWI Interface enabled.
(1<<TWIE)|(1<<TWINT)| // Enable TWI Interupt and clear the flag.
(1<<TWEA)|(0<<TWSTA)|(0<<TWSTO)| // Prepare to ACK next time the Slave is addressed.
(0<<TWWC); //
TWI_busy = 1;
}
 
/****************************************************************************
Call this function to start the Transceiver without specifing new transmission data. Useful for restarting
a transmission, or just starting the transceiver for reception. The driver will reuse the data previously put
in the transceiver buffers. The function will hold execution (loop) until the TWI_ISR has completed with the
previous operation, then initialize the next operation and return.
****************************************************************************/
void twi_slave_start( void )
{
while ( twi_slave_busy() ) {} // Wait until TWI is ready for next transmission.
TWI_statusReg.all = 0;
TWI_state = TWI_NO_STATE ;
TWCR = (1<<TWEN)| // TWI Interface enabled.
(1<<TWIE)|(1<<TWINT)| // Enable TWI Interupt and clear the flag.
(1<<TWEA)|(0<<TWSTA)|(0<<TWSTO)| // Prepare to ACK next time the Slave is addressed.
(0<<TWWC); //
TWI_busy = 0;
}
/****************************************************************************
Call this function to read out the received data from the TWI transceiver buffer. I.e. first call
TWI_Start_Transceiver to get the TWI Transceiver to fetch data. Then Run this function to collect the
data when they have arrived. Include a pointer to where to place the data and the number of bytes
to fetch in the function call. The function will hold execution (loop) until the TWI_ISR has completed
with the previous operation, before reading out the data and returning.
If there was an error in the previous transmission the function will return the TWI State code.
****************************************************************************/
unsigned char twi_slave_get_data( unsigned char *msg, unsigned char msgSize )
{
unsigned char i;
 
while ( twi_slave_busy() ) {} // Wait until TWI is ready for next transmission.
 
if( TWI_statusReg.lastTransOK ) // Last transmission completed successfully.
{
for ( i=0; i<msgSize; i++ ) // Copy data from Transceiver buffer.
{
msg[ i ] = TWI_buf[ i ];
}
TWI_statusReg.RxDataInBuf = FALSE; // Slave Receive data has been read from buffer.
}
return( TWI_statusReg.lastTransOK );
}
 
 
// ********** Interrupt Handlers ********** //
/****************************************************************************
This function is the Interrupt Service Routine (ISR), and called when the TWI interrupt is triggered;
that is whenever a TWI event has occurred. This function should not be called directly from the main
application.
****************************************************************************/
ISR(TWI_vect)
{
static unsigned char TWI_bufPtr;
switch (TWSR)
{
case TWI_STX_ADR_ACK: // Own SLA+R has been received; ACK has been returned
// case TWI_STX_ADR_ACK_M_ARB_LOST: // Arbitration lost in SLA+R/W as Master; own SLA+R has been received; ACK has been returned
TWI_bufPtr = 0; // Set buffer pointer to first data location
case TWI_STX_DATA_ACK: // Data byte in TWDR has been transmitted; ACK has been received
TWDR = TWI_buf[TWI_bufPtr++];
TWCR = (1<<TWEN)| // TWI Interface enabled
(1<<TWIE)|(1<<TWINT)| // Enable TWI Interupt and clear the flag to send byte
(1<<TWEA)|(0<<TWSTA)|(0<<TWSTO)| //
(0<<TWWC); //
TWI_busy = 1;
break;
case TWI_STX_DATA_NACK: // Data byte in TWDR has been transmitted; NACK has been received.
// I.e. this could be the end of the transmission.
if (TWI_bufPtr == TWI_msgSize) // Have we transceived all expected data?
{
TWI_statusReg.lastTransOK = TRUE; // Set status bits to completed successfully.
}
else // Master has sent a NACK before all data where sent.
{
TWI_state = TWSR; // Store TWI State as errormessage.
}
TWCR = (1<<TWEN)| // Enable TWI-interface and release TWI pins
(1<<TWIE)|(1<<TWINT)| // Keep interrupt enabled and clear the flag
(1<<TWEA)|(0<<TWSTA)|(0<<TWSTO)| // Answer on next address match
(0<<TWWC); //
TWI_busy = 0; // Transmit is finished, we are not busy anymore
break;
case TWI_SRX_GEN_ACK: // General call address has been received; ACK has been returned
// case TWI_SRX_GEN_ACK_M_ARB_LOST: // Arbitration lost in SLA+R/W as Master; General call address has been received; ACK has been returned
TWI_statusReg.genAddressCall = TRUE;
case TWI_SRX_ADR_ACK: // Own SLA+W has been received ACK has been returned
// case TWI_SRX_ADR_ACK_M_ARB_LOST: // Arbitration lost in SLA+R/W as Master; own SLA+W has been received; ACK has been returned
// Dont need to clear TWI_S_statusRegister.generalAddressCall due to that it is the default state.
TWI_statusReg.RxDataInBuf = TRUE;
TWI_bufPtr = 0; // Set buffer pointer to first data location
// Reset the TWI Interupt to wait for a new event.
TWCR = (1<<TWEN)| // TWI Interface enabled
(1<<TWIE)|(1<<TWINT)| // Enable TWI Interupt and clear the flag to send byte
(1<<TWEA)|(0<<TWSTA)|(0<<TWSTO)| // Expect ACK on this transmission
(0<<TWWC);
TWI_busy = 1;
break;
case TWI_SRX_ADR_DATA_ACK: // Previously addressed with own SLA+W; data has been received; ACK has been returned
case TWI_SRX_GEN_DATA_ACK: // Previously addressed with general call; data has been received; ACK has been returned
// TODO: What is this? Seems to be no bounds checking!
TWI_buf[TWI_bufPtr++] = TWDR;
TWI_statusReg.lastTransOK = TRUE; // Set flag transmission successfull.
// Reset the TWI Interupt to wait for a new event.
TWCR = (1<<TWEN)| // TWI Interface enabled
(1<<TWIE)|(1<<TWINT)| // Enable TWI Interupt and clear the flag to send byte
(1<<TWEA)|(0<<TWSTA)|(0<<TWSTO)| // Send ACK after next reception
(0<<TWWC); //
TWI_busy = 1;
break;
case TWI_SRX_STOP_RESTART: // A STOP condition or repeated START condition has been received while still addressed as Slave
// Enter not addressed mode and listen to address match
TWCR = (1<<TWEN)| // Enable TWI-interface and release TWI pins
(1<<TWIE)|(1<<TWINT)| // Enable interrupt and clear the flag
(1<<TWEA)|(0<<TWSTA)|(0<<TWSTO)| // Wait for new address match
(0<<TWWC); //
TWI_busy = 0; // We are waiting for a new address match, so we are not busy
break;
case TWI_SRX_ADR_DATA_NACK: // Previously addressed with own SLA+W; data has been received; NOT ACK has been returned
case TWI_SRX_GEN_DATA_NACK: // Previously addressed with general call; data has been received; NOT ACK has been returned
case TWI_STX_DATA_ACK_LAST_BYTE: // Last data byte in TWDR has been transmitted (TWEA = �0�); ACK has been received
// case TWI_NO_STATE // No relevant state information available; TWINT = �0�
case TWI_BUS_ERROR: // Bus error due to an illegal START or STOP condition
TWI_state = TWSR; //Store TWI State as errormessage, operation also clears noErrors bit
TWCR = (1<<TWSTO)|(1<<TWINT); //Recover from TWI_BUS_ERROR, this will release the SDA and SCL pins thus enabling other devices to use the bus
break;
default:
TWI_state = TWSR; // Store TWI State as errormessage, operation also clears the Success bit.
TWCR = (1<<TWEN)| // Enable TWI-interface and release TWI pins
(1<<TWIE)|(1<<TWINT)| // Keep interrupt enabled and clear the flag
(1<<TWEA)|(0<<TWSTA)|(0<<TWSTO)| // Acknowledge on any new requests.
(0<<TWWC); //
TWI_busy = 0; // Unknown status, so we wait for a new address match that might be something we can handle
}
}
 
/*
void example(){
unsigned char messageBuf[TWI_BUFFER_SIZE];
unsigned char TWI_slaveAddress;
// LED feedback port - connect port B to the STK500 LEDS
DDRB = 0xFF; // Set to ouput
PORTB = 0x55; // Startup pattern
// Own TWI slave address
TWI_slaveAddress = 0x10;
 
// Initialise TWI module for slave operation. Include address and/or enable General Call.
TWI_Slave_Initialise( (unsigned char)((TWI_slaveAddress<<TWI_ADR_BITS) | (TRUE<<TWI_GEN_BIT) ));
SEI();
 
// Start the TWI transceiver to enable reseption of the first command from the TWI Master.
TWI_Start_Transceiver();
 
// This example is made to work together with the AVR315 TWI Master application note. In adition to connecting the TWI
// pins, also connect PORTB to the LEDS. The code reads a message as a TWI slave and acts according to if it is a
// general call, or an address call. If it is an address call, then the first byte is considered a command byte and
// it then responds differently according to the commands.
 
// This loop runs forever. If the TWI is busy the execution will just continue doing other operations.
for(;;)
{
#ifdef POWER_MANAGEMENT_ENABLED
// Sleep while waiting for TWI transceiver to complete or waiting for new commands.
// If we have data in the buffer, we can't enter sleep because we have to take care
// of it first.
// If the transceiver is busy, we enter idle mode because it will wake up by all TWI
// interrupts.
// If the transceiver not is busy, we can enter power-down mode because next receive
// should be a TWI address match and it wakes the device up from all sleep modes.
if( ! TWI_statusReg.RxDataInBuf ) {
if(TWI_Transceiver_Busy()) {
MCUCR = (1<<SE)|(0<<SM2)|(0<<SM1)|(0<<SM0); // Enable sleep with idle mode
} else {
MCUCR = (1<<SE)|(0<<SM2)|(1<<SM1)|(0<<SM0); // Enable sleep with power-down mode
}
SLEEP();
} else {
NOP(); // There is data in the buffer, code below takes care of it.
}
#else // No power management
// Here you can add your own code that should be run while waiting for the TWI to finish
NOP(); // Put own code here.
#endif
// Check if the TWI Transceiver has completed an operation.
if ( ! TWI_Transceiver_Busy() )
{
// Check if the last operation was successful
if ( TWI_statusReg.lastTransOK )
{
// Check if the last operation was a reception
if ( TWI_statusReg.RxDataInBuf )
{
TWI_Get_Data_From_Transceiver(messageBuf, 2);
// Check if the last operation was a reception as General Call
if ( TWI_statusReg.genAddressCall )
{
// Put data received out to PORTB as an example.
PORTB = messageBuf[0];
}
else // Ends up here if the last operation was a reception as Slave Address Match
{
// Example of how to interpret a command and respond.
// TWI_CMD_MASTER_WRITE stores the data to PORTB
if (messageBuf[0] == TWI_CMD_MASTER_WRITE)
{
PORTB = messageBuf[1];
}
// TWI_CMD_MASTER_READ prepares the data from PINB in the transceiver buffer for the TWI master to fetch.
if (messageBuf[0] == TWI_CMD_MASTER_READ)
{
messageBuf[0] = PINB;
TWI_Start_Transceiver_With_Data( messageBuf, 1 );
}
}
}
else // Ends up here if the last operation was a transmission
{
NOP(); // Put own code here.
}
// Check if the TWI Transceiver has already been started.
// If not then restart it to prepare it for new receptions.
if ( ! TWI_Transceiver_Busy() )
{
TWI_Start_Transceiver();
}
}
else // Ends up here if the last operation completed unsuccessfully
{
TWI_Act_On_Failure_In_Last_Transmission( TWI_Get_State_Info() );
}
}
}
}*/
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/utils/twi_slave.h
0,0 → 1,121
/*****************************************************************************
*
* Atmel Corporation
*
* File : TWI_Slave.h
* Compiler : IAR EWAAVR 2.28a/3.10c
* Revision : $Revision: 2475 $
* Date : $Date: 2007-09-20 12:00:43 +0200 (to, 20 sep 2007) $
* Updated by : $Author: mlarsson $
*
* Support mail : avr@atmel.com
*
* Supported devices : All devices with a TWI module can be used.
* The example is written for the ATmega16
*
* AppNote : AVR311 - TWI Slave Implementation
*
* Description : Header file for TWI_slave.c
* Include this file in the application.
*
****************************************************************************/
/*! \page MISRA
*
* General disabling of MISRA rules:
* * (MISRA C rule 1) compiler is configured to allow extensions
* * (MISRA C rule 111) bit fields shall only be defined to be of type unsigned int or signed int
* * (MISRA C rule 37) bitwise operations shall not be performed on signed integer types
* As it does not work well with 8bit architecture and/or IAR
 
* Other disabled MISRA rules
* * (MISRA C rule 109) use of union - overlapping storage shall not be used
* * (MISRA C rule 61) every non-empty case clause in a switch statement shall be terminated with a break statement
*/
 
/****************************************************************************
TWI Status/Control register definitions
****************************************************************************/
 
#define TWI_BUFFER_SIZE 4 // Reserves memory for the drivers transceiver buffer.
// Set this to the largest message size that will be sent including address byte.
 
/****************************************************************************
Global definitions
****************************************************************************/
union TWI_statusReg_t // Status byte holding flags.
{
unsigned char all;
struct
{
unsigned char lastTransOK:1;
unsigned char RxDataInBuf:1;
unsigned char genAddressCall:1; // TRUE = General call, FALSE = TWI Address;
unsigned char unusedBits:5;
};
};
 
extern union TWI_statusReg_t TWI_statusReg;
 
 
/****************************************************************************
Function definitions
****************************************************************************/
void twi_slave_init( unsigned char );
unsigned char twi_slave_busy( void );
unsigned char twi_slave_get_status( void );
void twi_slave_start_with_data( unsigned char * , unsigned char );
void twi_slave_start( void );
unsigned char twi_slave_get_data( unsigned char *, unsigned char );
 
/****************************************************************************
Bit and byte definitions
****************************************************************************/
#define TWI_READ_BIT 0 // Bit position for R/W bit in "address byte".
#define TWI_ADR_BITS 1 // Bit position for LSB of the slave address bits in the init byte.
#define TWI_GEN_BIT 0 // Bit position for LSB of the general call bit in the init byte.
 
#define TRUE 1
#define FALSE 0
 
/****************************************************************************
TWI State codes
****************************************************************************/
// General TWI Master staus codes
#define TWI_START 0x08 // START has been transmitted
#define TWI_REP_START 0x10 // Repeated START has been transmitted
#define TWI_ARB_LOST 0x38 // Arbitration lost
 
// TWI Master Transmitter staus codes
#define TWI_MTX_ADR_ACK 0x18 // SLA+W has been tramsmitted and ACK received
#define TWI_MTX_ADR_NACK 0x20 // SLA+W has been tramsmitted and NACK received
#define TWI_MTX_DATA_ACK 0x28 // Data byte has been tramsmitted and ACK received
#define TWI_MTX_DATA_NACK 0x30 // Data byte has been tramsmitted and NACK received
 
// TWI Master Receiver staus codes
#define TWI_MRX_ADR_ACK 0x40 // SLA+R has been tramsmitted and ACK received
#define TWI_MRX_ADR_NACK 0x48 // SLA+R has been tramsmitted and NACK received
#define TWI_MRX_DATA_ACK 0x50 // Data byte has been received and ACK tramsmitted
#define TWI_MRX_DATA_NACK 0x58 // Data byte has been received and NACK tramsmitted
 
// TWI Slave Transmitter staus codes
#define TWI_STX_ADR_ACK 0xA8 // Own SLA+R has been received; ACK has been returned
#define TWI_STX_ADR_ACK_M_ARB_LOST 0xB0 // Arbitration lost in SLA+R/W as Master; own SLA+R has been received; ACK has been returned
#define TWI_STX_DATA_ACK 0xB8 // Data byte in TWDR has been transmitted; ACK has been received
#define TWI_STX_DATA_NACK 0xC0 // Data byte in TWDR has been transmitted; NOT ACK has been received
#define TWI_STX_DATA_ACK_LAST_BYTE 0xC8 // Last data byte in TWDR has been transmitted (TWEA = �0�); ACK has been received
 
// TWI Slave Receiver staus codes
#define TWI_SRX_ADR_ACK 0x60 // Own SLA+W has been received ACK has been returned
#define TWI_SRX_ADR_ACK_M_ARB_LOST 0x68 // Arbitration lost in SLA+R/W as Master; own SLA+W has been received; ACK has been returned
#define TWI_SRX_GEN_ACK 0x70 // General call address has been received; ACK has been returned
#define TWI_SRX_GEN_ACK_M_ARB_LOST 0x78 // Arbitration lost in SLA+R/W as Master; General call address has been received; ACK has been returned
#define TWI_SRX_ADR_DATA_ACK 0x80 // Previously addressed with own SLA+W; data has been received; ACK has been returned
#define TWI_SRX_ADR_DATA_NACK 0x88 // Previously addressed with own SLA+W; data has been received; NOT ACK has been returned
#define TWI_SRX_GEN_DATA_ACK 0x90 // Previously addressed with general call; data has been received; ACK has been returned
#define TWI_SRX_GEN_DATA_NACK 0x98 // Previously addressed with general call; data has been received; NOT ACK has been returned
#define TWI_SRX_STOP_RESTART 0xA0 // A STOP condition or repeated START condition has been received while still addressed as Slave
 
// TWI Miscellaneous status codes
#define TWI_NO_STATE 0xF8 // No relevant state information available; TWINT = �0�
#define TWI_BUS_ERROR 0x00 // Bus error due to an illegal START or STOP condition
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/utils/twimaster.c
0,0 → 1,202
/*************************************************************************
* Title: I2C master library using hardware TWI interface
* Author: Peter Fleury <pfleury@gmx.ch> http://jump.to/fleury
* File: $Id: twimaster.c,v 1.3 2005/07/02 11:14:21 Peter Exp $
* Software: AVR-GCC 3.4.3 / avr-libc 1.2.3
* Target: any AVR device with hardware TWI
* Usage: API compatible with I2C Software Library i2cmaster.h
**************************************************************************/
#include <inttypes.h>
#include <compat/twi.h>
 
#include <i2cmaster.h>
 
 
/* define CPU frequency in Mhz here if not defined in Makefile */
#ifndef F_CPU
#define F_CPU 16000000UL
#endif
 
/* I2C clock in Hz */
#define SCL_CLOCK 400000L
 
 
/*************************************************************************
Initialization of the I2C bus interface. Need to be called only once
*************************************************************************/
void i2c_init(void)
{
/* initialize TWI clock: 100 kHz clock, TWPS = 0 => prescaler = 1 */
TWSR = 0; /* no prescaler */
TWBR = ((F_CPU/SCL_CLOCK)-16)/2; /* must be > 10 for stable operation */
 
}/* i2c_init */
 
 
/*************************************************************************
Issues a start condition and sends address and transfer direction.
return 0 = device accessible, 1= failed to access device
*************************************************************************/
unsigned char i2c_start(unsigned char address)
{
uint8_t twst;
 
// send START condition
TWCR = (1<<TWINT) | (1<<TWSTA) | (1<<TWEN);
 
// wait until transmission completed
while(!(TWCR & (1<<TWINT)));
 
// check value of TWI Status Register. Mask prescaler bits.
twst = TW_STATUS & 0xF8;
if ( (twst != TW_START) && (twst != TW_REP_START)) return 1;
 
// send device address
TWDR = address;
TWCR = (1<<TWINT) | (1<<TWEN);
 
// wail until transmission completed and ACK/NACK has been received
while(!(TWCR & (1<<TWINT)));
 
// check value of TWI Status Register. Mask prescaler bits.
twst = TW_STATUS & 0xF8;
if ( (twst != TW_MT_SLA_ACK) && (twst != TW_MR_SLA_ACK) ) return 1;
 
return 0;
 
}/* i2c_start */
 
 
/*************************************************************************
Issues a start condition and sends address and transfer direction.
If device is busy, use ack polling to wait until device is ready
Input: address and transfer direction of I2C device
*************************************************************************/
void i2c_start_wait(unsigned char address)
{
uint8_t twst;
 
 
while ( 1 )
{
// send START condition
TWCR = (1<<TWINT) | (1<<TWSTA) | (1<<TWEN);
// wait until transmission completed
while(!(TWCR & (1<<TWINT)));
// check value of TWI Status Register. Mask prescaler bits.
twst = TW_STATUS & 0xF8;
if ( (twst != TW_START) && (twst != TW_REP_START)) continue;
// send device address
TWDR = address;
TWCR = (1<<TWINT) | (1<<TWEN);
// wail until transmission completed
while(!(TWCR & (1<<TWINT)));
// check value of TWI Status Register. Mask prescaler bits.
twst = TW_STATUS & 0xF8;
if ( (twst == TW_MT_SLA_NACK )||(twst ==TW_MR_DATA_NACK) )
{
/* device busy, send stop condition to terminate write operation */
TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWSTO);
// wait until stop condition is executed and bus released
while(TWCR & (1<<TWSTO));
continue;
}
//if( twst != TW_MT_SLA_ACK) return 1;
break;
}
 
}/* i2c_start_wait */
 
 
/*************************************************************************
Issues a repeated start condition and sends address and transfer direction
 
Input: address and transfer direction of I2C device
Return: 0 device accessible
1 failed to access device
*************************************************************************/
unsigned char i2c_rep_start(unsigned char address)
{
return i2c_start( address );
 
}/* i2c_rep_start */
 
 
/*************************************************************************
Terminates the data transfer and releases the I2C bus
*************************************************************************/
void i2c_stop(void)
{
/* send stop condition */
TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWSTO);
// wait until stop condition is executed and bus released
while(TWCR & (1<<TWSTO));
 
}/* i2c_stop */
 
 
/*************************************************************************
Send one byte to I2C device
Input: byte to be transfered
Return: 0 write successful
1 write failed
*************************************************************************/
unsigned char i2c_write( unsigned char data )
{
uint8_t twst;
// send data to the previously addressed device
TWDR = data;
TWCR = (1<<TWINT) | (1<<TWEN);
 
// wait until transmission completed
while(!(TWCR & (1<<TWINT)));
 
// check value of TWI Status Register. Mask prescaler bits
twst = TW_STATUS & 0xF8;
if( twst != TW_MT_DATA_ACK) return 1;
return 0;
 
}/* i2c_write */
 
 
/*************************************************************************
Read one byte from the I2C device, request more data from device
Return: byte read from I2C device
*************************************************************************/
unsigned char i2c_readAck(void)
{
TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWEA);
while(!(TWCR & (1<<TWINT)));
 
return TWDR;
 
}/* i2c_readAck */
 
 
/*************************************************************************
Read one byte from the I2C device, read is followed by a stop condition
Return: byte read from I2C device
*************************************************************************/
unsigned char i2c_readNak(void)
{
TWCR = (1<<TWINT) | (1<<TWEN);
while(!(TWCR & (1<<TWINT)));
return TWDR;
 
}/* i2c_readNak */
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/utils/xutils.c
0,0 → 1,765
/*****************************************************************************
* Copyright (C) 2013 Oliver Gemesi *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
*****************************************************************************/
 
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//+ xutils.c - erweiterte String-Funktionen, xprintf (Info nach History)
//+ und weitere Hilfsfunktionen wie z.B. UTCdatetime2local()
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
//############################################################################
//# HISTORY xutils.c
//#
//# 12.04.2014 OG
//# - chg: strncpyat(), strncpyat_P(), _strncpyat() erweitert um Parameter 'sepcharcount'
//#
//# 08.04.2014 OG
//# - add: strncpyat(), strncpyat_P(), _strncpyat()
//#
//# 28.02.2014 OG
//# - add: buffered_sprintf(), buffered_sprintf_P()
//# - add: buffer sprintf_buffer[]
//# - chg: PGMBUFF_SIZE und ARGBUFF_SIZE von 80 auf 40 geaendert
//#
//# 24.06.2013 OG
//# - add: strrtrim() entfernt Leerzeichen auf der rechten Seite
//#
//# 14.05.2013 OG
//# - chg: Kommentarkopf von UTCdatetime2local() aktualisiert
//#
//# 05.05.2013 OG
//# - chg: UTCdatetime2local() auf Config.timezone/summertime umgestellt
//# - add: include eeprom.h
//#
//# 04.05.2013 OG
//# - chg: umbenannt zu xutils.c
//#
//# 03.05.2013 OG
//# - add: UTCdatetime2local()
//# - fix: _xvsnprintf() Darstellung kleiner negativer Nachkommazahlen (-1<z<0)
//#
//# 29.04.2013 OG
//# - chg: Doku zu xprintf Ergaenzt bei 'bekannte Einschraenkungen'
//# - chg: includes reduziert auf das Notwendige
//#
//# 28.04.2013 OG - NEU
//############################################################################
 
 
//############################################################################
//# xprintf
//#
//# Diese Variante von printf ist angepasst auf das PKT:
//#
//# - Unterstuetzung von Festkomma-Integer Anzeige
//# - Overflow-Anzeige durch '*' wenn eine Zahl die Format-Maske sprengt
//# - progmen wird optional unterstuetz fuer den format-String als auch fuer
//# String Argumente
//# - strikte Einhaltung von Laengen einer Format-Maske
//# (ggf. wird die Ausgabe gekuerzt)
//#
//# In diesem Source sind nur die Basis-xprintf zum Erzeugen von formatierten
//# Strings. Die direkten Ausgabefunktionen auf den Screen sind in lcd.c
//# als lcdx_printf_at() und lcdx_printf_at_P().
//#
//# FORMAT ANGABEN:
//#
//# %d: dezimal int signed (Rechtsbuendige Ausgabe) (Wandlung via itoa)
//# "%d" arg: 1234 -> "1234"
//# "%5d" arg: 1234 -> " 1234"
//# "%5.2d" arg: 1234 -> " 12.34"
//# "%05d" arg: 123 -> "00123"
//# "%3.2d" arg: -13 -> " -0.13"
//#
//# %u: dezimal int unsigned (Rechtsbuendige Ausgabe) (Wandlung via utoa)
//# wie %d jedoch mittels utoa
//#
//# %h: hex int unsigned -> Hex-Zahl Rechtsbuendig, Laenge wird unterstuetzt z.B. "%4h"
//# %o: octal int unsigned -> Octal-Zahl Rechtsbuendig, Laenge wird unterstuetzt z.B. "%2o"
//# %b: binary int unsigned -> Binaer-Zahl Rechtsbuendig, Laenge wird unterstuetzt z.B. "%8b"
//#
//# %ld, %lu, %lh, %lo, %lb:
//# wie die obigen jedoch fuer long-zahlen (via ltoa, ultoa)
//# nur wenn define USE_XPRINTF_LONG gesetzt ist!
//# Bespiele: "%ld", "%5.6ld" usw.
//#
//# %s: String aus RAM -> Linksbuendig, Laenge wird unterstuetzt (z.B. "%8s")
//# %S: String aus progmem -> Linksbuendig, Laenge wird unterstuetzt (z.B. "%8s")
//#
//# %c: einzelnes char -> Linksbuendig, Laenge wird unterstuetzt (z.B. "%8s")
//# %%: Ausgabe von "%"
//#
//#
//# BEISPIELE:
//#
//# vorhanden in: osd/osdata.c, lcd/lcd.c
//#
//#
//# BEKANNTE EINSCHRAENKUNGEN:
//#
//# 1. padding '0' mit negativen Zahlen wenn padding aktiv ist ergibt z.B. "00-1.5"
//# 2. der Entwickler muss auf eine korrekte Format-Maske achten. Andernfalls
//# kommt es zu nicht vorhersehbaren Ausgaben.
//# 3. nicht in ISR's verwenden - dazu muss ggf. eine Anpassung durchgefuert werden
//#
//# KOMPILIER OPTIONEN
//#
//# define: USE_XPRINTF_LONG
//# Unterstuetzung von long int / unsigned long int ('l' Modifier in Maske)
// Wird in der main.h gesetzt
//############################################################################
 
#define USE_XPRINTF_LONG // Unterstuetzung von long integer - Achtung! Muss fuer PKT gesetzt sein
// da in Sourcen verwendet!
 
 
#include <avr/pgmspace.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <stdarg.h>
#include <stdbool.h>
 
#include "../main.h"
#include "../timer/timer.h"
#include "../eeprom/eeprom.h"
 
 
#define PGMBUFF_SIZE 40 // max. 40 chars bei format-String aus progmem
#define ARGBUFF_SIZE 40 // buffer fuer xprintf Parameter (strings, itoa, utoa) (fuer ltoa ggf. anpassen)
 
 
#define SPRINTF_BUFFER_SIZE 40 // max. 40 Chars fuer den Buffer fuer xsnprintf(), xsnprintf_P()
char sprintf_buffer[SPRINTF_BUFFER_SIZE];
 
 
//----------------------
// xprintf parser data
//----------------------
typedef struct
{
uint8_t parse; // true / false
char cmd; // char: d u h o b s S c %
uint8_t prelen; // Vorkomma
uint8_t declen; // decimal (Nachkomma)
uint8_t point; // true / false
uint8_t uselong; // true / false
uint8_t mask; // true / false
char pad; // ' ' oder '0'
} xprintf_t;
 
 
//----------------------
// Buffers
//----------------------
char cmddigit[7];
char argbuff[ARGBUFF_SIZE];
char pgmbuff[PGMBUFF_SIZE];
 
 
//####################################################################################
 
 
//---------------------------------------------------------------------
// Basisfunktion von xprintf
// Doku: siehe oben
//---------------------------------------------------------------------
void _xvsnprintf( uint8_t useprogmem, char *buffer, uint8_t n, const char *format, va_list ap )
{
const char *p_fmt; // pointer auf den format-String
char *p_dst; // pointer auf den destination buffer
const char *p_str; // pointer auf einen arg-String wenn ein String ausgegeben werden soll
char *p_cmddigit = 0; // pointer auf den Digit-Buffer fuer eine Maske (Laenge/Nachkommastellen)
const char *p_fmtbuff; // pointer auf den format-Buffer (fuer progmem)
const char *p_argbuff; // pointer auf den argbuffer
uint8_t fmtlen, arglen, overflow;
uint8_t i,j,dec;
uint8_t dstcnt;
uint8_t minus;
xprintf_t cmd; // parser Daten
 
p_fmtbuff = format;
 
if( useprogmem ) // format von progmem in's RAM kopieren
{
strncpy_P( pgmbuff, format, PGMBUFF_SIZE);
pgmbuff[PGMBUFF_SIZE-1] = 0;
p_fmtbuff = pgmbuff;
}
 
cmd.parse = false;
p_fmt = p_fmtbuff-1; // -1 -> wird am Anfang der Schleife korrigiert
p_dst = buffer;
dstcnt = 0;
 
do
{
if( dstcnt >= n ) // max. Anzahl von Zeichen fuer Ziel 'buffer' erreicht?
break;
 
p_fmt++; // naechstes Zeichen von format
 
//########################
//# 1. PARSE
//########################
 
//------------------------
// START: parse cmd
//------------------------
if( cmd.parse == false && *p_fmt == '%' )
{
memset( &cmd, 0, sizeof(xprintf_t) ); // init
cmd.parse = true;
cmd.pad = ' ';
p_cmddigit = cmddigit;
continue;
}
 
//------------------------
// NO parse: copy char
//------------------------
if( cmd.parse == false )
{
*p_dst = *p_fmt;
p_dst++;
dstcnt++;
continue;
}
 
//------------------------
// set: pad (eine '0' ganz am Anfang der Formatmaske)
//------------------------
if( cmd.parse == true && *p_fmt == '0' && p_cmddigit == cmddigit )
{
cmd.pad = '0';
continue;
}
 
//------------------------
// set: vor/nach-kommastellen
//------------------------
if( cmd.parse == true && *p_fmt >= '0' && *p_fmt <= '9' )
{
*p_cmddigit = *p_fmt;
p_cmddigit++;
continue;
}
 
//------------------------
// set: point
//------------------------
if( cmd.parse == true && *p_fmt == '.' && cmd.point == false )
{
cmd.point = true;
*p_cmddigit = 0;
cmd.prelen = atoi( cmddigit );
p_cmddigit = cmddigit;
continue;
}
 
//------------------------
// set: uselong
//------------------------
#ifdef USE_XPRINTF_LONG
if( cmd.parse == true && *p_fmt == 'l' )
{
cmd.uselong = true;
continue;
}
#endif
 
//------------------------
// END: parse cmd
//------------------------
if( cmd.parse == true && (*p_fmt == 'd' || *p_fmt == 'u' || *p_fmt == 'x' || *p_fmt == 'b' || *p_fmt == 'o' ||
*p_fmt == 's' || *p_fmt == 'S' || *p_fmt == 'c' || *p_fmt == '%') )
{
cmd.cmd = *p_fmt;
cmd.parse = false;
 
*p_cmddigit = 0;
if( cmd.point == false ) cmd.prelen = atoi(cmddigit);
else cmd.declen = atoi(cmddigit);
 
if( cmd.point || cmd.prelen>0 )
cmd.mask = true;
}
 
 
//########################
//# 2. EXECUTE
//########################
 
//------------------------
// exec cmd: "d,u,x,b,o"
//------------------------
if( cmd.cmd == 'd' || cmd.cmd == 'u' || cmd.cmd == 'x' || cmd.cmd == 'b' || cmd.cmd == 'o' )
{
if( cmd.uselong )
{
#ifdef USE_XPRINTF_LONG
switch(cmd.cmd)
{
case 'd': ltoa ( va_arg(ap, long) , argbuff, 10); break; // LONG dezimal int signed
case 'u': ultoa( va_arg(ap, unsigned long), argbuff, 10); break; // LONG dezimal int unsigned
case 'x': ultoa( va_arg(ap, unsigned long), argbuff, 16); break; // LONG hex int unsigned
case 'b': ultoa( va_arg(ap, unsigned long), argbuff, 2); break; // LONG binary int unsigned
case 'o': ultoa( va_arg(ap, unsigned long), argbuff, 8); break; // LONG octal int unsigned
}
#endif
}
else
{
switch(cmd.cmd)
{
case 'd': itoa( va_arg(ap, int) , argbuff, 10); break; // dezimal int signed
case 'u': utoa( va_arg(ap, unsigned int), argbuff, 10); break; // dezimal int unsigned
case 'x': utoa( va_arg(ap, unsigned int), argbuff, 16); break; // hex int unsigned
case 'b': utoa( va_arg(ap, unsigned int), argbuff, 2); break; // binary int unsigned
case 'o': utoa( va_arg(ap, unsigned int), argbuff, 8); break; // octal int unsigned
}
}
 
minus = (argbuff[0] == '-');
arglen = strlen(argbuff);
 
fmtlen = cmd.prelen + cmd.declen + (cmd.point ? 1 : 0);
arglen = strlen(argbuff);
 
overflow = cmd.mask && // Zahl zu gross -> "*" anzeigen statt der Zahl
(arglen > cmd.prelen + cmd.declen || cmd.prelen < 1+minus);
 
if( overflow ) // overflow: Zahl passt nicht in Maske
{ // -> zeige '*.*'
for( i=0; (i < fmtlen) && (dstcnt < n); i++)
{
if( cmd.point && i==cmd.prelen ) *p_dst = '.';
else *p_dst = '*';
p_dst++;
dstcnt++;
}
}
else // else: if( overflow )
{
if( !cmd.mask ) // keine Maske: alles von der Zahl ausgeben
fmtlen = arglen;
 
p_argbuff = argbuff;
if( minus ) // wenn Zahl negativ: merken und auf dem argbuff nehmen
{
p_argbuff++;
arglen--;
}
 
//-----------------
// die Zahl wird 'Rueckwaerts' uebertragen
//-----------------
dec = -1; // wird am Anfang der Schleife auf 0 gesetzt
j = 1; // zaehler fuer argbuff
for( i=1; i<=fmtlen; i++ )
{
dec++; // Zaehler Dizmalstellen
 
if( dstcnt+fmtlen-i <= n ) // wenn Zielbuffer nicht ueberschritten
{
if( cmd.point && (dec == cmd.declen) ) // Dezimalpunkt setzen
{
p_dst[fmtlen-i] = '.';
continue;
}
 
if( j <= arglen ) // Ziffer uebertragen aus argbuff
{
p_dst[fmtlen-i] = p_argbuff[arglen-j];
j++;
continue;
}
 
if( cmd.declen > 0 && // Nachkomma und 1. Vorkommastelle ggf. auf '0'
(dec < cmd.declen || dec == cmd.declen+1) ) // setzen wenn die Zahl zu klein ist
{
p_dst[fmtlen-i] = '0';
continue;
}
 
if( minus && ( (cmd.pad == ' ') || // ggf. Minuszeichen setzen
(cmd.pad != ' ' && i == fmtlen) ) ) // Minuszeichen bei '0'-padding an erster Stelle setzen
{
minus = false;
p_dst[fmtlen-i] = '-';
continue;
}
 
p_dst[fmtlen-i] = cmd.pad; // padding ' ' oder '0'
} // end: if( dstcnt+fmtlen-i <= n )
}
p_dst += fmtlen;
dstcnt += fmtlen;
}
continue;
}
 
//------------------------
// exec cmd: "s", "S", "c"
//------------------------
if( cmd.cmd == 's' || cmd.cmd == 'S' || cmd.cmd == 'c' )
{
switch(cmd.cmd)
{
case 's': p_str = va_arg( ap, char *); // String aus dem RAM
break;
 
case 'S': strncpy_P( argbuff, va_arg( ap, char *), ARGBUFF_SIZE); // String liegt im progmem -> in's RAM kopieren
argbuff[ARGBUFF_SIZE-1] = 0;
p_str = argbuff;
break;
 
case 'c': argbuff[0] = va_arg( ap, int); // einzelnes char
argbuff[1] = 0;
p_str = argbuff;
break;
}
 
fmtlen = cmd.prelen;
arglen = strlen(p_str);
 
if( !cmd.mask ) // keine Maske: alles vom String ausgeben
fmtlen = arglen;
 
for( i=0; i<fmtlen; i++)
{
if( dstcnt < n ) // wenn Zielbuffer nicht ueberschritten
{
if( *p_str ) // char uebertragen
{
*p_dst = *p_str;
p_str++;
}
else // padding
{
*p_dst = ' ';
}
p_dst++;
}
dstcnt++;
}
 
continue;
}
 
//------------------------
// exec cmd: "%"
//------------------------
if( cmd.cmd == '%' )
{
*p_dst = '%';
p_dst++;
dstcnt++;
continue;
}
 
} while( (dstcnt < n) && *p_fmt );
 
*(p_dst + (dstcnt < n ? 0 : -1)) = 0; // terminierende 0 im Ausgabebuffer setzen
}
 
 
 
//---------------------------------------------------------------------
//---------------------------------------------------------------------
void xsnprintf( char *buffer, uint8_t n, const char *format, ... )
{
va_list ap;
 
va_start(ap, format);
_xvsnprintf( false, buffer, n, format, ap);
va_end(ap);
}
 
 
//---------------------------------------------------------------------
//---------------------------------------------------------------------
void xsnprintf_P( char *buffer, uint8_t n, const char *format, ... )
{
va_list ap;
 
va_start(ap, format);
_xvsnprintf( true, buffer, n, format, ap);
va_end(ap);
}
 
 
 
//-----------------------------------------------------------
// buffered_sprintf_P( format, ...)
//
// Ausgabe direkt in einen internen Buffer.
// Der Pointer auf den RAM-Buffer wird zurueckgegeben.
// Abgesichert bzgl. Buffer-Overflow.
//
// Groesse des Buffers: PRINTF_BUFFER_SIZE
//
// Parameter:
// format : String aus PROGMEM (siehe: xprintf in utils/xstring.h)
// ... : Parameter fuer 'format'
//-----------------------------------------------------------
char * buffered_sprintf( const char *format, ... )
{
va_list ap;
 
va_start( ap, format );
_xvsnprintf( false, sprintf_buffer, SPRINTF_BUFFER_SIZE, format, ap );
va_end(ap);
return sprintf_buffer;
}
 
 
 
//-----------------------------------------------------------
// buffered_sprintf_P( format, ...)
//
// Ausgabe direkt in einen internen Buffer.
// Der Pointer auf den RAM-Buffer wird zurueckgegeben.
// Abgesichert bzgl. Buffer-Overflow.
//
// Groesse des Buffers: PRINTF_BUFFER_SIZE
//
// Parameter:
// format : String aus PROGMEM (siehe: xprintf in utils/xstring.h)
// ... : Parameter fuer 'format'
//-----------------------------------------------------------
char * buffered_sprintf_P( const char *format, ... )
{
va_list ap;
 
va_start( ap, format );
_xvsnprintf( true, sprintf_buffer, SPRINTF_BUFFER_SIZE, format, ap );
va_end(ap);
return sprintf_buffer;
}
 
 
 
//--------------------------------------------------------------
// kopiert einen String von src auf dst mit fester Laenge und
// ggf. Space paddings rechts
//
// - fuellt ggf. den dst-String auf size Laenge mit Spaces
// - setzt Terminierung's 0 bei dst auf Position size
//--------------------------------------------------------------
void strncpyfill( char *dst, const char *src, size_t size)
{
uint8_t i;
uint8_t pad = false;
 
for( i=0; i<size; i++)
{
if(*src == 0) pad = true;
 
if( pad ) *dst = ' ';
else *dst = *src;
 
src++;
dst++;
}
dst--;
*dst = 0;
}
 
 
 
//--------------------------------------------------------------
// entfernt rechte Leerzeichen aus einem String
//--------------------------------------------------------------
void strrtrim( char *dst)
{
char *p;
 
p = dst + strlen(dst) - 1;
 
while( (p != dst) && (*p == ' ') ) p--;
 
if( (*p != ' ') && (*p != 0) ) p++;
*p = 0;
}
 
 
 
//--------------------------------------------------------------
// INTERN - fuer strncpyat(), strncpyat_P()
//--------------------------------------------------------------
void _strncpyat( char *dst, const char *src, size_t size, const char sepchar, uint8_t sepcharcount, uint8_t progmem)
{
uint8_t i;
 
if( progmem )
strncpy_P( dst, src, size);
else
strncpy( dst, src, size);
 
for( i=0; i<size; i++)
{
if( *dst == 0) return;
if( *dst == sepchar)
{
sepcharcount--;
if( sepcharcount==0 )
{
*dst = 0;
return;
}
}
dst++;
}
dst--;
*dst = 0;
}
 
 
//--------------------------------------------------------------
// strncpyat( dst, src, size, sepchar)
//
// kopiert einen String von 'src 'auf 'dst' mit max. Laenge 'size'
// oder bis 'sepchar' gefunden wird.
//
// src in PROGMEM
//--------------------------------------------------------------
void strncpyat( char *dst, const char *src, size_t size, const char sepchar, uint8_t sepcharcount)
{
_strncpyat( dst, src, size, sepchar, sepcharcount, false);
}
 
 
//--------------------------------------------------------------
// strncpyat_P( dst, src, size, sepchar)
//
// kopiert einen String von 'src 'auf 'dst' mit max. Laenge 'size'
// oder bis 'sepchar' gefunden wird.
//
// src in RAM
//--------------------------------------------------------------
void strncpyat_P( char *dst, const char *src, size_t size, const char sepchar, uint8_t sepcharcount)
{
_strncpyat( dst, src, size, sepchar, sepcharcount, true);
}
 
 
 
//--------------------------------------------------------------
// UTCdatetime2local( PKTdatetime_t *dtbuffer, PKTdatetime_t dt )
//
// konvertiert die UTC-Time 'dt' in die lokale Zeit und speichert
// dieses in 'dtbuffer' ab.
//
// Parameter:
//
// dtdst: Pointer Destination (PKTdatetime_t) (Speicher muss alloziiert sein!)
// dtsrc: Pointer Source (PKTdatetime_t)
//
// Hinweise:
//
// Schaltjahre (bzw. der 29.02.) werden nicht unterstuetzt
//--------------------------------------------------------------
void UTCdatetime2local( PKTdatetime_t *dtdst, PKTdatetime_t *dtsrc )
{
int8_t timeoffset;
int32_t v;
int8_t diff;
// 01 02 03 04 05 06 07 08 09 10 11 12 Monat
int8_t daymonth[] = {31,28,31,30,31,30,31,31,30,31,30,31};
 
//--------------------------
// timezone: Einstellbereich -12 .. 0 .. 12 (+1 = Berlin)
// summertime: Einstellung: 0 oder 1 (0=Winterzeit, 1=Sommerzeit)
//--------------------------
timeoffset = Config.timezone + Config.summertime;
//timeoffset = 2; // solange noch nicht in PKT-Config: Berlin, Sommerzeit
 
 
memcpy( dtdst, dtsrc, sizeof(PKTdatetime_t) ); // copy datetime to destination
 
//--------------------------
// Zeitzonenanpassung
//--------------------------
if( dtdst->year != 0 && dtdst->month >= 1 && dtdst->month <= 12 ) // nur wenn gueltiges Datum vorhanden
{
//--------------------------
// 1. Sekunden
//--------------------------
v = (int32_t)dtdst->seconds;
v += timeoffset*3600; // Stunden korrigieren
diff = 0;
 
if( v > 86400 ) // Tagesueberschreitung? (86400 = 24*60*60 bzw. 24 Stunden)
{
v -= 86400;
diff++; // inc: Tag
}
else if( v < 0 ) // Tagesunterschreitung?
{
v += 86400;
diff--; // dec: Tag
}
dtdst->seconds = (uint32_t)v; // SET: seconds
 
//--------------------------
// 2. Tag
//--------------------------
v = (int32_t)dtdst->day;
v += diff;
diff = 0;
 
if( v > daymonth[dtdst->month-1] ) // Monatsueberschreitung?
{
v = 1; // erster Tag des Monats
diff++; // inc: Monat
}
else if( v < 1 ) // Monatsunterschreitung?
{
if( dtdst->month > 1 )
v = daymonth[dtdst->month-1-1]; // letzter Tag des vorherigen Monats
else
v = 31; // letzter Tag im Dezember des vorherigen Jahres
diff--; // dec: Monat
}
dtdst->day = (uint8_t)v; // SET: day
 
//--------------------------
// 3. Monat
//--------------------------
v = (int32_t)dtdst->month;
v += diff;
diff = 0;
 
if( v > 12 ) // Jahresueberschreitung?
{
v = 1;
diff++; // inc: Jahr
}
else if( v < 1 ) // Jahresunterschreitung?
{
v = 12;
diff--; // dec: Jahr
}
dtdst->month = (uint8_t)v; // SET: month
 
//--------------------------
// 4. Jahr
//--------------------------
dtdst->year += diff; // SET: year
}
}
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/utils/xutils.h
0,0 → 1,64
/*****************************************************************************
* Copyright (C) 2013 Oliver Gemesi *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
*****************************************************************************/
 
//############################################################################
//# HISTORY xutils.h
//#
//# 12.04.2014 OG
//# - chg: strncpyat(), strncpyat_P(), _strncpyat() erweitert um Parameter 'sepcharcount'
//#
//# 08.04.2014 OG
//# - add: strncpyat(), strncpyat_P()
//#
//# 28.02.2014 OG
//# - add: buffered_sprintf(), buffered_sprintf_P()
//#
//# 24.06.2013 OG
//# - add: strrtrim()
//#
//# 04.05.2013 OG
//# - chg: umbenannt zu xutils.h
//#
//# 03.05.2013 OG
//# - add: UTCdatetime2local()
//#
//# 28.04.2013 OG - NEU
//############################################################################
 
#ifndef _XUTILS_H
#define _XUTILS_H
 
#include <stdarg.h>
 
 
void _xvsnprintf( uint8_t useprogmem, char *buffer, uint8_t n, const char *format, va_list ap );
void xsnprintf( char *buffer, uint8_t n, const char *format, ... );
void xsnprintf_P( char *buffer, uint8_t n, const char *format, ... );
 
char *buffered_sprintf( const char *format, ... );
char *buffered_sprintf_P( const char *format, ... );
 
void strncpyfill( char *dst, const char *src, size_t size);
void strrtrim( char *dst);
void strncpyat( char *dst, const char *src, size_t size, const char sepchar, uint8_t sepcharcount);
void strncpyat_P( char *dst, const char *src, size_t size, const char sepchar, uint8_t sepcharcount);
 
 
void UTCdatetime2local( PKTdatetime_t *dtdst, PKTdatetime_t *dtsrc );
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/utils
Property changes:
Added: svn:ignore
+_old
+
+maniacbug-mighty-1284p-68ed99c
+
+Arduino
+
+_doc
+
+maniacbug-mighty-1284p-68ed99c.zip
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/waypoints/waypoints.c
0,0 → 1,362
/*#######################################################################################*/
/* !!! THIS IS NOT FREE SOFTWARE !!! */
/*#######################################################################################*/
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) 2008 Ingo Busker, Holger Buss
// + Nur für den privaten Gebrauch / NON-COMMERCIAL USE ONLY
// + FOR 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 permitted
// + 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 <stdlib.h>
#include <avr/io.h>
#include <stdint.h>
#include <string.h>
#include <stdbool.h>
//#include "91x_lib.h"
#include "waypoints.h"
#include "../mk-data-structs.h"
#include "../uart/uart1.h"
#include "../eeprom/eeprom.h"
#include "../main.h"
 
#include <util/delay.h>
 
#ifdef USE_WAYPOINTS
 
// the waypoints list
 
 
 
NaviData_t *NaviData;
 
//Point_t PointList[MAX_LIST_LEN];
uint8_t WPIndex = 0; // list index of GPS point representig the current WP, can be maximal WPCount
uint8_t POIIndex = 0; // list index of GPS Point representing the current POI, can be maximal WPCount
uint8_t WPCount = 0; // number of waypoints
uint8_t PointCount = 0; // number of wp in the list can be maximal equal to MAX_LIST_LEN
uint8_t POICount = 0;
 
uint8_t WPActive = false;
 
uint8_t PointList_Init(void)
{
return PointList_Clear();
}
 
uint8_t PointList_Clear(void)
{
uint8_t i;
WPIndex = 0; // real list position are 1 ,2, 3 ...
POIIndex = 0; // real list position are 1 ,2, 3 ...
WPCount = 0; // no waypoints
POICount = 0;
PointCount = 0; // no contents
WPActive = false;
NaviData->WaypointNumber = WPCount;
NaviData->WaypointIndex = 0;
 
for(i = 0; i < MAX_LIST_LEN; i++)
{
Config.PointList[i].Position.Status = INVALID;
Config.PointList[i].Position.Latitude = 0;
Config.PointList[i].Position.Longitude = 0;
Config.PointList[i].Position.Altitude = 0;
Config.PointList[i].Heading = 361; // invalid value
Config.PointList[i].ToleranceRadius = 0; // in meters, if the MK is within that range around the target, then the next target is triggered
Config.PointList[i].HoldTime = 0; // in seconds, if the was once in the tolerance area around a WP, this time defines the delay before the next WP is triggered
Config.PointList[i].Type = POINT_TYPE_INVALID;
Config.PointList[i].Event_Flag = 0; // future implementation
Config.PointList[i].AltitudeRate = 0; // no change of setpoint
}
return true;
}
 
uint8_t PointList_GetCount(void)
{
return PointCount; // number of points in the list
}
 
Point_t* PointList_GetAt(uint8_t index)
{
if((index > 0) && (index <= PointCount)) return(&(Config.PointList[index-1])); // return pointer to this waypoint
else return(NULL);
}
 
uint8_t PointList_SetAt(Point_t* pPoint)
{
// if index is in range
if((pPoint->Index > 0) && (pPoint->Index <= MAX_LIST_LEN))
{
// check list entry before update
switch(Config.PointList[pPoint->Index-1].Type)
{
case POINT_TYPE_INVALID: // was invalid
switch(pPoint->Type)
{
default:
case POINT_TYPE_INVALID:
// nothing to do
break;
 
case POINT_TYPE_WP:
WPCount++;
PointCount++;
break;
case POINT_TYPE_POI:
POICount++;
PointCount++;
break;
}
break;
case POINT_TYPE_WP: // was a waypoint
switch(pPoint->Type)
{
case POINT_TYPE_INVALID:
WPCount--;
PointCount--;
break;
 
default:
case POINT_TYPE_WP:
//nothing to do
break;
case POINT_TYPE_POI:
POICount++;
WPCount--;
break;
}
break;
case POINT_TYPE_POI: // was a poi
switch(pPoint->Type)
{
case POINT_TYPE_INVALID:
POICount--;
PointCount--;
break;
 
case POINT_TYPE_WP:
WPCount++;
POICount--;
break;
case POINT_TYPE_POI:
default:
// nothing to do
break;
}
break;
}
memcpy(&Config.PointList[pPoint->Index-1], pPoint, sizeof(Point_t)); // copy data to list entry
NaviData->WaypointNumber = WPCount;
return pPoint->Index;
}
else return(0);
}
 
// returns the pointer to the first waypoint within the list
Point_t* PointList_WPBegin(void)
{
uint8_t i;
WPIndex = 0; // set list position invalid
 
if(WPActive == false) return(NULL);
 
POIIndex = 0; // set invalid POI
if(PointCount > 0)
{
// search for first wp in list
for(i = 0; i <MAX_LIST_LEN; i++)
{
if((Config.PointList[i].Type == POINT_TYPE_WP) && (Config.PointList[i].Position.Status != INVALID))
{
WPIndex = i + 1;
break;
}
}
if(WPIndex) // found a WP in the list
{
NaviData->WaypointIndex = 1;
// update index to POI
if(Config.PointList[WPIndex-1].Heading < 0) POIIndex = (uint8_t)(-Config.PointList[WPIndex-1].Heading);
else POIIndex = 0;
}
else // some points in the list but no WP found
{
NaviData->WaypointIndex = 0;
//Check for an existing POI
for(i = 0; i < MAX_LIST_LEN; i++)
{
if((Config.PointList[i].Type == POINT_TYPE_POI) && (Config.PointList[i].Position.Status != INVALID))
{
POIIndex = i + 1;
break;
}
}
}
}
else // no point in the list
{
POIIndex = 0;
NaviData->WaypointIndex = 0;
}
 
if(WPIndex) return(&(Config.PointList[WPIndex-1]));
else return(NULL);
}
 
// returns the last waypoint
Point_t* PointList_WPEnd(void)
{
uint8_t i;
WPIndex = 0; // set list position invalid
POIIndex = 0; // set invalid
 
if(WPActive == false) return(NULL);
 
if(PointCount > 0)
{
// search backward!
for(i = 1; i <= MAX_LIST_LEN; i++)
{
if((Config.PointList[MAX_LIST_LEN - i].Type == POINT_TYPE_WP) && (Config.PointList[MAX_LIST_LEN - i].Position.Status != INVALID))
{
WPIndex = MAX_LIST_LEN - i + 1;
break;
}
}
if(WPIndex) // found a WP within the list
{
NaviData->WaypointIndex = WPCount;
if(Config.PointList[WPIndex-1].Heading < 0) POIIndex = (uint8_t)(-Config.PointList[WPIndex-1].Heading);
else POIIndex = 0;
}
else // list contains some points but no WP in the list
{
// search backward for a POI!
for(i = 1; i <= MAX_LIST_LEN; i++)
{
if((Config.PointList[MAX_LIST_LEN - i].Type == POINT_TYPE_POI) && (Config.PointList[MAX_LIST_LEN - i].Position.Status != INVALID))
{
POIIndex = MAX_LIST_LEN - i + 1;
break;
}
}
NaviData->WaypointIndex = 0;
}
}
else // no point in the list
{
POIIndex = 0;
NaviData->WaypointIndex = 0;
}
if(WPIndex) return(&(Config.PointList[WPIndex-1]));
else return(NULL);
}
 
// returns a pointer to the next waypoint or NULL if the end of the list has been reached
Point_t* PointList_WPNext(void)
{
uint8_t wp_found = 0;
if(WPActive == false) return(NULL);
if(WPIndex < MAX_LIST_LEN) // if there is a next entry in the list
{
uint8_t i;
for(i = WPIndex; i < MAX_LIST_LEN; i++) // start search for next at next list entry
{
if((Config.PointList[i].Type == POINT_TYPE_WP) && (Config.PointList[i].Position.Status != INVALID)) // jump over POIs
{
wp_found = i+1;
break;
}
}
}
if(wp_found)
{
WPIndex = wp_found; // update list position
NaviData->WaypointIndex++;
if(Config.PointList[WPIndex-1].Heading < 0) POIIndex = (uint8_t)(-Config.PointList[WPIndex-1].Heading);
else POIIndex = 0;
return(&(Config.PointList[WPIndex-1])); // return pointer to this waypoint
}
else
{ // no next wp found
NaviData->WaypointIndex = 0;
POIIndex = 0;
return(NULL);
}
}
 
void PointList_WPActive(uint8_t set)
{
if(set)
{
WPActive = true;
PointList_WPBegin(); // uopdates POI index
}
else
{
WPActive = false;
POIIndex = 0; // disable POI also
}
}
Point_t* PointList_GetPOI(void)
{
return PointList_GetAt(POIIndex);
}
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/waypoints/waypoints.h
0,0 → 1,56
#ifndef _WAYPOINTS_H
#define _WAYPOINTS_H
 
//#include "ubx.h"
#include "../mk-data-structs.h"
#define POINT_TYPE_INVALID 255
#define POINT_TYPE_WP 0
#define POINT_TYPE_POI 1
#define INVALID 0x00
 
//typedef struct
//{
// int32_t Longitude; // in 1E-7 deg
// int32_t Latitude; // in 1E-7 deg
// int32_t Altitude; // in mm
// uint8_t Status;// validity of data
//} __attribute__((packed)) GPS_Pos_t;
 
 
//typedef struct
//{
// GPS_Pos_t Position; // the gps position of the waypoint, see ubx.h for details
// int16_t Heading; // orientation, 0 no action, 1...360 fix heading, neg. = Index to POI in WP List
// uint8_t ToleranceRadius; // in meters, if the MK is within that range around the target, then the next target is triggered
// uint8_t HoldTime; // in seconds, if the was once in the tolerance area around a WP, this time defines the delay before the next WP is triggered
// uint8_t Event_Flag; // future implementation
// uint8_t Index; // to indentify different waypoints, workaround for bad communications PC <-> NC
// uint8_t Type; // typeof Waypoint
// uint8_t WP_EventChannelValue; //
// uint8_t AltitudeRate; // rate to change the setpoint
// uint8_t reserve[8]; // reserve
//} __attribute__((packed)) Point_t;
 
// Init List, return TRUE on success
uint8_t PointList_Init(void);
// Clear List, return TRUE on success
uint8_t PointList_Clear(void);
// Returns number of points in the list
uint8_t PointList_GetCount(void);
// return pointer to point at position
Point_t* PointList_GetAt(uint8_t index);
// set a point in the list at index, returns its index on success, else 0
uint8_t PointList_SetAt(Point_t* pPoint);
// goto the first WP in the list and return pointer to it
Point_t* PointList_WPBegin(void);
// goto the last WP in the list and return pointer to it
Point_t* PointList_WPEnd(void);
// goto next WP in the list and return pointer to it
Point_t* PointList_WPNext(void);
// enables/disables waypoint function
void PointList_WPActive(uint8_t set);
// returns pointer to actual POI
Point_t* PointList_GetPOI(void);
 
 
#endif // _WAYPOINTS_H
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/wi232/Wi232.c
0,0 → 1,451
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
 
//############################################################################
//# HISTORY Wi232.c
//#
//# 15.06.2014 OG
//# -chg: umgestellt auf PKT_Progress_Init() / PKT_Progress_Next()
//#
//# 10.06.2014 OG
//# KOMPLETTE SANIERUNG ab v3.80cX5
//# (ehemaliger Code in v3.80cX4 oder frueher)
//# - add: Wi232_ConfigPC() - ehemals in connect.c als Port_USB2CFG_Wi()
//#
//# 06.06.2014 OG
//# - add: Wi232_Write_Progress()
//# - chg: Codeformattierung
//#
//# 05.06.2014 OG
//# -chg: Codeformattierung
//#
//# 14.05.2014 OG
//# - chg: InitErrorWi232(), InitWi232() - umgestellt auf dezimale Anzeige des
//# Fehlercodes damit der einfacher im Source zu identifizieren ist
//# - add: Source-Historie ergaenzt
//############################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <util/delay.h>
#include <stdlib.h>
#include <string.h>
#include "../messages.h"
#include "../lcd/lcd.h"
#include "../uart/usart.h"
#include "../uart/uart1.h"
#include "../main.h"
#include "../wi232/Wi232.h"
#include "../timer/timer.h"
#include "../eeprom/eeprom.h"
#include "../setup/setup.h"
#include "../pkt/pkt.h"
#include "../utils/xutils.h"
#include "../lipo/lipo.h"
#include "../utils/menuctrl.h"
 
 
//############################################################################
//############################################################################
 
 
static const char STR_WI232INIT[] PROGMEM = "Wi.232 Init";
 
 
//############################################################################
//############################################################################
 
 
//--------------------------------------------------------------
// lError = WriteWi232( Wi232Register, RegisterValue)
//
// set Register to Wi232, Register, Value
//
// Returns:
// 0 = ACK, FF = NAK
//--------------------------------------------------------------
uint8_t Wi232_Write( uint8_t Wi232Register, uint8_t RegisterValue )
{
uint8_t timeout = 10;
uint8_t tc = 0;
unsigned int v;
 
 
if( RegisterValue < 0x80 )
{
USART_putc(0xff);
USART_putc(0x02);
USART_putc(Wi232Register);
USART_putc(RegisterValue);
}
else // RegisterValue >= 0x80
{
USART_putc(0xff);
USART_putc(0x03);
USART_putc(Wi232Register);
USART_putc(0xfe);
USART_putc(RegisterValue - 0x80);
}
 
 
do
{
v = USART_getc(); // ACK erwartet
_delay_ms(100);
tc++;
} while( (v == 0) && (tc != timeout) );
 
 
if( v != 0x06 )
{
//PKT_Message_P( text, error, timeout, beep, clearscreen)
//PKT_Message_P( PSTR("Wi.232 NAK"), true, 2000, true, true); // ERROR: max. 20 Sekunden anzeigen (wird nicht mehr angezeigt da uebernommen von hoeheren Funktionen)
return 0xFF; // return: ERROR
}
 
return 0; // return: OK (v==0x06)
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t Wi232_Write_Progress( uint8_t Wi232Register, uint8_t RegisterValue, uint8_t errorcode )
{
uint8_t nError;
 
// nError = 0: ok
// nError > 0: Fehler
nError = Wi232_Write( Wi232Register, RegisterValue );
 
PKT_Progress_Next(); // Progressbar
 
if( nError )
{
nError = errorcode;
}
 
return nError;
}
 
 
 
//--------------------------------------------------------------
// Registervalue = Wi232_Read( Wi232Register )
//
// send Readcommand to Wi232,
//
// Returns:
// Registervalue: 0 = timeout 0xFF = Syntaxerror
//--------------------------------------------------------------
uint8_t Wi232_Read( uint8_t Wi232Register )
{
uint8_t timeout = 10;
uint8_t tc = 0;
uint8_t v;
 
 
v = USART_getc(); // Zeichen loeschen
USART_putc(0xff);
USART_putc(0x02);
USART_putc(0xfe);
USART_putc(Wi232Register);
_delay_ms(50);
//lcd_printpns_at (0, 2, PSTR("read Wi232"),0);
 
 
do
{
v = USART_getc(); //ACK erwartet
_delay_ms(100);
tc++;
} while( v==0 && tc!=timeout );
 
if( tc == timeout )
return 0; // Timeout
 
if( v != 0x06 )
return 0xFF; // Syntaxerror
 
// lcd_print_hex(v,0);
// v = USART_getc(); /*Register*/
// lcd_print_hex(v,0);
// v = USART_getc(); /*Value*/
// lcd_print_hex(v,0);
 
return v;
}
 
 
 
//--------------------------------------------------------------
// foundbaud = Wi232_CheckBaud( Baudrate )
//
// RUECKGABE:
// =0: Error (Wi.232 not found at given Baud)
// >0: Baudrate
//
// INFO: Baudrate
// Baud_9600 1
// Baud_19200 2
// Baud_38400 3
// Baud_57600 4
// Baud_115200 5
// Baud_4800 6
// Baud_2400 7
//--------------------------------------------------------------
uint16_t Wi232_CheckBaud( uint8_t Baudrate ) // Suche Wi232 mit entsprechender Baudrate
{
uint8_t RegisterWi232;
 
//lcdx_cls_row( y, mode, yoffs )
lcdx_cls_row( 2, MNORMAL, 1 ); // Zeile loeschen
lcdx_printf_center_P( 2, MNORMAL, 0,1, PSTR("%S %lu Baud"), strGet(STR_SEARCH), Baud_to_uint32(Baudrate) ); // "suche nnn Baud"
 
SetBaudUart0( Baudrate ); // UART auf angegebene Baudrate setzen
 
RegisterWi232 = Wi232_Read( regDiscover );
 
//---------------------------------------------------
// Hinweis zu RegisterWi232 nach regDiscover
// == 0 : "no Wi.232 found"
// == 0xFF: "Wi.232 Syntaxerror"
//
// >0 && < 0xff: Wi.232 Version (Wi.232 gefunden)
//---------------------------------------------------
if( RegisterWi232 > 0 && RegisterWi232 < 0xFF )
{
return Baudrate; // Wi.232 gefunden
}
 
return 0; // Wi.232 nicht gefunden bei gegebener Baudrate
}
 
 
 
//--------------------------------------------------------------
// InitWI232( InitBaudrate )
//
// set Wi232Register for Mikrokopter
//
// Returns:
// 0 = ACK, FF = NAK ?????????
//--------------------------------------------------------------
void Wi232_Initalize( void )
{
uint8_t foundbaud = 0;
uint8_t nError = 0;
uint8_t InitBaudrate = Config.PKT_Baudrate;
 
 
//----------------------------
// 1. Kopter ausgeschaltet?
//----------------------------
// Text1: "Kopter ausschalten!"
// Text2: NULL
// Head : "* ACHTUNG *"
// Titel: "Wi.232 Init"
 
if( !PKT_Ask_P( ASK_CANCEL_OK, strGet(STR_SWITCHOFFMK), NULL, strGet(STR_ATTENTION), STR_WI232INIT) )
{
return;
}
 
 
//----------------------------
// 2. Wi.232 suchen
//----------------------------
PKT_Title_P( STR_WI232INIT, true, true ); // Titel - mit ShowLipo und clearscreen
 
Change_Output( Uart02Wi ); // Verbindung zu Wi232 herstellen
SwitchToWi232(); // Serielle Kanaele Wi232 mit USB verbinden
set_WI232CMD();
_delay_ms(100);
//_delay_ms(200);
 
if( !foundbaud ) foundbaud = Wi232_CheckBaud( Old_Baudrate ); // versuche zuerst mit der 'alten' Baudrate (hohe Trefferwahrscheinlichkeit)
if( !foundbaud ) foundbaud = Wi232_CheckBaud( Baud_2400 );
if( !foundbaud ) foundbaud = Wi232_CheckBaud( Baud_9600 );
if( !foundbaud ) foundbaud = Wi232_CheckBaud( Baud_19200 );
if( !foundbaud ) foundbaud = Wi232_CheckBaud( Baud_38400 );
if( !foundbaud ) foundbaud = Wi232_CheckBaud( Baud_57600 );
if( !foundbaud ) foundbaud = Wi232_CheckBaud( Baud_115200 );
 
if( !foundbaud ) // gefunden?
{
//PKT_Message_P( text, error, timeout, beep, clearscreen)
PKT_Message_P( PSTR("Wi.232 not found"), true, 2000, true, true); // ERROR: max. 20 Sekunden anzeigen
}
 
 
//----------------------------
// 3. Wi.232 initialisieren
//----------------------------
if( foundbaud > 0 )
{
//--------------
// Screen
//--------------
PKT_Title_P( STR_WI232INIT, true, true ); // Titel - mit ShowLipo und clearscreen
lcdx_printf_center_P( 2, MNORMAL, 0,1, STR_WI232INIT );
 
//PKT_Progress_Init( max, yoffs, width, height);
PKT_Progress_Init( 18, 0, 0,0); // 18 Progress Steps
 
 
// DEBUG - hier kann ggf. die _gefundene_ Baudrate vom Wi.232 angezeigt werden
//lcdx_printf_center_P( 6, MNORMAL, 0,-4, PSTR("(found %lu Baud)"), Baud_to_uint32(foundbaud) ); // zeige Baudrate
// DEBUG - und hier auf welche Baudrate das Wi.232 gesetzt werden soll
//lcdx_printf_center_P( 7, MNORMAL, 0,-2, PSTR("(set %lu Baud)"), Baud_to_uint32(Config.PKT_Baudrate) ); // zeige Baudrate
 
 
SetBaudUart0( foundbaud );
 
// wenn sich ein EEPROM-Wert ändert wird auch das Ram beschrieben damit die Änderung sofort wirksam wird
 
//--------------------------------------------------------------------------------------------------------------------
// + Errorcode
// |
// |
if( !nError ) nError = Wi232_Write_Progress( regNVTXCHANNEL,Config.WiTXRXChannel, 1); // TX Channel
if( !nError ) nError = Wi232_Write_Progress( regTXCHANNEL,Config.WiTXRXChannel , 2); // TX Channel
if( !nError ) nError = Wi232_Write_Progress( regNVRXCHANNEL,Config.WiTXRXChannel, 3); // RX Channel
if( !nError ) nError = Wi232_Write_Progress( regRXCHANNEL,Config.WiTXRXChannel , 4); // RX Channel
if( !nError ) nError = Wi232_Write_Progress( regNVSLPMODE ,Sleep_Awake , 5); // Sleepmode
if( !nError ) nError = Wi232_Write_Progress( regNVPWRMODE,WbModeP15 , 6); // Transceiver Mode/Powermode
 
 
//---------
// 06.06.2014 OG: nicht mehr unterstuetzt via setup.c (ggf. spaeter festen Standardwert einsetzen statt Config.xyz)
// Standard: TWaitTime16 (=0x10 // 16 ms Delay (default))
if( !nError ) nError = Wi232_Write_Progress( regNVTXTO,Config.WiTXTO , 7); // UART Timeout
if( !nError ) nError = Wi232_Write_Progress( regTXTO,Config.WiTXTO , 8); // UART Timeout
 
//---------
// 06.06.2014 OG: nicht mehr unterstuetzt via setup.c (ggf. spaeter festen Standardwert einsetzen statt Config.xyz)
// Standard: UartMTU64 (=64 // default=64, valid 1-144)
if( !nError ) nError = Wi232_Write_Progress( regNVUARTMTU,Config.WiUartMTU , 9); // UART Buffer
if( !nError ) nError = Wi232_Write_Progress( regUARTMTU,Config.WiUartMTU ,10); // UART Buffer
 
//---------
// 06.06.2014 OG: nicht mehr unterstuetzt via setup.c (ggf. spaeter festen Standardwert einsetzen statt Config.xyz)
// Standard: NetMode_Normal (=0x01 // Normalmode (default))
if( !nError ) nError = Wi232_Write_Progress( regNVNETMODE,Config.WiNetworkMode ,11); // Networkmode
if( !nError ) nError = Wi232_Write_Progress( regNETMODE,Config.WiNetworkMode ,12); // Networkmode
 
if( !nError ) nError = Wi232_Write_Progress( regNVUSECRC ,CRC_Enable ,13); // CRC
if( !nError ) nError = Wi232_Write_Progress( regNVCSMAMODE,CSMA_En ,14); // CSMA
if( !nError ) nError = Wi232_Write_Progress( regNVNETGRP,Config.WiNetworkGroup ,15); // Networkgroup
if( !nError ) nError = Wi232_Write_Progress( regNETGRP,Config.WiNetworkGroup ,16); // Networkgroup
if( !nError ) nError = Wi232_Write_Progress( regNVDATARATE,InitBaudrate ,17); // Baudrate
_delay_ms(200);
if( !nError ) nError = Wi232_Write_Progress( regDATARATE,InitBaudrate ,18); // Baudrate
_delay_ms(250);
 
//_delay_ms(6000); // DEBUG
 
 
if( nError )
{
//PKT_Message( text, error, timeout, beep, clearscreen)
PKT_Message( buffered_sprintf_P(PSTR("Wi.232 Error: %d"),nError), true, 2000, true, true); // ERROR: 2000 = max. 20 Sekunden anzeigen
}
else
{
//PKT_Message_P( text, error, timeout, beep, clearscreen)
PKT_Message_P( PSTR("Wi.232 Init OK!"), false, 1000, true, true); // OK: 1000 = max. 10 Sekunden anzeigen
WriteWiInitFlag(); // erfolgreiches Init merken
}
}
 
 
clr_WI232CMD();
SetBaudUart0( Config.PKT_Baudrate ); // die richtige UART Baudrate wiederherstellen !!
clear_key_all();
}
 
 
 
//--------------------------------------------------------------
// Wi232_ConfigPC()
//
// Connect USB direct to Wi.232 in Progmode
//--------------------------------------------------------------
void Wi232_ConfigPC( void )
{
lcd_cls ();
 
lcd_frect( 0, 0, 127, 7, 1); // Titelzeile Invers
lcdx_printf_at_P( 1, 0, MINVERS, 0,0, strGet(STR_WI232CONFIG) ); // Titeltext "Wi.232 Konfig."
 
lcdx_printp_center( 2, strGet(STR_USBCONNECTED), MNORMAL, 0,-2); // "mit USB verbunden"
 
lcdx_printp_center( 4, strGet(STR_SEEMKWIKI) , MNORMAL, 0,0); // "siehe MK-Wiki:"
lcdx_printp_center( 5, PSTR("\"RadioTronix\"") , MNORMAL, 0,2); // "RadioTronix"
lcd_rect_round( 0, 28, 127, 24, 1, R2); // Rahmen um Text
 
lcd_printp_at(12, 7, strGet(ENDE), MNORMAL); // Keyline "Ende"
 
 
Change_Output(USB2Wi);
 
set_WI232CMD(); // Port D6 = CMD
 
while(!get_key_press(1 << KEY_ESC))
{
show_Lipo();
}
 
clr_WI232CMD(); // Port D6 = CMD
 
if( Config.U02SV2 == 1 )
Change_Output(Uart02FC);
else
Change_Output(Uart02Wi);
 
 
// 10.06.2014 OG: das Folgende war im orginalen Port_USB2CFG_Wi() nicht
// vorhanden - das hatte den Effekt, dass wenn man diese
// Funktion aufgerufen und wieder beendet hatte das
// PKT-Updatetool kein PKT-Update mehr via PKT_CtrlHook()
// durchfuehren konnte. Die USB Umschaltung war wohl nicht sauber.
//
uart1_init( UART_BAUD_SELECT(USART_BAUD,F_CPU) ); // USB wieder zuruecksetzen damit PKT wieder normal via USB erreichbar (u.a. fuer PKT-Updatetool)
SetBaudUart1( Config.PKT_Baudrate ); // USB wieder zuruecksetzen damit PKT wieder normal via USB erreichbar (u.a. fuer PKT-Updatetool)
}
 
 
//#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/wi232/Wi232.h
0,0 → 1,192
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY Wi232.h
//#
//# 10.06.2014 OG
//# - add: Wi232_Initalize()
//# - add: Wi232_ConfigPC()
//# - del: InitWi232()
//#
//# 08.06.2014 OG
//# - chg: InitWi232() - Parameteraenderung
//# - del: Wi232_New_Baudrate
//# - add: Source-Historie ergaenzt
//############################################################################
 
#ifndef WI232_H_
#define WI232_H_
 
 
// Non-volatile Registers
// Name Address Description Default
#define regNVTXCHANNEL 0x00 // Transmit channel setting ## 0 ##
#define regNVRXCHANNEL 0x01 // Receive channel setting ## 0 ##
#define regNVPWRMODE 0x02 // Operating mode settings ## +13 dBm widebandmode ##
#define regNVDATARATE 0x03 // UART data rate ## 2400bps ##
#define regNVNETMODE 0x04 // Network mode (Normal/Slave) ## Normal ##
#define regNVTXTO 0x05 // Transmit wait timeout ## ~16ms ##
#define regNVNETGRP 0x06 // Network group ID ## 0x00 ##
#define regNVUSECRC 0x08 // Enable/Disable CRC ## Enabled ##
#define regNVUARTMTU 0x09 // Minimum transmission unit. ## 64 bytes ##
#define regNVSHOWVER 0x0A // Enable/Disable start-up message ## Enabled ##
#define regNVCSMAMODE 0x0B // Enable/Disable CSMA ## Enabled ##
#define regNVSLPMODE 0x0D // Power state of module ## Awake ##
#define regNVACKONWAKE 0x0E // Send ACK character to host on wake
 
 
// Non-volatile Read Only Registers
// Name Address Description
#define regMAC0 0x22 // These registers form the unique 48-bit MAC address.
#define regMAC1 0x23 // MAC
#define regMAC2 0x24 // MAC
#define regOUI0 0x25 // MAC
#define regOUI1 0x26 // MAC
#define regOUI2 0x27 // MAC
 
#define regDiscover 0x78 // Versionsregister
 
 
// Volatile Read/Write Registers
// Name Address Description
#define regTXCHANNEL 0x4B // Transmit channel setting
#define regRXCHANNEL 0x4C // Receive channel setting
#define regPWRMODE 0x4D // Operating mode settings
#define regDATARATE 0x4E // UART data rate
#define regNETMODE 0x4F // Network mode (Normal or Slave)
#define regTXTO 0x50 // Transmit wait timeout
#define regNETGRP 0x51 // Network group ID
#define regUSECRC 0x53 // Enable/Disable CRC
#define regUARTMTU 0x54 // Minimum transmission unit.
#define regSHOWVER 0x55 // Enable/Disable start-up message
#define regCSMAMODE 0x56 // Enable/disable CSMA
#define regSLPMODE 0x58 // Power state of module
#define regACKONWAKE 0x59 // Send ACK character to host on wake
 
 
// Wideband Channels
// regNVTXCHAN (0x00) regTXCHAN (0x4B)
// Channel Number Frequency
#define wChan0 0x00 // 868.300 MHz
#define wChan1 0x01 // 868.95 MHz ## MK ##
 
// Narrowband Channels
// regNVRXCHAN (0x01) regRXCHAN (0x4C)
// Channel Number Frequency
#define nChan0 0x00 // 868.225 MHz
#define nChan1 0x01 // 868.375 MHz ## MK ##
#define nChan2 0x02 // 868.850 MHz
#define nChan3 0x03 // 869.050 MHz
#define nChan4 0x04 // 869.525 MHz
#define nChan5 0x05 // 869.850 MHz
 
// Power Mode
// regNVPWRMODE (0x02) regPWRMODE (0x4D)
// PM1 PM1 PM0 Mode
#define NbModeN0 0x00 // 0 0 0 Narrowband Mode 0dBm power setting (typical)
#define WbModeP5 0x01 // 0 0 1 Wideband Mode +5dBm power setting (typical)
#define WbModeP10 0x02 // 0 1 0 Wideband Mode +10dBm power setting (typical)
#define WbModeP15 0x03 // 0 1 1 Wideband Mode +15dBm power setting (typical) ## MK ##
#define WbModeN0 0x04 // 1 0 0 Wideband Mode 0dBm power setting (typical)
#define NbModeP5 0x05 // 1 0 1 Narrowband Mode +5dBm power setting (typical)
#define NbModeP10 0x06 // 1 1 0 Narrowband Mode +10dBm power setting (typical)
#define NbModeP15 0x07 // 1 1 1 Narrowband Mode +15dBm power setting (typical)
 
// Wi232 UART Baudrate
// regNVDATARATE (0x03) regDATARATE (0x4E)
// Baud Rate BR2 BR1 BR0
#define Wi232_2400 Baud_2400 // 0 0 0* (default 2400)
#define Wi232_9600 Baud_9600 // 0 0 1
#define Wi232_19200 Baud_19200 // 0 1 0
#define Wi232_38400 Baud_38400 // 0 1 1
#define Wi232_57600 Baud_57600 // 1 0 0 ## MK ##
#define Wi232_115200 Baud_115200 // 1 0 1
#define Wi232_10400 0x06 // 1 1 0
#define Wi232_31250 0x07 // 1 1 1
 
// NetworkMode
// regNVNETMODE (0x04) regNETMODE (0x4F)
#define NetMode_Slave 0x00 // Slavemode
#define NetMode_Normal 0x01 // Normalmode (default)
 
// Transmit Wait Timeout
// regNVTXTO (0x05) regTXTO (0x50)
#define TWaitTimeFull 0x00 // full Buffer required
#define TWaitTime16 0x10 // 16 ms Delay (default)
 
// Network Group
// regNVNETGRP (0x06) regNETGRP (0x51)
#define NetWorkGroup 66 // default = 0, valid 0-127 ## MK = 66 ##
 
// CRC Control
// regNVUSECRC (0x08) regUSECRC (0x53)
#define CRC_Disable 0x00 // no CRC check
#define CRC_Enable 0x01 // CRC check (default)
 
// UART minimum transmission unit
// regNVUARTMTU (0x09) regUARTMTU (0x54)
#define UartMTU64 64 // default=64, valid 1-144
 
// Verbose mode
// regNVSHOWVER (0x0A)
#define ShowVers_Dis 0x00 // do not show Startupmessage ## MK = 66 ##
#define ShowVers_En 0x01 // show Startupmessage (default)
 
// CSMA enable
// regNVCSMAMODE (0x0B) regCSMAMODE (0x56)
#define CSMA_Dis 0x00 // disable CSMA Carrier-sense multiple access
#define CSMA_En 0x01 // enable CSMA (default)
 
// Sleep control
// regNVSLPMODE (0x0D) regSLPMODE (0x58)
#define Sleep_Awake 0x00 // Sleepmode = Awake (default)
#define Sleep 0x01 // Sleepmode = Sleep
#define Sleep_Stby 0x02 // Sleepmode = Standby
 
// ACK on Wake
// regNVACKONWAKE (0x0D) regACKONWAKE (0x59)
#define ACKwake_Dis 0x00 // disable ACK on Wake
#define ACKwake_En 0x01 // enable ACK on Wake (default)
 
 
 
//----------------------------------
// EXPORT
//----------------------------------
void Wi232_Initalize( void );
void Wi232_ConfigPC( void );
 
 
 
#endif // WI232_H_
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/wifly/PKT_WiFlyHQ.c
0,0 → 1,1406
/*-
* Copyright (c) 2012,2013 Darran Hunt (darran [at] hunt dot net dot nz)
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED ``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 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.
*/
 
/**
* @file WiFly RN-XV Library
*/
 
 
 
//############################################################################
//# HISTORY PKT_WiFlyHQ.c
//#
//# 03.06.2014 OG
//# - fix: find_WiFly() - Benutzer kann Suche nach WiFly jetzt abbrechen
//# (z.b. weil er kein WiFly angesteckt hat)
//# von dieser Aenderungen betroffen sind auch noch einige Codechanges
//# an anderen Funktionen.
//#
//# 15.04.2014 OG
//# - chg: wifly_init() - Logik bei der Versionsverifikation von WIFLY_ADHOC
//# geaendert da v2.38 ansonsten ggf. den Bach runter gegangen waere.
//# AKTUELL UNGETESTET DA KEIN WIFLY ADHOC VORHANDEN!
//# - add: Wifly_update() ein paar Kommentare im Code
//# - add: KOMMENTAR zu define DEBUG_WIFLY ! (lesenswert!)
//#
//# 14.04.2014 Cebra
//# - add: Defines für getestete WiFly Softwareversionen
//# - add: wifly_init bei der Versionsabfrage erweitert
//#
//# 13.04.2014 OG
//# - ggf. Probleme beim Downgrade des WiFly auf v2.38 -> deaktiviert
//# - FAST KOMPLETT NEUER CODE
//#
//# 03.04.2014 OG
//# - add: define DELAY_BEFORE_SAVE
//# - add: define DELAY_BEFORE_REBOOT
//#
//# 02.04.2014 OG
//# WIP: etliche weitere Aenderungen....
//# - chg: getVersion(): Rueckgabe/Logik geaendert
//# - add: define DELAY_AFTER_MODUL_ON
//#
//# 01.04.2014 SH
//# - chg: Nicht benötigte Progmem Strings auskommentiert
//#
//# 11.03.2014 SH
//# - add: neue Funktionen wl_reset() und wl_update()
//# - chg: wl_init() wurde komplett auf den neuen AP Modus geändert, die Init Routine vom Ad Hoc Modus befindet sich ausgeklammert darunter
//# - chg: getVersion wurde angepasst + neuer Wert für resp_Version[] PROGMEM = "RN-171\r\n" anstatt WiFly
//# - chg: setSSID() und setPassphrase() wurden um weiteren Parameter ergänzt
//# - chg: createAdhocNetwork angepasst da Funktion setSSID() enthalten
//# - del: ausgeklammerte Funktionen getConnection, getDHCPMode, getSpaceReplace, getopt_Asc und join
//#
//# 12.02.2014 OG
//# - chg: readTimeout() Auskommentiert: "unused variable 'ind'"
//# - chg: wl_init() Auskommentiert: "unused variable 'dhcpMode'"
//#
//# 02.07.2013 cebra
//# - new: Routinen für WiFly WLAN-Modul
//#
//###########################################################################
 
 
#include <avr/pgmspace.h>
#include <stdbool.h>
#include <stdlib.h>
#include <stdarg.h>
#include <util/delay.h>
#include <inttypes.h>
#include <string.h>
#include "../main.h"
#include "PKT_WiFlyHQ.h"
#include "../eeprom/eeprom.h"
#include "../uart/uart1.h"
#include "../timer/timer.h"
#include "../lcd/lcd.h"
#include "../messages.h"
#include "../pkt/pkt.h"
#include "../utils/xutils.h"
#include "wifly_setup.h"
 
 
#ifdef USE_WLAN
 
 
//----------------------------------------------------
// DEBUG
//
// Wenn 'DEBUG_WIFLY' eingeschalte wird dann werden die Ausgaben
// des WiFly auf dem PKT-Screen angezeigt - fast wie bei einem
// Terminal Programm!
//
// Man kann dadurch genaueres erkennen wie die Kommunikation
// ablaeuft und mit welchen Strings beispielsweise das WiFly
// ein Ok quittiert.
//----------------------------------------------------
//#define DEBUG_WIFLY
 
//----------------------------------------------------
// unterstützte WiFly Softwareversionen
//----------------------------------------------------
 
#define Adhoc_Version1 232 // getestet Version 2.32
#define Adhoc_Version2 238 // getestet Version 2.38
 
#define Apmode_Version1 441 // getestet Version 4.41
 
 
//----------------------------------------------------
// Einstellungen
//----------------------------------------------------
static const char WIFLY_IP_ADDRESS[] PROGMEM = "169.254.1.1";
static const char WIFLY_IP_PORT[] PROGMEM = "2000";
 
static const char WIFLY_IP_GATEWAY[] PROGMEM = "169.254.1.1";
static const char WIFLY_IP_NETMASK[] PROGMEM = "255.255.0.0";
 
static const char WIFLY_VERSION_ADHOC[] PROGMEM = "2.38.3";
//static const char WIFLY_VERSION_ADHOC[] PROGMEM = "v2.32";
static const char WIFLY_VERSION_APMODE[] PROGMEM = "4.41";
 
 
//----------------------------------------------------
// Einsstellungen fuer Delay's
//----------------------------------------------------
//#define WIFLY_DEFAULT_TIMEOUT 500 /* 500 milliseconds */
#define WIFLY_DEFAULT_TIMEOUT 100 // n milliseconds
 
 
//----------------------------------------------------
//----------------------------------------------------
uint8_t progress_max = 0;
uint8_t progress_act = 0;
char progress_buffer[22];
char buffer[20];
 
 
char wifly_version_string[12];
uint16_t wifly_version;
 
 
//----------------------------------------------------
// Texte
//----------------------------------------------------
static const char STR_WIFLY_NOT_FOUND[] PROGMEM = "WiFly not found";
 
static const char RECEIVE_AOK[] PROGMEM = "AOK";
 
#define REPLACE_SPACE_CHAR '$' // ersetzt Spaces in einem String-Parameter des WiFly - '$' ist WiFly default (0x24) fuer SSID und Pwd
 
//static const char [] PROGMEM = "";
 
//----------------------------------------------------
 
 
//#############################################################################
//#
//#############################################################################
 
 
//----------------------------------------------------
//----------------------------------------------------
void debug_begin( void )
{
lcd_cls();
lcd_setpos(0,0);
}
 
 
//----------------------------------------------------
//----------------------------------------------------
void debug_wait( void )
{
set_beep( 25, 0xffff, BeepNormal );
clear_key_all();
while( !get_key_press(1 << KEY_ESC) && !get_key_press(1 << KEY_ENTER) );
lcd_print_LF();
}
 
 
//----------------------------------------------------
//----------------------------------------------------
void debug_message( uint8_t *text )
{
lcd_print_LF();
lcd_print( text, MINVERS );
debug_wait();
lcd_print_LF();
}
 
 
 
 
 
 
//#############################################################################
//#
//#############################################################################
 
 
/** Read the next character from the WiFly serial interface.
* Waits up to timeout milliseconds to receive the character.
* @param chp pointer to store the read character in
* @param timeout the number of milliseconds to wait for a character
* @retval true - character read
* @retval false - timeout reached, character not read
*/
bool readTimeout( char *chp, uint16_t timeout)
{
char ch;
timer2 = timeout;
 
while( timer2>0 )
{
if( uart1_available() > 0 )
{
ch = uart1_getc();
*chp = ch;
 
#ifdef DEBUG_WIFLY
lcd_print_char( ch, MNORMAL);
#endif
 
return (true);
}
}
 
return (false);
}
 
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void flushRx( int timeout )
{
char ch;
while( readTimeout( &ch, timeout) );
}
 
 
 
 
/**
* Read characters from the WiFly and match them against the
* progmem string. Ignore any leading characters that don't match. Keep
* reading, discarding the input, until the string is matched
* or until no characters are received for the timeout duration.
* @param str The string to match, in progmem.
* @param timeout fail if no data received for this period (in milliseconds).
* @retval true - a match was found
* @retval false - no match found, timeout reached
*/
bool match_P( const char *str, uint16_t timeout)
{
const char *match = str;
char ch, ch_P;
 
ch_P = pgm_read_byte(match);
if( ch_P == '\0' ) return true; /* Null string always matches */
 
while( readTimeout( &ch, timeout) )
{
// DEBUG
//lcd_print_char( ch, MNORMAL );
 
if( ch == ch_P ) match++;
else
{
match = str; // Restart match
if( ch == pgm_read_byte(match) ) match++;
}
 
ch_P = pgm_read_byte( match );
if( ch_P == '\0' ) return (true);
}
 
return (false);
}
 
 
 
 
 
 
//#############################################################################
//# progress
//#############################################################################
 
//--------------------------------------------------------------
// msg: PROGMEM
//--------------------------------------------------------------
void progress_begin( uint8_t maxsteps )
{
progress_max = maxsteps;
progress_act = 0;
}
 
 
//--------------------------------------------------------------
// wait4key: true / false
//--------------------------------------------------------------
void progress_end( uint8_t wait4key )
{
progress_max = 0;
progress_act = 0;
 
if( wait4key )
{
lcd_printp_at( 12, 7, strGet(ENDE), MNORMAL); // Keyline
set_beep( 25, 0xffff, BeepNormal ); // kurzer Bestaetigungs-Beep
clear_key_all();
while( !get_key_press(1 << KEY_ESC) ); // warte auf Taste...
}
}
 
 
 
//--------------------------------------------------------------
// msg: PROGMEM
//--------------------------------------------------------------
void progress_show( const char *msg )
{
int8_t yoffs = 3;
 
#ifdef DEBUG_WIFLY
return;
#endif
 
if( progress_max )
{
progress_act++;
 
lcdx_printf_center_P( 4, MNORMAL, 0,yoffs, PSTR("%d/%d"), progress_act, progress_max );
 
if( msg )
{
strncpyat_P( progress_buffer, msg, 20, ' ', 2);
 
lcd_frect( 2, (5*8)+yoffs, 124, 7, 0); // Zeile 5 loeschen
lcdx_print_center( 5, (uint8_t *)progress_buffer, MNORMAL, 0,yoffs); // Text zentriert; String im RAM
}
 
lcd_rect_round( 0, 28+yoffs, 127, 22, 1, R2); // Rahmen
_delay_ms(700); // fuer Anzeige (Entschleunigung)
}
}
 
 
 
//--------------------------------------------------------------
// gibt zentriert einen Text und loescht vorher die Zeile
//--------------------------------------------------------------
void MsgCenter_P( uint8_t y, const char *text, uint8_t mode, int8_t yoffs )
{
lcdx_cls_row( y, MNORMAL, yoffs );
lcdx_printp_center( y, text, MNORMAL, 0, yoffs );
}
 
 
 
//#############################################################################
//# sendcmd
//#############################################################################
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void cmd_showerror( const char *cmdstr)
{
//void PKT_Message_P( const char *text, uint8_t error, uint16_t timeout, uint8_t beep, uint8_t clearscreen )
PKT_Message_P( cmdstr, true, 3000, true, true ); // max. 30 Sekunden anzeigen
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t find_Prompt()
{
char c;
uint8_t state = 0;
 
while( readTimeout( &c, WIFLY_DEFAULT_TIMEOUT) )
{
if( state == 0 && (c == '>') ) { state = 1; continue; }
if( state == 1 && (c == ' ') ) return true;
 
if( state == 1 ) break; // Fehler: nicht vorgesehen
}
 
return false;
}
 
 
//--------------------------------------------------------------
// nicht verwendet...
//--------------------------------------------------------------
uint8_t find_Prompt2()
{
char c;
 
timer2 = 800; // 8 Sekunden max. suchen
while( readTimeout( &c, WIFLY_DEFAULT_TIMEOUT) && timer2 )
{
if( c == '>' ) return true;
}
 
return false;
}
 
 
 
//--------------------------------------------------------------
// Das ist erstmal so uebernommen - ob das alles sein muss??
//
// Put the WiFly into command mode
//
// RUECKGABE:
// >0: ok
// =0: Fehler
// -1: Abbruch Benutzer
//--------------------------------------------------------------
int8_t cmd_EnterCommandMode( void )
{
uint8_t retry = 2;
int8_t result = 0; // false
 
while( retry && !result )
{
//_delay_ms(250);
uart1_puts_p( PSTR("$$$") );
//_delay_ms(250);
_delay_ms(100);
uart1_putc('\r');
 
if( get_key_short(1 << KEY_ESC) ) // Abbruch durch Benutzer?
{
return -1; // -1 = Abbruch Benutzer
}
 
result = find_Prompt(); // ggf. result = true
if( !result )
{
retry--;
_delay_ms(250);
}
}
 
return result;
}
 
 
 
//--------------------------------------------------------------
// PARAMETER:
// cmdstr : PROGMEM
// strvalue : RAM
// match_receive: PROGMEM
// findprompt : true/false
//--------------------------------------------------------------
uint8_t cmdsend( const char *cmdstr, const char *strvalue, const char *match_receive, uint8_t findprompt )
{
uint8_t result = true;
const char *p;
char c;
 
progress_show( cmdstr );
 
//--------------------
// Senden...
//--------------------
uart1_puts_p( cmdstr );
 
if( strvalue != NULL )
{
uart1_putc(' ');
 
p = strvalue;
while( *p )
{
c = *p;
if( c == ' ' ) c = REPLACE_SPACE_CHAR;
uart1_putc( c );
p++;
}
}
uart1_putc('\r');
 
 
//--------------------
// Antwort...
//--------------------
if( match_receive )
{
//if( !match_P( p, WIFLY_DEFAULT_TIMEOUT) )
if( !match_P( match_receive, 2000) )
{
cmd_showerror( cmdstr ); // Fehler auf PKT Screen anzeigen und durch Benutzer bestaetigen lassen
result = false;
}
// DEBUG
//lcdx_printf_at_P( 2, 7, MINVERS, 0,0, PSTR("%d"), result );
}
 
#ifdef DEBUG_WIFLY
debug_wait();
#endif
 
// TODO: Kommandos die keinen Prompt zurueckliefern? (evtl. 'reset'?)
//uart1_putc('\r'); // fuer cmd_Join ein extra Return... (bei den anderen Kommandos stoert es nicht)
 
if( result && findprompt)
{
result = find_Prompt();
}
 
return( result );
}
 
 
 
//--------------------------------------------------------------
// cmdsend_P()
//
// PARAMETER:
//--------------------------------------------------------------
uint8_t cmdsend_P( const char *cmdstr, const char *strvalue, const char *match_receive, uint8_t findprompt )
{
strncpy_P( buffer, strvalue, 20);
return cmdsend( cmdstr, buffer, match_receive, findprompt );
}
 
 
 
//--------------------------------------------------------------
// Version wird anhand des Prompt's ermittelt
// Implementiert als State-Machine
//--------------------------------------------------------------
uint8_t cmd_GetVersion( void )
{
char c;
uint8_t state = 0;
char *dst = wifly_version_string;
uint8_t n = 0;
 
wifly_version = 0;
 
uart1_putc('\r'); // erzwinge Prompt
 
while( readTimeout( &c, WIFLY_DEFAULT_TIMEOUT) )
{
if( (state == 0) && (c == '<') )
{
state = 1;
continue;
}
 
if( (state == 1) && (c != '>') )
{
// TODO: Ende vom Prompt im Fehlerfall catchen...
if( n+1 >= sizeof(wifly_version_string) )
break;
*dst = c;
dst++;
n++;
continue;
}
 
if( (state == 1) && (c == '>') ) // Versionsstring-Ende erreicht
{
*dst = 0;
state = 2;
break;
}
 
}
 
 
if( state == 2 )
{
//uint16_t wifly_version;
wifly_version = (wifly_version_string[0]-'0') * 100;
wifly_version += (wifly_version_string[2]-'0') * 10;
wifly_version += (wifly_version_string[3]-'0') * 1;
}
else
{
cmd_showerror( PSTR("get version") ); // Fehler auf PKT Screen anzeigen und durch Benutzer bestaetigen lassen
}
 
return (state == 2);
}
 
 
 
//--------------------------------------------------------------
// cmd_Set()
//
// PARAMETER:
// cmdstr: PROGMEM
//--------------------------------------------------------------
uint8_t cmd_Set( const char *cmdstr )
{
return cmdsend( cmdstr, 0, RECEIVE_AOK, true );
}
 
 
 
//--------------------------------------------------------------
// cmd_SetStr()
//
// PARAMETER:
// cmdstr: PROGMEM
// str : RAM
//--------------------------------------------------------------
uint8_t cmd_SetStr( const char *cmdstr, const char *str )
{
return cmdsend( cmdstr, str, RECEIVE_AOK, true );
}
 
 
 
//--------------------------------------------------------------
// cmd_SetStr()
//
// PARAMETER:
// cmdstr: PROGMEM
// str : PROGMEM
//--------------------------------------------------------------
uint8_t cmd_SetStr_P( const char *cmdstr, const char *str )
{
return cmdsend_P( cmdstr, str, RECEIVE_AOK, true );
}
 
 
 
//--------------------------------------------------------------
// cmd_SetNum()
//
// PARAMETER:
// cmdstr: PROGMEM
// value : Dezimal
//--------------------------------------------------------------
uint8_t cmd_SetNum( const char *cmdstr, const uint16_t value )
{
utoa( value, buffer, 10 );
return cmd_SetStr( cmdstr, buffer);
}
 
 
 
//--------------------------------------------------------------
// cmd_Reset()
//--------------------------------------------------------------
uint8_t cmd_Reset( void )
{
uint8_t result = true;
 
//_delay_ms( 500 );
result = cmdsend( PSTR("factory RESET"), 0, PSTR("Defaults"), false );
_delay_ms( 1000 );
 
return result;
 
// return cmdsend( PSTR("factory RESET"), 0, PSTR("Defaults"), true );
}
 
 
 
//--------------------------------------------------------------
// cmd_Save()
//--------------------------------------------------------------
uint8_t cmd_Save( void )
{
//_delay_ms( DELAY_BEFORE_SAVE );
_delay_ms( 200 );
return cmdsend( PSTR("save"), 0, PSTR("Storing"), true );
}
 
 
//--------------------------------------------------------------
// cmd_Join()
//--------------------------------------------------------------
uint8_t cmd_Join( const char *ssid )
{
uint8_t result = true;
 
result = cmdsend( PSTR("join"), ssid, PSTR("Associated"), false );
if( result ) uart1_putc('\r');;
if( result ) result = find_Prompt();
 
return result;
}
 
 
 
//--------------------------------------------------------------
// cmd_Reboot()
//--------------------------------------------------------------
uint8_t cmd_Reboot( void )
{
//_delay_ms( DELAY_BEFORE_REBOOT );
_delay_ms( 300 );
cmdsend( PSTR("reboot"), 0, 0, false );
_delay_ms( 2000 );
return true;
}
 
 
 
//#############################################################################
//# WiFly suchen
//#############################################################################
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
void find_WiFly_searchmsg( const char *text, uint8_t baud )
{
lcd_frect( 0, 2*8, 126, 7, 0); // Zeile 2 loeschen
lcdx_printf_center_P( 2, MNORMAL, 0,0, PSTR("%S %lu Baud"), text, Baud_to_uint32(baud) ); // Text zentriert
}
 
 
 
//--------------------------------------------------------------
// RUECKGABE:
// >0: ok
// =0: Fehler
// -1: Abbruch Benutzer
//--------------------------------------------------------------
int8_t find_WiFly_baud( uint8_t baud )
{
int8_t result = 1;
 
find_WiFly_searchmsg( strGet(STR_SEARCH), baud );
 
// Anmerkung 06.04.2014 OG:
// SetBaudUart1() (in uart/uart1.c) setzt nur die Baudrate des Uart.
// Config.PKT_Baudrate wird durch SetBaudUart1() NICHT geaendert!
SetBaudUart1( baud );
 
result = cmd_EnterCommandMode();
 
if( result > 0 )
{
return baud; // Baud gefunden, ok!
}
 
return result; // nicht gefunden oder Abbruch durch Benutzer
}
 
 
 
//--------------------------------------------------------------
// ok = find_WiFly()
//
// Sucht das WiFly mit verschiedenen Baudraten.
//
// Wenn das WiFly mit von Config.PKT_Baudrate (= 57600) abweichender
// Baudrate gefunden wird (z.B. 9600 Baud) dann wird das WiFly
// automatisch auf 57600 Baud umkonfiguriert damit nachfolgende
// Funktionen das nicht mehr beachten muessen.
//
// RUECKGABE:
// ok = true : WiFly gefunden und ist auf 57600 Baud
// ok = false: kein WiFly gefunden
//
// >0: ok
// =0: Fehler
// -1: Abbruch Benutzer
//
// Anmerkung:
// #define Baud_9600 1
// #define Baud_19200 2
// #define Baud_38400 3
// #define Baud_57600 4
// #define Baud_115200 5
// #define Baud_4800 6
// #define Baud_2400 7
//--------------------------------------------------------------
int8_t find_WiFly( void ) // search Wifly with all Baudrates
{
int8_t result = 1; // 1 == true
int8_t baud = 0;
 
//inCommandMode = false;
//exitCommand = 0;
 
set_Modul_On( Wlan ); // WiFly einschalten
 
timer2 = 60; // Delay damit das WiFly booten kann
while( timer2 );
 
lcd_printp_at(12, 7, strGet(ENDE), MNORMAL); // Keyline: "Ende"
 
//------------------------
// suche WiFly mit versch. Baudraten
//------------------------
if( baud==0 ) baud = find_WiFly_baud( Baud_57600 );
if( baud==0 ) baud = find_WiFly_baud( Baud_9600 );
if( baud==0 ) baud = find_WiFly_baud( Baud_115200 );
if( baud==0 ) baud = find_WiFly_baud( Baud_38400 );
if( baud==0 ) baud = find_WiFly_baud( Baud_19200 );
if( baud==0 ) baud = find_WiFly_baud( Baud_4800 );
if( baud==0 ) baud = find_WiFly_baud( Baud_2400 );
 
lcdx_cls_row( 7, MNORMAL, 0); // Keyline loeschen
 
//------------------------
// Abbruch durch Benutzer?
//------------------------
if( baud < 0 )
{
SetBaudUart1( Config.PKT_Baudrate ); // orginal Baudrate von Uart1 wieder herstellen
set_Modul_On( USB ); // wieder auf USB zurueckschalten
return -1; // -1 = Abbruch Benutzer
}
 
 
//------------------------
// kein WiFly gefunden...
//------------------------
if( baud==0 ) // WiFly nicht gefunden :-(
{
SetBaudUart1( Config.PKT_Baudrate ); // orginal Baudrate von Uart1 wieder herstellen
set_Modul_On( USB ); // wieder auf USB zurueckschalten
 
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( STR_WIFLY_NOT_FOUND, true, 3000, true, true ); // max. 30 Sekunden anzeigen
 
return false; // 0 = nicht gefunden
}
 
 
//------------------------
// WiFly gefunden!
//------------------------
find_WiFly_searchmsg( strGet(STR_FOUND), baud ); // Anzeige: "gefunden..."
 
 
//------------------------
// WiFly Baud ok?
// -> ggf. WiFly Baud umkonfigurieren
//------------------------
if( Config.PKT_Baudrate != baud )
{
find_WiFly_searchmsg( strGet(STR_SET), Config.PKT_Baudrate ); // Anzeige: "setze..."
 
if( result ) result = cmd_Set( PSTR("set u b 57600") ); // -> etwas unsauber hier einfach 57600 zu setzen und nicht Config.PKT_Baudrate
if( result ) result = cmd_Save();
if( result ) result = cmd_Reboot(); // true = uart-baud setzen
 
SetBaudUart1( Config.PKT_Baudrate ); // orginal Baudrate von Uart1 wieder herstellen
if( result ) result = cmd_EnterCommandMode();
}
 
 
return result;
}
 
 
 
//#############################################################################
//#
//#############################################################################
 
 
//--------------------------------------------------------------
// zeigt die WiFly-Version an
//--------------------------------------------------------------
uint8_t wifly_version_show( void )
{
int8_t result = 1; // 1 = true
 
ShowTitle_P( PSTR("WiFly Version"), true );
 
result = find_WiFly();
 
if( result < 0 ) // Abbruch durch Benutzer?
{
clear_key_all();
return result;
}
 
if( result ) result = cmd_GetVersion(); // Ergebnis in 'wifly_version_string'
 
set_Modul_On( USB );
 
if( result )
{
// TODO:
// Anzeige ob WiFly-Version kompatibel zum gewaehlten
// Mode (AP-Mode, AdHoc) ist
//lcd_frect( 0, 2*8, 126, 7, 0); // Zeile 2 loeschen
 
lcd_rect_round( 0, 8*4+3, 127, 8*2, 1, R2); // Anzeige-Rahmen
lcdx_printf_center_P( 5, MNORMAL, 0,0, PSTR("Version: v%s"), wifly_version_string );
 
lcd_printp_at( 12, 7, strGet(ENDE), MNORMAL); // Keyline
set_beep( 25, 0xffff, BeepNormal ); // kurzer Bestaetigungs-Beep
 
clear_key_all();
while( !get_key_press(1 << KEY_ESC) ); // warte auf Taste...
}
else
{
PKT_Message_P( PSTR("Version FAIL!"), true, 3000, true, true ); // max. 30 Sekunden anzeigen
}
 
clear_key_all();
return result;
}
 
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t _ask( uint8_t keyline )
{
uint8_t ask = 0;
 
lcd_rect_round( 0, 34, 127, 16, 1, R2); // Rahmen
 
lcd_printp_at( 12, 7, strGet(keyline), MNORMAL); // Keyline
 
if( keyline == ENDE )
set_beep( 1000, 0xffff, BeepNormal ); // langer Error-Beep
else
set_beep( 25, 0xffff, BeepNormal ); // kurzer Bestaetigungs-Beep
 
clear_key_all();
while( !ask ) // warte auf Ja/Nein
{
if( get_key_press(1 << KEY_ENTER) ) ask = 1; // "Ja"
if( get_key_press(1 << KEY_ESC) ) ask = 2; // "Nein"
};
 
return( ask==1 );
}
 
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t wifly_init_perform( uint8_t wiflymode ) //AP Mode
{
uint8_t result = true;
 
#ifndef DEBUG_WIFLY
MsgCenter_P( 2, PSTR("INIT"), MNORMAL, 0 );
#endif
 
 
//---------------
// WIFLY_ADHOC
//---------------
if( wiflymode == WIFLY_ADHOC )
{
progress_begin( 9 );
 
//if( result ) result = cmd_Set( PSTR("set u m 1") ); // ist das notwendig? - (turn off echo)
//if( result ) result = cmd_Set( PSTR("set sys printlvl 0") ); // ist das notwendig?
//if( result ) result = cmd_Set( PSTR("set comm remote 0") ); // ist das notwendig?
 
if( result ) result = cmd_Set( PSTR("set wlan join 4") ); // 4 = AdHoc
if( result ) result = cmd_Set( PSTR("set ip dhcp 0") );
 
if( result ) result = cmd_SetStr_P( PSTR("set ip address"), WIFLY_IP_ADDRESS );
if( result ) result = cmd_SetStr_P( PSTR("set ip gateway"), WIFLY_IP_GATEWAY );
if( result ) result = cmd_SetStr_P( PSTR("set ip netmask"), WIFLY_IP_NETMASK );
 
if( result ) result = cmd_SetStr( PSTR("set wlan ssid"), Config.Wlan_SSID );
if( result ) result = cmd_SetNum( PSTR("set wlan chan"), Config.Wlan_Channel );
}
 
 
//---------------
// WIFLY_APMODE
//---------------
if( wiflymode == WIFLY_APMODE )
{
progress_begin( 13 );
 
if( result ) result = cmd_Set( PSTR("set wlan join 7") );
if( result ) result = cmd_Set( PSTR("set ip dhcp 4") );
 
if( result ) result = cmd_SetStr_P( PSTR("set ip address"), WIFLY_IP_ADDRESS );
if( result ) result = cmd_SetStr_P( PSTR("set ip gateway"), WIFLY_IP_GATEWAY );
if( result ) result = cmd_SetStr_P( PSTR("set ip netmask"), WIFLY_IP_NETMASK );
 
if( result ) result = cmd_Set( PSTR("set wlan rate 3") );
if( result ) result = cmd_SetStr( PSTR("set apmode ssid") , Config.Wlan_SSID );
if( result ) result = cmd_SetStr( PSTR("set apmode pass") , Config.Wlan_Password );
if( result ) result = cmd_SetNum( PSTR("set wlan channel"), Config.Wlan_Channel );
if( result ) result = cmd_Set( PSTR("set ip protocol 0x3") );
if( result ) result = cmd_Set( PSTR("set apmode link_monitor 0") );
}
 
if( result ) result = cmd_Save();
if( result ) result = cmd_Reboot();
 
progress_end( false ); // Progress abschalten
 
return( result );
}
 
 
 
 
//--------------------------------------------------------------
// ok = wifly_init( wiflymode )
//
// initialisiert das WiFly fuer AP-Mode oder AdHoc
//
// PARAMETER:
// wiflymode: WIFLY_APMODE = Firmware wifly7-441.img
// WIFLY_ADHOC = Firmware wifly7-2383.img
//--------------------------------------------------------------
uint8_t wifly_init( uint8_t wiflymode ) //AP Mode
{
int8_t result = 1; // 1 = true
uint8_t ask = false;
uint8_t versionerror = false;
char *title = (char *)PSTR("Init WiFly");
char *strMode;
 
if( wiflymode == WIFLY_ADHOC ) strMode = (char *)PSTR("AdHoc");
else strMode = (char *)PSTR("AP-Mode");
 
ShowTitle_P( title, true );
 
result = find_WiFly();
 
if( result < 0 ) // Abbruch durch Benutzer?
{
clear_key_all();
return result;
}
 
 
if( result ) result = cmd_GetVersion();
 
//-----------------------------
// Version pruefen
//-----------------------------
if( result )
{
//--------
// ADHOC
//--------
if( wiflymode == WIFLY_ADHOC )
{
if( (wifly_version != Adhoc_Version1) // 2.32
&& (wifly_version != Adhoc_Version2) // 2.38
)
{
versionerror = true;
}
}
 
//--------
// APMODE
//--------
if( wiflymode == WIFLY_APMODE && wifly_version != Apmode_Version1 ) versionerror = true;
 
if( versionerror )
{
set_Modul_On( USB );
ShowTitle_P( title, true );
lcdx_printf_center_P( 2, MNORMAL, 0, -4, PSTR("WiFly v%s"), wifly_version_string );
lcdx_printf_center_P( 3, MNORMAL, 0, -1, PSTR("ERROR") );
lcdx_printf_center_P( 5, MNORMAL, 0, -1, PSTR("Version no %S!"), strMode ); // "Version no AP-Mode" / "AdHoc"
ask = _ask( ENDE );
 
return false;
}
}
 
 
//-----------------------------
// Benutzer fragen
//-----------------------------
if( result )
{
ShowTitle_P( title, true );
//lcdx_printf_at_P( 0, 1, MINVERS, 0,0, PSTR("%d"), wifly_version );
 
lcdx_printf_center_P( 2, MNORMAL, 0, -4, PSTR("WiFly v%s"), wifly_version_string ); // WiFly Versionsanzeige
lcdx_printf_center_P( 3, MNORMAL, 0, -2, PSTR("%S: OK") , strMode ); // "AP-Mode" oder "AdHoc"
lcdx_printf_center_P( 5, MNORMAL, 0, -1, PSTR("%S?") , title ); // "Init WiFly?"
 
ask = _ask( NOYES );
 
if( !ask ) // "Nein"
{
set_Modul_On( USB );
return false;
}
}
 
 
//-----------------------------
// Init durchfuehren
//-----------------------------
if( result )
{
ShowTitle_P( title, true );
result = wifly_init_perform( wiflymode );
}
 
set_Modul_On( USB );
 
if( !result )
PKT_Message_P( PSTR("Init FAIL!"), true, 3000, true, true ); // max. 30 Sekunden anzeigen
else
PKT_Message_P( PSTR("Init OK!"), false, 3000, true, true ); // max. 30 Sekunden anzeigen
 
clear_key_all();
return( result );
}
 
 
 
//--------------------------------------------------------------
// PARAMETER:
// wiflymode: WIFLY_APMODE = Firmware wifly7-441.img
// WIFLY_ADHOC = Firmware wifly7-2383.img
//--------------------------------------------------------------
uint8_t wifly_update( uint8_t wiflymode )
{
int8_t result = 1; // 1 = true
uint8_t ask = false;
char *title = (char *)PSTR("Update WiFly");
const char *pStr;
 
 
ShowTitle_P( title, true );
 
result = find_WiFly();
 
if( result < 0 ) // Abbruch durch Benutzer?
{
clear_key_all();
return result;
}
 
 
if( result ) result = cmd_GetVersion();
 
//-----------------------------
// Benutzer fragen
//-----------------------------
if( result )
{
if( wiflymode == WIFLY_ADHOC ) pStr = WIFLY_VERSION_ADHOC;
else pStr = WIFLY_VERSION_APMODE;
 
ShowTitle_P( title, true );
//lcdx_printf_at_P( 0, 1, MINVERS, 0,0, PSTR("%d"), wifly_version );
lcdx_printf_center_P( 2, MNORMAL, 0, -4, PSTR("%S: v%s"), strGet(STR_VON), wifly_version_string );
lcdx_printf_center_P( 3, MNORMAL, 0, -2, PSTR("%S: v%S"), strGet(STR_NACH), pStr );
lcdx_printf_center_P( 5, MNORMAL, 0, -1, PSTR("%S?"), title );
 
ask = _ask( NOYES );
 
if( !ask ) // "Nein"
{
set_Modul_On( USB );
return false;
}
}
 
 
//-----------------------------
// Update durchfuehren
//-----------------------------
if( result )
{
ShowTitle_P( title, true );
progress_begin( 16 );
}
 
//----------------------------
// 1. Reset
//----------------------------
#ifndef DEBUG_WIFLY
if( result ) MsgCenter_P( 2, PSTR("Reset"), MNORMAL, 0 );
#endif
if( result ) result = cmd_Reset();
if( result ) result = cmd_Reboot();
if( result ) result = find_WiFly();
 
//----------------------------
// 2. mit Heimnetz verbinden
//----------------------------
#ifndef DEBUG_WIFLY
if( result ) MsgCenter_P( 2, PSTR("verbinde Heimnetz"), MNORMAL, 0 );
#endif
if( result ) result = cmd_Set( PSTR("set ip dhcp 1") );
if( result ) result = cmd_SetStr( PSTR("set wlan phrase"), Config.Wlan_HomePassword );
if( result ) result = cmd_Set( PSTR("set wlan channel 0") );
 
if( result ) result = cmd_Join( Config.Wlan_HomeSSID );
 
//----------------------------
// 3. FTP Download & Update
//----------------------------
#ifndef DEBUG_WIFLY
if( result ) MsgCenter_P( 2, PSTR("FTP Update"), MNORMAL, 0 );
#endif
if( result ) result = cmd_Set( PSTR("set ftp address 198.175.253.161") );
if( result ) result = cmd_Set( PSTR("set ftp dir public") );
if( result ) result = cmd_Set( PSTR("set ftp user roving") );
if( result ) result = cmd_Set( PSTR("set ftp pass Pass123") );
if( result ) result = cmd_Set( PSTR("set ftp timeout 800") );
 
//if( result ) result = cmd_Set( PSTR("del config") );
 
if( result )
{
//-----
// das kann einiges gekuerzt werden wenn das denn zuverlaessig laufen wuerde...
//
// hier wird auf v4.40 geprueft da laut Refrenz-Manual erst seit dieser Version
// "cupdate" unterstuetzt wird. Bei einem Downgraden von v4.4 auf eine aeltere
// Version ist ein clean des Dateisystems ('c') erforderlich da sonst das WiFly
// nur via Hardware-Taster an GPIO9 wiedre zum Leben erweckt werden kann.
//
// Anmerkung: evtl. wuer auch ein "del config" reichen - das ist aber nicht
// hinreichend getestet
//-----
if( wifly_version >= 440 )
{
if( wiflymode == WIFLY_ADHOC )
result = cmdsend( PSTR("ftp cupdate wifly7-2383.img"), 0, PSTR("UPDATE OK"), false );
else
result = cmdsend( PSTR("ftp cupdate wifly7-441.img") , 0, PSTR("UPDATE OK"), false );
}
else
{
if( wiflymode == WIFLY_ADHOC )
result = cmdsend( PSTR("ftp update wifly7-2383.img"), 0, PSTR("UPDATE OK"), false );
else
result = cmdsend( PSTR("ftp update wifly7-441.img") , 0, PSTR("UPDATE OK"), false );
}
}
 
if( result ) result = cmd_Reset();
if( result ) { timer2 = 50; while(timer2); };
 
 
/*
//-----
// Baustelle / Experimente bzgl. FTP-Update
//-----
//debug_message("FTP END");
//debug_message("RESET");
//if( result ) result = cmd_Reboot();
if( result ) { timer2 = 100; while(timer2); };
if( result ) { timer2 = 200; while(timer2); };
debug_message("FINDPR");
uart1_putc('\r');
if( result ) result = find_Prompt();
if( result ) debug_message("FINDPR END: 1");
else debug_message("FINDPR END: 0");
*/
 
 
//progress_end( true ); // Progress abschalten & warten
progress_end( false ); // Progress abschalten
 
 
//----------------------------
// 4. Init
//----------------------------
/*
if( result ) { timer2 = 10; while(timer2); };
if( result ) set_Modul_On( USB );
if( result ) { timer2 = 10; while(timer2); };
if( result ) ShowTitle_P( title, true );
if( result ) result = result = find_WiFly();
if( result ) result = wifly_init_perform( wiflymode );
*/
 
set_Modul_On( USB );
 
 
if( !result )
PKT_Message_P( PSTR("Update FAIL!"), true, 3000, true, true ); // max. 30 Sekunden anzeigen
else
PKT_Message_P( PSTR("Update OK!"), false, 3000, true, true ); // max. 30 Sekunden anzeigen
 
 
clear_key_all();
return result;
}
 
 
 
//--------------------------------------------------------------
//--------------------------------------------------------------
uint8_t wifly_reset( void )
{
int8_t result = 1; // 1 = true
uint8_t ask = false;
char *title = (char *)PSTR("Reset WiFly");
 
ShowTitle_P( title, true );
 
result = find_WiFly();
 
if( result < 0 ) // Abbruch durch Benutzer?
{
clear_key_all();
return result;
}
 
 
//-----------------------------
// Benutzer fragen
//-----------------------------
if( result )
{
ShowTitle_P( title, true );
lcdx_printf_center_P( 5, MNORMAL, 0, -1, PSTR("%S?"), title );
 
ask = _ask( NOYES );
 
if( !ask ) // "Nein"
{
set_Modul_On( USB );
return false;
}
}
 
ShowTitle_P( title, true );
 
if( result ) progress_begin( 2 );
 
if( result ) result = cmd_Reset();
if( result ) result = cmd_Reboot();
 
progress_end( false ); // Progress abschalten
 
set_Modul_On( USB );
 
if( result )
{
//PKT_Message_P( *text, error, timeout, beep, clearscreen )
PKT_Message_P( PSTR("Reset OK!"), false, 3000, true, true ); // max. 30 Sekunden anzeigen
}
else
{
PKT_Message_P( PSTR("Reset FAIL!"), true, 3000, true, true ); // max. 30 Sekunden anzeigen
}
 
clear_key_all();
return result;
}
 
 
 
//#############################################################################
//# TEST / DEBUG
//#############################################################################
 
 
//--------------------------------------------------------------
// nur zum testen!
//--------------------------------------------------------------
uint8_t wifly_test( void )
{
uint8_t result = true;
 
return result;
}
 
#endif
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/wifly/PKT_WiFlyHQ.h
0,0 → 1,89
/*-
* Copyright (c) 2012,2013 Darran Hunt (darran [at] hunt dot net dot nz)
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED ``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 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.
*/
 
/* Release history
*
* Version Date Description
* 0.1 25-Mar-2012 First release.
* 0.2 09-Apr-2012 Added features to support http servers.
* - added an httpserver.ino example.
* - added sendChunk() and sendChunkln() to send chunked HTTP bodies.
* - added terminal() method for simple terminal access via debug stream
* - replaced getFreeMemory() with simpler version that works with 0 bytes
* - turned peek buffer into a circular buffer to fix bug with detecting
* *CLOS* and *OPEN* after a partial match.
* - Added new TCP connection detection via *OPEN* match from available().
* isConnected() can now be polled until a client connects.
* - made the match() function public, handy for matching text in a stream.
* - Added a getProtocol() function to get current set of protocols.
* 0.3 21-Apr-2012 Added createAdhocNetwork() to create an Ad Hoc WiFi network.
* Optimised the setopt() and getopt() function so they handle
* integer conversions and refactored all of the set and get functions.
* Added a multMatch_P() function to match serial data against multiple
* progmem strings.
* Added failure detection to the join() function to quickly detect
* a failure rather than relying on a timeout.
* Added setJoin() and getJoin() function for access to the wlan join parameter.
* Refactored getres() to use the new multiMatch_P() function.
*
*/
 
/**
* @mainpage WiFlyHQ WiFly RN-XV Arduino library
*
* This library provides functions for setting up and managing the WiFly module,
* sending UDP packets, opening TCP connections and sending and receiving data
* over the TCP connection.
*
* @author Harlequin-Tech
*/
 
//############################################################################
//# HISTORY PKT_WiFlyHQ.h
//#
//# 13.04.2014 OG
//# - FAST KOMPLETT NEUER CODE
//#
//# 02.04.2014 OG
//# - add: Versionshistorie ergaenzt
//###########################################################################
 
 
#ifndef _WIFLYHQ_H_
#define _WIFLYHQ_H_
 
// Todo: Strings verfuegbar machen für connect.c
//extern const char WIFLY_IP_ADDRESS[];
//extern const char WIFLY_IP_PORT[];
 
 
uint8_t wifly_update( uint8_t wiflymode );
uint8_t wifly_reset(void);
uint8_t wifly_version_show( void );
uint8_t wifly_init( uint8_t wiflymode );
 
uint8_t wifly_test( void );
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/wifly/wifly_setup.c
0,0 → 1,424
/*
* wifly_setup.c
*
* Created on: 02.07.2013
* Author: cebra
*/
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
//############################################################################
//# HISTORY wifly_setup.c
//#
//# 08.06.2014 OG
//# - chg: Setup_WiFly() - Tipptext fuer Module-Installed ergaenzt
//#
//# 04.06.2014 OG
//# - chg: Menuetext angepasst; Menue-Separator hinzugefuegt
//#
//# 31.05.2014 OG
//# - chg: Setup's auf geaendertes Edit_String() umgestellt (Param 'Text' entfernt)
//#
//# 28.05.2014 OG
//# - chg: Setup's auf das neue Edit_generic() umgestellt
//#
//# 13.04.2014 OG
//# - ggf. Probleme beim Downgrade des WiFly auf v2.38 -> deaktiviert
//# - FAST KOMPLETT NEUER CODE
//#
//# 03.04.2014 OG
//# - add: #include "../pkt/pkt.h"
//#
//# 30.03.2014 OG
//# - chg: Text von WL_INSTALLED geaendert von "Modul eingebaut?" auf "Modul vorhanden?"
//# -> das Modul wird aufgesteckt und nicht eingebaut...
//# - chg: ein paar englische Texte geaendert
//# - chg: Sprache Hollaendisch vollstaendig entfernt
//# - chg: MenuCtrl_PushML_P() umgestellt auf MenuCtrl_PushML2_P()
//#
//# 11.03.2014 SH
//# - add: neue Menüpunkte Reset, Version und Update
//# - chg: Menüpunkt Passwort wurde wieder aktiviert
//# - chg: beim Menüpunkt Kanal fängt die Auswahl jetzt bei 0 an (Modul sucht sich automatisch den besten Kanal)
//#
//# 12.02.2014 OG
//# - chg: Setup_WiFly() Auskommentiert: "unused variable 'z'"
//# - chg: Setup_WiFly() Auskommentiert: "unused variable 'i'"
//#
//# 02.07.2013 cebra
//# - new: wifly_setup(): Setup für WiFly WLAN-Modul
//###########################################################################
 
 
#include "../cpu.h"
#include <avr/io.h>
#include <avr/interrupt.h>
//#include <avr/pgmspace.h>
//#include <string.h>
//#include <util/delay.h>
//#include <string.h>
 
#include <avr/pgmspace.h>
#include <stdbool.h>
#include <stdlib.h>
#include <stdarg.h>
#include <util/delay.h>
#include <inttypes.h>
#include <string.h>
 
#include "../main.h"
#include "../messages.h"
#include "../lcd/lcd.h"
#include "../pkt/pkt.h"
#include "../utils/menuctrl.h"
#include "../utils/xutils.h"
#include "../eeprom/eeprom.h"
#include "../uart/uart1.h"
#include "../setup/setup.h"
#include "../wifly/PKT_WiFlyHQ.h"
#include "wifly_setup.h"
 
 
#ifdef USE_WLAN
 
 
//char buffer[20]; // fuer Versionsabfrage
 
 
 
//-----------------------------
// Setup_WiFly() (WLAN)
//-----------------------------
#define WL_INSTALLED 1
#define WL_SSID 2
#define WL_PASSWORD 3
#define WL_CHANNEL 4
#define WL_INIT 5
#define WL_RESET 6
#define WL_VERSION 7
#define WL_UPDATE 8
#define WL_PCCONFIG 9
#define WL_WPA 10
 
#define WL_HOMESSID 11
#define WL_HOMEPASSWORD 12
#define WL_TEST 99
 
 
static const char WL_INSTALLED_de[] PROGMEM = "WiFly Modus";
static const char WL_INSTALLED_en[] PROGMEM = "WiFly mode";
 
static const char WL_SSID_de[] PROGMEM = "SSID";
#define WL_SSID_en WL_SSID_de
 
static const char WL_PASSWORD_de[] PROGMEM = "Passwort";
static const char WL_PASSWORD_en[] PROGMEM = "Password";
 
static const char WL_HOMESSID_de[] PROGMEM = "Home SSID";
#define WL_HOMESSID_en WL_HOMESSID_de
 
static const char WL_HOMEPASSWORD_de[] PROGMEM = "Home Passwort";
static const char WL_HOMEPASSWORD_en[] PROGMEM = "Home Password";
 
static const char WL_CHANNEL_de[] PROGMEM = "Kanal";
static const char WL_CHANNEL_en[] PROGMEM = "Channel";
 
static const char WL_VERSION_de[] PROGMEM = "zeige Version";
static const char WL_VERSION_en[] PROGMEM = "show version";
 
static const char WL_UPDATE_de[] PROGMEM = "Update";
#define WL_UPDATE_en WL_UPDATE_de
 
static const char WL_PCCONFIG_de[] PROGMEM = "WiFly einschalten";
static const char WL_PCCONFIG_en[] PROGMEM = "WiFly power on";
 
static const char WL_WPA_de[] PROGMEM = "Sicherheit";
static const char WL_WPA_en[] PROGMEM = "Security";
 
 
//############################################################################
 
 
//--------------------------------------------------------------
// Setup_WiFly_MenuCreate()
//
// das Menue aendert sich je nachdem ob WiFly ein- oder
// ausgeschaltet ist
//--------------------------------------------------------------
void Setup_WiFly_MenuCreate( void )
{
 
//---------------
// Create
//---------------
MenuCtrl_Create();
 
if( Config.UseWL == WIFLY_APMODE ) MenuCtrl_SetTitle_P( PSTR("WiFly AP-Mode"));
else if( Config.UseWL == WIFLY_ADHOC ) MenuCtrl_SetTitle_P( PSTR("WiFly AdHoc"));
else MenuCtrl_SetTitle_P( PSTR("WiFly"));
 
 
//---------------
// Menuitems
//---------------
MenuCtrl_PushML2_P( WL_INSTALLED , MENU_ITEM, NOFUNC , WL_INSTALLED_de , WL_INSTALLED_en );
 
if( Config.UseWL )
{
//MenuCtrl_Push_P( WL_TEST , MENU_ITEM, NOFUNC , PSTR("TEST") );
 
MenuCtrl_PushML2_P( WL_VERSION , MENU_ITEM, NOFUNC , WL_VERSION_de , WL_VERSION_en );
 
MenuCtrl_PushSeparator();
 
MenuCtrl_PushML2_P( WL_SSID , MENU_ITEM, NOFUNC , WL_SSID_de , WL_SSID_en );
 
if( Config.UseWL == WIFLY_APMODE )
MenuCtrl_PushML2_P( WL_PASSWORD, MENU_ITEM, NOFUNC , WL_PASSWORD_de , WL_PASSWORD_en );
 
MenuCtrl_PushML2_P( WL_CHANNEL , MENU_ITEM, NOFUNC , WL_CHANNEL_de , WL_CHANNEL_en );
 
 
if( Config.UseWL == WIFLY_APMODE )
MenuCtrl_Push_P( WL_INIT , MENU_ITEM, NOFUNC , PSTR("INIT: AP-Mode") );
else
MenuCtrl_Push_P( WL_INIT , MENU_ITEM, NOFUNC , PSTR("INIT: AdHoc") );
 
MenuCtrl_PushSeparator();
 
MenuCtrl_PushML2_P( WL_HOMESSID , MENU_ITEM, NOFUNC , WL_HOMESSID_de , WL_HOMESSID_en );
MenuCtrl_PushML2_P( WL_HOMEPASSWORD, MENU_ITEM, NOFUNC , WL_HOMEPASSWORD_de , WL_HOMEPASSWORD_en );
MenuCtrl_Push_P( WL_UPDATE , MENU_ITEM, NOFUNC , PSTR("UPDATE: WiFly") );
 
MenuCtrl_PushSeparator();
 
MenuCtrl_Push_P( WL_RESET , MENU_ITEM, NOFUNC , PSTR("RESET: WiFly") );
MenuCtrl_PushML2_P( WL_PCCONFIG , MENU_ITEM, &Port_WiFly2Wi , WL_PCCONFIG_de , WL_PCCONFIG_en );
//MenuCtrl_PushML2_P( WL_WPA , MENU_ITEM, NOFUNC , WL_WPA_de , WL_WPA_en );
 
 
if( Config.UseWL == WIFLY_ADHOC )
{
// aktuell kann es zu Problemen kommen wenn das WiFly
// auf v2.38 gedowngraded wird (WiFly nicht mehr ansprechbar)
// -> deshalb: deaktiviert
MenuCtrl_ItemActive( WL_UPDATE, false );
}
}
}
 
 
 
//--------------------------------------------------------------
// Setup_WiFly()
//--------------------------------------------------------------
void Setup_WiFly( void )
{
uint8_t itemid;
uint8_t UseWL;
char string[20];
 
Setup_WiFly_MenuCreate();
 
//---------------
// Control
//---------------
while( true )
{
MenuCtrl_Control( MENUCTRL_EVENT );
 
if( MenuCtrl_GetKey() == KEY_ESC ) break; // ENDE
 
itemid = MenuCtrl_GetItemId(); // welcher Menu-Punkt (ID)
edit = 0;
 
 
//--------------------
// TEST
//--------------------
/*
if( itemid == WL_TEST )
{
lcd_cls();
ShowTitle_P( PSTR("TEST"), true );
wifly_test();
}
*/
 
 
 
//--------------------
// Wlan_INSTALLED
//--------------------
if( itemid == WL_INSTALLED )
{
UseWL = Config.UseWL;
 
Config.UseWL = Edit_generic( Config.UseWL, 0, 2, WlanMode, 1, strGet(STR_EXTSV2MODULE),NULL);
 
if( UseWL != Config.UseWL ) // hat Benutzer Einstellung geaendert?
{
MenuCtrl_Destroy(); // Menue aendern wegen wechsel Wlan vorhanden / nicht vorhanden
Setup_WiFly_MenuCreate();
continue;
}
}
 
 
//--------------------
// WL_VERSION
//--------------------
if( itemid == WL_VERSION )
{
wifly_version_show();
}
 
 
//--------------------
// WL_SSID
//--------------------
if( itemid == WL_SSID )
{
strncpyfill( string, Config.Wlan_SSID, wlan_ssid_length+1 ); // wlan_ssid_length
Edit_String( string, wlan_ssid_length , EDIT_SSID );
 
if( edit == 1 )
{
strrtrim( EditString ); // Leerzeichen rechts entfernen
strncpy( Config.Wlan_SSID, EditString, wlan_ssid_length+1 );
}
}
 
 
//--------------------
// WL_PASSWORD
//--------------------
if( itemid == WL_PASSWORD)
{
strncpyfill( string, Config.Wlan_Password, wlan_password_length+1 ); //
Edit_String( string, wlan_password_length , EDIT_WL_PASSWORD );
 
if( edit == 1 )
{
strrtrim( EditString ); // Leerzeichen rechts entfernen
strncpy( Config.Wlan_Password, EditString, wlan_password_length+1 );
}
}
 
 
//--------------------
// WL_HOMESSID
//--------------------
if( itemid == WL_HOMESSID )
{
strncpyfill( string, Config.Wlan_HomeSSID, wlan_ssid_length+1 ); // wlan_ssid_length
Edit_String( string, wlan_ssid_length , EDIT_SSID );
 
if( edit == 1 )
{
strrtrim( EditString); // Leerzeichen rechts entfernen
strncpy( Config.Wlan_HomeSSID, EditString, wlan_ssid_length+1 );
}
}
 
 
//--------------------
// WL_HOMEPASSWORD
//--------------------
if( itemid == WL_HOMEPASSWORD)
{
strncpyfill( string, Config.Wlan_HomePassword, wlan_password_length+1 ); //
Edit_String( string, wlan_password_length , EDIT_WL_PASSWORD );
 
if( edit == 1 )
{
strrtrim( EditString ); // Leerzeichen rechts entfernen
strncpy( Config.Wlan_HomePassword, EditString, wlan_password_length+1 );
}
}
 
 
 
//--------------------
// WL_CHANNEL
//--------------------
if( itemid == WL_CHANNEL )
{
Config.Wlan_Channel = Edit_generic( Config.Wlan_Channel, 0,13,Show_uint3,1 ,NULL,NULL);
}
 
 
//--------------------
// WL_INIT
//--------------------
if( itemid == WL_INIT )
{
wifly_init( Config.UseWL ); // Config.UseWL = WIFLY_APMODE oder WIFLY_ADHOC
}
 
 
//--------------------
// Wlan_RESET
//--------------------
if( itemid == WL_RESET )
{
wifly_reset();
}
 
 
//--------------------
// Wlan_UPDATE
//--------------------
if( itemid == WL_UPDATE )
{
wifly_update( Config.UseWL ); // Config.UseWL = WIFLY_APMODE oder WIFLY_ADHOC
}
 
//--------------------
// Wlan_WPA
//--------------------
//if( itemid == WL_WPA )
//{
// Config.Wlan_WPA = Edit_generic(Config.Wlan_WPA,0,1,WL3,WlanSecurity,1);
//}
 
} // end: while( true )
 
//---------------
// Destroy
//---------------
MenuCtrl_Destroy();
 
} // end: Setup_WiFly()
 
#endif
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/wifly/wifly_setup.h
0,0 → 1,18
/*
* wifly_setup.h
*
* Created on: 02.07.2013
* Author: cebra
*/
 
#ifndef WIFLY_SETUP_H_
#define WIFLY_SETUP_H_
 
 
#define WIFLY_APMODE 1
#define WIFLY_ADHOC 2
 
 
void Setup_WiFly( void );
 
#endif /* WIFLY_SETUP_H_ */
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2/wifly
Property changes:
Added: svn:ignore
+_old_source
+
+_doc
/Transportables_Koptertool/PKT/branches/branch_FollowMeStep2
Property changes:
Added: svn:ignore
+_doc
+
+Koptertool3.9
+
+nmealib
+
+Resourcen
+
+TinyGPS
+
+LICENSE.TXT
+
+Source_PKT384e_TEST!.zip
+
+Source_PKT384a.zip
+
+mkparameters.c
+
+DIFF_PKT384a.txt
+
+DIFF_PKT384e.txt
+
+DIFF_PKT384d.txt
+
+.refactorings
+
+.settings
+
+.directory
+
+.cproject
+
+.project