Subversion Repositories FlightCtrl

Compare Revisions

Ignore whitespace Rev 2346 → Rev 2347

/beta/Code Redesign killagreg/eeprom.c
72,6 → 72,7
#include "main.h"
#include "fc.h"
#include "twimaster.h"
#include "libfc.h"
 
paramset_t ParamSet;
MixerTable_t Mixer;
144,16 → 145,16
 
ParamSet.Config0 = CFG0_AXIS_COUPLING_ACTIVE | CFG0_COMPASS_ACTIVE | CFG0_GPS_ACTIVE | CFG0_HEIGHT_SWITCH;//CFG0_HEIGHT_CONTROL | CFG0_COMPASS_FIX;
ParamSet.Config1 = 0;
ParamSet.Config2 = /*CFG2_HEIGHT_LIMIT |*/ CFG2_VARIO_BEEP;//|CFG2_SENSITIVE_RC;
ParamSet.Config2 = CFG2_GPS_AID | CFG2_VARIO_BEEP;
ParamSet.HeightMinGas = 30;
ParamSet.MaxHeight = 255;
ParamSet.HeightP = 15;
ParamSet.HeightSwitch = 255;
ParamSet.HeightP = 15; //Wert 0-50: (15 -> ca. +/- 5m/sek bei Stick-Voll-Ausschlag)
ParamSet.HeightD = 30;
ParamSet.Height_ACC_Effect = 0;
ParamSet.Height_HoverBand = 8;
ParamSet.Height_GPS_Z = 64;
ParamSet.Height_StickNeutralPoint = 0; // Value : 0-250 (0 = Hoover-Estimation)
ParamSet.Height_Gain = 20;
ParamSet.Height_Gain = 15; // Value : 0-50 (15 -> ca. +/- 5m/sek bei Stick-Voll-Ausschlag)
ParamSet.GasMin = 8;
ParamSet.GasMax = 230;
ParamSet.CompassYawEffect = 64;
199,20 → 200,24
ParamSet.NaviGpsI = 90;
ParamSet.NaviGpsD = 90;
ParamSet.NaviGpsPLimit = 75;
ParamSet.NaviGpsILimit = 75;
ParamSet.NaviGpsILimit = 85;
ParamSet.NaviGpsDLimit = 75;
ParamSet.NaviGpsACC = 0;
ParamSet.NaviGpsMinSat = 6;
ParamSet.NaviStickThreshold = 8;
ParamSet.NaviWindCorrection = 90;
ParamSet.NaviSpeedCompensation = 30;
ParamSet.NaviAccCompensation = 42;
ParamSet.NaviOperatingRadius = 245;
ParamSet.NaviAngleLimitation = 100;
ParamSet.NaviPHLoginTime = 2;
ParamSet.NaviAngleLimitation = 140;
ParamSet.NaviPHLoginTime = 5;
ParamSet.ExternalControl = 0;
ParamSet.OrientationAngle = 0;
ParamSet.OrientationModeControl = 0;
ParamSet.CareFreeModeControl = 0;
ParamSet.MotorSafetySwitch = 0;
ParamSet.MotorSmooth = 0;
ParamSet.ComingHomeAltitude = 0; // 0 = don't change
ParamSet.FailSafeTime = 0; // 0 = off
ParamSet.MaxAltitude = 150; // 0 = off
}
 
/***************************************************/
351,6 → 356,9
// read paramset from eeprom
eeprom_read_block((void *) &ParamSet, (void*)(EEPROM_ADR_PARAMSET + PARAMSET_STRUCT_LEN * (setnumber - 1)), PARAMSET_STRUCT_LEN);
LED_Init();
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
LIBFC_HoTT_Clear();
#endif
return 1;
}
 
367,6 → 375,8
if(setnumber > 5) setnumber = 5;
if(setnumber < 1) return 0;
 
LIBFC_CheckSettings();
 
// update checksum
ParamSet.crc = RAM_Checksum((uint8_t*)(&ParamSet), sizeof(ParamSet)-1);
 
383,6 → 393,9
// update active settings number
SetActiveParamSet(setnumber);
LED_Init();
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
LIBFC_HoTT_Clear();
#endif
return 1;
}
// wrong revision
528,7 → 541,6
if(EEPARAM_REVISION != GetParamByte(PID_EE_REVISION) )
{
ee_default = 1; // software update or forced by mktool
SetParamByte(PID_EE_REVISION, EEPARAM_REVISION);
}
 
 
585,12 → 597,14
printf("\n\rUsing Parameter Set %d", i);
 
// load mixer table
if(ee_default || !MixerTable_ReadFromEEProm() )
if(GetParamByte(PID_EE_REVISION) == 0xFF || !MixerTable_ReadFromEEProm() )
{
printf("\n\rGenerating default Mixer Table");
MixerTable_Default(); // Quadro
MixerTable_WriteToEEProm();
}
if(ee_default) SetParamByte(PID_EE_REVISION, EEPARAM_REVISION);
 
// determine motornumber
RequiredMotors = 0;
for(i = 0; i < 16; i++)
/beta/Code Redesign killagreg/eeprom.h
5,7 → 5,7
#include "twimaster.h"
 
 
#define EEPARAM_REVISION 85 // is count up, if paramater stucture has changed (compatibility)
#define EEPARAM_REVISION 87 // is count up, if paramater stucture has changed (compatibility)
#define EEMIXER_REVISION 1 // is count up, if mixer stucture has changed (compatibility)
#define EEBLCONFIG_REVISON 35 // is count up, if blconfig stucture has changed (compatibility to BLs!)
 
57,10 → 57,10
#define CFG1_LOOP_DOWN 0x02
#define CFG1_LOOP_LEFT 0x04
#define CFG1_LOOP_RIGHT 0x08
#define CFG1_MOTOR_BLINK 0x10
#define CFG1_MOTOR_BLINK1 0x10
#define CFG1_MOTOR_OFF_LED1 0x20
#define CFG1_MOTOR_OFF_LED2 0x40
#define CFG1_RES4 0x80
#define CFG1_MOTOR_BLINK2 0x80
 
// bit mask for ParamSet.Config2
#define CFG2_HEIGHT_LIMIT 0x01
67,9 → 67,9
#define CFG2_VARIO_BEEP 0x02
#define CFG2_SENSITIVE_RC 0x04
#define CFG2_3V3_REFERENCE 0x08
#define CFG2_RES2 0x10
#define CFG2_RES3 0x20
#define CFG2_RES4 0x40
#define CFG2_NO_RCOFF_BEEPING 0x10
#define CFG2_GPS_AID 0x20
#define CFG2_LEARNABLE_CAREFREE 0x40
#define CFG2_RES5 0x80
 
// defines for the receiver selection
115,7 → 115,7
uint8_t Config0; // see upper defines for bitcoding
uint8_t HeightMinGas; // Value : 0-100
uint8_t HeightD; // Value : 0-247
uint8_t MaxHeight; // Value : 0-32
uint8_t HeightSwitch; // Value : 0-247
uint8_t HeightP; // Value : 0-32
uint8_t Height_Gain; // Value : 0-50
uint8_t Height_ACC_Effect; // Value : 0-247
194,7 → 194,7
uint8_t NaviGpsMinSat; // number of sattelites neccesary for GPS functions
uint8_t NaviStickThreshold; // activation threshild for detection of manual stick movements
uint8_t NaviWindCorrection; // streng of wind course correction
uint8_t NaviSpeedCompensation; // D gain fefore position hold login
uint8_t NaviAccCompensation; // D gain before position hold login
uint8_t NaviOperatingRadius; // Radius limit in m around start position for GPS flights
uint8_t NaviAngleLimitation; // limitation of attitude angle controlled by the gps algorithm
uint8_t NaviPHLoginTime; // position hold logintimeout
202,8 → 202,12
uint8_t ExternalControl; // for serial control
//---CareFree---------------------------------------------
uint8_t OrientationAngle; // Where is the front-direction in steps of 15°?
uint8_t OrientationModeControl; // switch for CareFre
uint8_t CareFreeModeControl; // switch for CareFre
uint8_t MotorSafetySwitch;
uint8_t MotorSmooth; // motor smoothing
uint8_t ComingHomeAltitude;
uint8_t FailSafeTime;
uint8_t MaxAltitude;
// config
uint8_t Config1; // see upper defines for bitcoding
uint8_t ServoCompInvert; // Bitfield: 0x01 = Nick invert, 0x02 = Roll invert // WICHTIG!!! am Ende lassen
/beta/Code Redesign killagreg/fc.c
120,7 → 120,7
// compass course
int16_t CompassHeading = -1; // negative angle indicates invalid data.
int16_t CompassCourse = -1; // compass course setpoint
int16_t CompassOffCourse = 0;
//int16_t CompassOffCourse = 0;
uint8_t CompassCalState = 0;
int8_t CalculateCompassTimer = 100;
uint8_t CompassFusion = 32;
129,12 → 129,12
uint16_t BadCompassHeading = 50;
uint8_t FunnelCourse = 0;
int32_t YawGyroHeading; // Yaw Gyro Integral supported by compass
int16_t YawGyroHeadingDeg;
int16_t YawGyroDrift;
 
 
int16_t NaviAccNick = 0, NaviAccRoll = 0, NaviCntAcc = 0;
 
 
// MK flags
uint16_t ModelIsFlying = 0;
 
165,6 → 165,9
 
// stick values derived by rc channels readings
int16_t StickNick = 0, StickRoll = 0, StickYaw = 0, StickGas = 0;
// height control hover gas value;
int16_t StickGasHover = RC_GAS_OFFSET;
// gps control signals
int16_t GPSStickNick = 0, GPSStickRoll = 0;
 
int16_t MaxStickNick = 0, MaxStickRoll = 0;
173,6 → 176,8
int16_t ExternStickNick = 0, ExternStickRoll = 0, ExternStickYaw = 0, ExternHeightValue = -20;
 
int32_t SetPointHeight = 0;
int16_t AltitudeSetpointTrimming = 0;
int8_t WaypointTrimming = 0;
int16_t ControlHeading = 0; // roll/nick rotation angle in steps of 2°
 
int16_t AttitudeCorrectionRoll = 0, AttitudeCorrectionNick = 0;
181,7 → 186,7
uint8_t LoopingLeft = 0, LoopingRight = 0, LoopingDown = 0, LoopingTop = 0;
 
 
fc_param_t FCParam = {48,251,16,58,64,64,8,150,150,150,150,2,10,0,0,0,0,0,0,0,0,100,100,70,90,65,64,100,0,0,0};
fc_param_t FCParam = {48,251,16,58,64,64,8,150,150,150,150,2,10,0,0,0,0,0,0,0,0,100,100,70,90,65,64,100,0,0,0,0,0,0};
 
 
 
200,7 → 205,7
DebugOut.Analog[8] = CompassHeading;
DebugOut.Analog[9] = UBat;
DebugOut.Analog[10] = RC_Quality;
DebugOut.Analog[11] = YawGyroHeading / GYRO_DEG_FACTOR;
DebugOut.Analog[11] = YawGyroHeadingDeg;
DebugOut.Analog[12] = Motor[0].SetPoint;
DebugOut.Analog[13] = Motor[1].SetPoint;
DebugOut.Analog[14] = Motor[2].SetPoint;
244,7 → 249,7
uint8_t i;
int32_t Sum_1, Sum_2 = 0, Sum_3;
 
//Servo_Off(); // disable servo output
Servo_Off(); // disable servo output
 
UART_VersionInfo.HardwareError[0] = 0;
 
368,8 → 373,8
 
ExternHeightValue = 0;
 
GPSStickNick = 0;
GPSStickRoll = 0;
//GPSStickNick = 0;
//GPSStickRoll = 0;
 
FC_StatusFlags |= FC_STATUS_CALIBRATE;
 
382,7 → 387,7
Poti[i] = PPM_in[ParamSet.ChannelAssignment[CH_POTI1+i]] + RC_POTI_OFFSET;
}
 
//Servo_On(); //enable servo output
Servo_On(); //enable servo output
RC_Quality = 100;
 
if((BiasHiResGyroNick < 150 * 16) || (BiasHiResGyroNick > 850 * 16)) { UART_VersionInfo.HardwareError[0] |= FC_ERROR0_GYRO_NICK; };
391,6 → 396,10
if((AdBiasAccNick < 300 * 2) || (AdBiasAccNick > 750 * 2)) { UART_VersionInfo.HardwareError[0] |= FC_ERROR0_ACC_NICK; };
if((AdBiasAccRoll < 300 * 2) || (AdBiasAccRoll > 750 * 2)) { UART_VersionInfo.HardwareError[0] |= FC_ERROR0_ACC_ROLL; };
if((AdBiasAccTop < 512) || (AdBiasAccTop > 850 )) { UART_VersionInfo.HardwareError[0] |= FC_ERROR0_ACC_TOP; };
 
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
LIBFC_HoTT_Clear();
#endif
}
 
/************************************************************************/
477,7 → 486,7
 
 
// Coupling fraction
if(! LoopingNick && !LoopingRoll && (ParamSet.Config0 & CFG0_AXIS_COUPLING_ACTIVE))
if(! LoopingNick && !LoopingRoll && (FCParam.Config0 & CFG0_AXIS_COUPLING_ACTIVE))
{
tmp13 = (FilterGyroRoll * AngleNick) / 2048L;
tmp13 *= FCParam.AxisCoupling2;
583,7 → 592,7
else TrimRoll -= ((int32_t)abs(CouplingNickRoll) * FCParam.AxisCouplingYawCorrection) / 64L;
 
// increase the nick/roll rates virtually from the threshold of 245 to slow down higher rotation rates
if((ParamSet.Config0 & CFG0_ROTARY_RATE_LIMITER) && ! LoopingNick && !LoopingRoll)
if((FCParam.Config0 & CFG0_ROTARY_RATE_LIMITER) && ! LoopingNick && !LoopingRoll)
{
if(FilterGyroNick > 256) GyroNick += 1 * (FilterGyroNick - 256);
else if(FilterGyroNick < -256) GyroNick += 1 * (FilterGyroNick + 256);
651,13 → 660,15
#define POTI_MAX 255
for(i=0; i<8; i++)
{
int tmp;
tmp = PPM_in[ParamSet.ChannelAssignment[CH_POTI1+i]] + RC_POTI_OFFSET;
LIMIT_MIN_MAX(tmp, POTI_MIN, POTI_MAX);
if(tmp != Poti[i])
int16_t tmp2;
tmp = ParamSet.ChannelAssignment[CH_POTI1+i];
tmp2 = PPM_in[tmp] + RC_POTI_OFFSET;
LIMIT_MIN_MAX(tmp2, POTI_MIN, POTI_MAX);
if(tmp == 25) Poti[i] = tmp2; // 25 = WaypointEvent channel -> no filter
else if(tmp2 != Poti[i])
{
Poti[i] += (tmp - Poti[i]) / 8;
if(Poti[i] > tmp) Poti[i]--;
Poti[i] += (tmp2 - Poti[i]) / 4;
if(Poti[i] > tmp2) Poti[i]--;
else Poti[i]++;
}
}
666,9 → 677,9
CHK_POTI_MM(FCParam.HeightP,ParamSet.HeightP,0,100);
CHK_POTI_MM(FCParam.GyroP,ParamSet.GyroP,10,255);
CHK_POTI_MM(FCParam.GyroYawP,ParamSet.GyroYawP,10,255);
CHK_POTI_MM(FCParam.J16Timing,ParamSet.J16Timing,1,255);
CHK_POTI_MM(FCParam.J17Timing,ParamSet.J17Timing,1,255);
CHK_POTI(FCParam.MaxHeight,ParamSet.MaxHeight);
CHK_POTI_MM(FCParam.J16Timing,ParamSet.J16Timing,5,255);
CHK_POTI_MM(FCParam.J17Timing,ParamSet.J17Timing,5,255);
CHK_POTI(FCParam.HeightSwitch,ParamSet.HeightSwitch);
CHK_POTI(FCParam.Height_ACC_Effect,ParamSet.Height_ACC_Effect);
CHK_POTI(FCParam.Height_GPS_Z,ParamSet.Height_GPS_Z);
CHK_POTI(FCParam.CompassYawEffect,ParamSet.CompassYawEffect);
695,9 → 706,12
CHK_POTI(FCParam.AxisCouplingYawCorrection,ParamSet.AxisCouplingYawCorrection);
CHK_POTI(FCParam.DynamicStability,ParamSet.DynamicStability);
CHK_POTI(FCParam.ExternalControl,ParamSet.ExternalControl);
CHK_POTI(FCParam.MaxAltitude,ParamSet.MaxAltitude);
FCParam.Config0 = ParamSet.Config0;
FCParam.Config2 = ParamSet.Config2;
Ki = 10300 / ( FCParam.IFactor + 1 );
 
CHK_POTI(tmp,ParamSet.OrientationModeControl);
CHK_POTI(tmp, ParamSet.CareFreeModeControl);
if(tmp > 50) // care free should be set on
{
// check dependencies like valid compass heading
716,9 → 730,6
}
else // everthing ok
{
#ifdef SWITCH_LEARNS_CAREFREE
if(!CareFree) ControlHeading = (((int16_t) ParamSet.OrientationAngle * 15 + CompassHeading) % 360) / 2;
#endif
CareFree = 1;
if(FCParam.AxisCoupling1 < 210) FCParam.AxisCoupling1 += 30;
FC_StatusFlags2 |= FC_STATUS2_CAREFREE;
729,7 → 740,7
{
CareFree = 0;
FC_StatusFlags2 &= ~FC_STATUS2_CAREFREE;
UART_VersionInfo.HardwareError[0] &= ~FC_ERROR0_CAREFREE; // reset error flag
//UART_VersionInfo.HardwareError[0] &= ~FC_ERROR0_CAREFREE; // reset error flag
}
// accoustic signal when CareFree state transition
if(CareFree != CareFreeOld)
738,6 → 749,15
else BeepTime = 200; // has been disabled
CareFreeOld = CareFree; // resync
}
 
// Limit the maximum altitude
if(FCParam.MaxAltitude)
{
if( (SetPointHeight/100) > FCParam.MaxAltitude)
{
SetPointHeight = (int32_t) FCParam.MaxAltitude * 100L;
}
}
}
}
 
788,7 → 808,6
static int16_t MotorValue[MAX_MOTORS];
 
Mean();
GRN_ON;
 
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// RC-signal is bad
886,7 → 905,7
// update active parameter set in eeprom
SetActiveParamSet(setting);
ParamSet_ReadFromEEProm(GetActiveParamSet());
if(ParamSet.Config0 & CFG0_AIRPRESS_SENSOR)
if(FCParam.Config0 & CFG0_AIRPRESS_SENSOR)
{
if((AdAirPressure > AIR_PRESSURE_SEARCH_MAX) || (AdAirPressure < AIR_PRESSURE_SEARCH_MIN)) SearchAirPressureOffset();
}
1003,7 → 1022,7
ReadingIntegralGyroRoll2 = IntegralGyroRoll;
IPartNick = 0;
IPartRoll = 0;
ControlHeading = (((int16_t)ParamSet.OrientationAngle * 15 + CompassHeading) % 360) / 2;
//ControlHeading = (((int16_t)ParamSet.OrientationAngle * 15 + CompassHeading) % 360) / 2;
UpdateCompassCourse = 100; // 2 seconds
}
else
1080,6 → 1099,12
StickRoll = ((cos_h * stick_roll) - (sin_h * stick_nick)) / 8;
}
 
if(NCGPSAidMode) // reduce rc stick effect in that case
{
StickNick /= 2;
StickRoll /= 2;
}
 
StickNick -= GPSStickNick;
StickRoll -= GPSStickRoll;
 
1121,7 → 1146,7
if(StickGas < 0) StickGas = 0;
 
// disable I part of gyro control feedback
if(ParamSet.Config0 & CFG0_HEADING_HOLD) GyroIFactor = 0;
if(FCParam.Config0 & CFG0_HEADING_HOLD) GyroIFactor = 0;
 
// update max stick positions for nick and roll
if(abs(StickNick / STICK_GAIN) > MaxStickNick)
1189,6 → 1214,18
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// in case of emergency landing
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(FC_StatusFlags2 & FC_STATUS2_RC_FAILSAVE_ACTIVE)
{
StickNick = -GPSStickNick;
StickRoll = -GPSStickRoll;
StickYaw = 0;
StickGas = StickGasHover; // set to hover point
FCParam.Config0 &= ~(CFG0_HEADING_HOLD | CFG0_ROTARY_RATE_LIMITER);
FCParam.Config0 |= CFG0_AIRPRESS_SENSOR | CFG0_AXIS_COUPLING_ACTIVE | CFG0_COMPASS_ACTIVE | CFG0_GPS_ACTIVE | CFG0_HEIGHT_SWITCH;
FCParam.Config2 &= ~(CFG2_HEIGHT_LIMIT | CFG2_LEARNABLE_CAREFREE | CFG2_VARIO_BEEP);
FCParam.HeightSwitch = 200; // switch on
}
else
// set all inputs to save values
if(FC_StatusFlags & FC_STATUS_EMERGENCY_LANDING)
{
1239,9 → 1276,9
if( FCParam.KalmanK > 0)
{
// determine the deviation of gyro integral from averaged acceleration sensor
tmp_long1 = (int32_t)(IntegralGyroNick / ParamSet.GyroAccFactor - (int32_t)AccNick);
tmp_long1 = (int32_t)(IntegralGyroNick / ParamSet.GyroAccFactor - (int32_t)(AccNick - FromNaviCtrl.AccErrorN));
tmp_long1 = (tmp_long1 * FCParam.KalmanK) / (32 * 16);
tmp_long2 = (int32_t)(IntegralGyroRoll / ParamSet.GyroAccFactor - (int32_t)AccRoll);
tmp_long2 = (int32_t)(IntegralGyroRoll / ParamSet.GyroAccFactor - (int32_t)(AccRoll - FromNaviCtrl.AccErrorR));
tmp_long2 = (tmp_long2 * FCParam.KalmanK) / (32 * 16);
CompassFusion = FCParam.KalmanK;
if((MaxStickNick > 64) || (MaxStickRoll > 64)) // reduce effect during stick commands
1459,7 → 1496,7
if(abs(StickYaw) > 3 ) // yaw stick is activated
{
//BadCompassHeading = 1000;
if(!(ParamSet.Config0 & CFG0_COMPASS_FIX))
if(!(FCParam.Config0 & CFG0_COMPASS_FIX))
{
UpdateCompassCourse = 50; // one second for login
}
1478,7 → 1515,7
// Compass
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// compass code is used only if compass option is selected
if( (CompassHeading >= 0) && (ParamSet.Config0 & (CFG0_COMPASS_ACTIVE|CFG0_GPS_ACTIVE)))
if( (CompassHeading >= 0) && (FCParam.Config0 & (CFG0_COMPASS_ACTIVE|CFG0_GPS_ACTIVE)))
{
if(CalculateCompassTimer-- == 1)
{
1497,7 → 1534,8
if(v > w) w = v;
correction = w / 4 + 1;
// calculate the deviation of the yaw gyro heading and the compass heading
error = ((540 + CompassHeading - (YawGyroHeading / GYRO_DEG_FACTOR)) % 360) - 180;
YawGyroHeadingDeg = YawGyroHeading / GYRO_DEG_FACTOR;
error = ((540 + CompassHeading - YawGyroHeadingDeg) % 360) - 180;
// log in compass value
if(BadCompassHeading) BadCompassHeading--;
else if(w < 25)
1507,8 → 1545,8
{
if(--UpdateCompassCourse == 0)
{
YawGyroHeading = (int32_t)CompassHeading * GYRO_DEG_FACTOR;
CompassCourse = (int16_t)(YawGyroHeading / GYRO_DEG_FACTOR);
//YawGyroHeading = (int32_t)CompassHeading * GYRO_DEG_FACTOR;
CompassCourse = YawGyroHeadingDeg;
}
}
}
1517,7 → 1555,7
// yawing MK
if(!UpdateCompassCourse)
{
r = ((540 + CompassCourse - (YawGyroHeading / GYRO_DEG_FACTOR)) % 360) - 180;
r = ((540 + CompassCourse - YawGyroHeadingDeg) % 360) - 180;
v = r * (FCParam.CompassYawEffect/2);
CompassYawSetPoint = v / 16;
}
1593,7 → 1631,7
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Airpressure sensor is enabled
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if((ParamSet.Config0 & CFG0_AIRPRESS_SENSOR) && !(LoopingRoll || LoopingNick) )
if((FCParam.Config0 & CFG0_AIRPRESS_SENSOR) && !(LoopingRoll || LoopingNick) )
{
int16_t CosAttitude; // for projection of hoover gas
int16_t HCGas, HeightDeviation = 0;
1602,7 → 1640,7
static int16_t FilterHCGas = 0;
 
static int16_t HeightTrimming = 0; // rate for change of height setpoint
static int8_t WaypointTrimming = 0;
//static int8_t WaypointTrimming = 0;
static uint8_t HCActive = 0;
// the states for the hover gas filter
#define HOVER_GAS_STATE_NONE 0
1612,7 → 1650,7
#define HOVER_GAS_AVERAGE 16384L // 16384 * 2ms = 32.8s averaging
static uint32_t HoverGasFilter = 0; // for averaging of GasMixFraction
 
static int16_t StickGasHover = RC_GAS_OFFSET, HoverGas = 0, HoverGasMin = 0, HoverGasMax = 1023;
static int16_t HoverGas = 0, HoverGasMin = 0, HoverGasMax = 1023;
 
static uint8_t delay = 100;
 
1673,9 → 1711,9
 
 
// if height control is activated by an rc channel
if(ParamSet.Config0 & CFG0_HEIGHT_SWITCH)
if(FCParam.Config0 & CFG0_HEIGHT_SWITCH)
{ // check if parameter is less than activation threshold
if( FCParam.MaxHeight < 50 ) // for 3 or 2-state switch height control is disabled in lowest position
if( FCParam.HeightSwitch < 50 ) // for 3 or 2-state switch height control is disabled in lowest position
{ //height control not active
if(!delay--)
{
1694,7 → 1732,7
{ // the height control is always active and the set point is defined by the parameter
if( !(BaroFlags & (BARO_LIMIT_MIN|BARO_LIMIT_MAX)) )
{
SetPointHeight = ((int16_t) ExternHeightValue + (int16_t) FCParam.MaxHeight) * (int16_t)ParamSet.Height_Gain;
SetPointHeight = ((int16_t) ExternHeightValue + (int16_t) FCParam.HeightSwitch) * (int16_t)ParamSet.Height_Gain;
}
HCActive = 1;
}
1706,12 → 1744,13
LIMIT_MAX(CosAttitude, 60); // limit effective attitude angle
CosAttitude = c_cos_8192(CosAttitude); // cos of actual attitude
VarioCharacter = ' ';
AltitudeSetpointTrimming = 0;
 
if(HCActive && !(FC_StatusFlags & FC_STATUS_EMERGENCY_LANDING))
{
FC_StatusFlags2 |= FC_STATUS2_ALTITUDE_CONTROL;
 
if((ParamSet.Config2 & CFG2_HEIGHT_LIMIT) || !(ParamSet.Config0 & CFG0_HEIGHT_SWITCH))
if((FCParam.Config2 & CFG2_HEIGHT_LIMIT) || !(FCParam.Config0 & CFG0_HEIGHT_SWITCH))
{
// Holgers original version
// start of height control algorithm
1721,6 → 1760,7
 
HCGas = GasMixFraction; // take current stick gas as neutral point for the height control
HeightTrimming = 0;
AltitudeSetpointTrimming = 0;
// set undefined state to indicate vario off
FC_StatusFlags |= (FC_STATUS_VARIO_TRIM_UP|FC_STATUS_VARIO_TRIM_DOWN);
}
1740,7 → 1780,8
SetPointHeight = ReadingHeight; // update setpoint to current height
}
FC_StatusFlags |= FC_STATUS_VARIO_TRIM_UP;
HeightTrimming += abs(StickGas - (StickGasHover + HC_STICKTHRESHOLD));
AltitudeSetpointTrimming = abs(StickGas - (StickGasHover + HC_STICKTHRESHOLD));
//HeightTrimming += abs(StickGas - (StickGasHover + HC_STICKTHRESHOLD));
VarioCharacter = '+';
WaypointTrimming= 0;
} // gas stick is below hover point
1752,7 → 1793,8
SetPointHeight = ReadingHeight; // update setpoint to current heigth
}
FC_StatusFlags |= FC_STATUS_VARIO_TRIM_DOWN;
HeightTrimming -= abs(StickGas - (StickGasHover - HC_STICKTHRESHOLD));
AltitudeSetpointTrimming = -abs(StickGas - (StickGasHover - HC_STICKTHRESHOLD));
//HeightTrimming -= abs(StickGas - (StickGasHover - HC_STICKTHRESHOLD));
VarioCharacter = '-';
WaypointTrimming= 0;
}
1762,7 → 1804,8
if(NCAltitudeSpeed && (NCSetPointHeight > SetPointHeight))
{
FC_StatusFlags |= FC_STATUS_VARIO_TRIM_UP;
HeightTrimming += NCAltitudeSpeed;
AltitudeSetpointTrimming = NCAltitudeSpeed;
//HeightTrimming += NCAltitudeSpeed;
WaypointTrimming = 10;
VarioCharacter = '^';
if(FC_StatusFlags & FC_STATUS_VARIO_TRIM_DOWN) // changed from sinking to rising
1774,7 → 1817,8
else if(NCAltitudeSpeed && (NCSetPointHeight < SetPointHeight))
{
FC_StatusFlags |= FC_STATUS_VARIO_TRIM_DOWN;
HeightTrimming -= NCAltitudeSpeed;
AltitudeSetpointTrimming = -NCAltitudeSpeed;
//HeightTrimming -= NCAltitudeSpeed;
WaypointTrimming = -10;
VarioCharacter = 'v';
if(FC_StatusFlags & FC_STATUS_VARIO_TRIM_UP) // changed from rising to sinking
1787,9 → 1831,9
{
FC_StatusFlags &= ~(FC_STATUS_VARIO_TRIM_UP|FC_STATUS_VARIO_TRIM_DOWN);
HeightTrimming = 0;
if(!WaypointTrimming) SetPointHeight = ReadingHeight; // update setpoint to current height
if(!WaypointTrimming) LIMIT_MIN_MAX( SetPointHeight, (ReadingHeight - 128), (ReadingHeight + 128)) // limit setpoint to current height +/- 1m
else WaypointTrimming = 0;
if(ParamSet.Config2 & CFG2_VARIO_BEEP) BeepTime = 500;
if(FCParam.Config2 & CFG2_VARIO_BEEP) BeepTime = 500;
if((HoverGasState == HOVER_GAS_STATE_NONE) && (ReadingHeight > 50) )
{
HoverGasState = HOVER_GAS_STATE_START; // initiate long term filter
1797,7 → 1841,8
}
}
// trim height set point if needed
if(abs(HeightTrimming) > 512)
HeightTrimming += AltitudeSetpointTrimming;
if(abs(HeightTrimming) > 500)
{
if(WaypointTrimming)
{
1806,11 → 1851,12
}
else
{
SetPointHeight += (HeightTrimming * ParamSet.Height_Gain)/((5 * 512) / 2); // move setpoint
if(HeightTrimming > 0) SetPointHeight += ParamSet.Height_Gain / 3;
else SetPointHeight -= ParamSet.Height_Gain / 3;
}
HeightTrimming = 0;
LIMIT_MIN_MAX(SetPointHeight, (ReadingHeight - 1024), (ReadingHeight + 1024)); // max. 10m deviation
if(ParamSet.Config2 & CFG2_VARIO_BEEP) BeepTime = 100;
if(FCParam.Config2 & CFG2_VARIO_BEEP) BeepTime = 100;
//update hover gas stick value when setpoint is shifted
if(!ParamSet.Height_StickNeutralPoint && (NCAltitudeSpeed == 0))
{
1833,7 → 1879,7
 
} //EOF alternative height control
 
if((ReadingHeight > SetPointHeight) || !(ParamSet.Config2 & CFG2_HEIGHT_LIMIT) )
if((ReadingHeight > SetPointHeight) || !(FCParam.Config2 & CFG2_HEIGHT_LIMIT) )
{
int16_t GasReduction = 0;
// from this point the Heigth Control Algorithm is identical for both versions
1858,7 → 1904,7
LIMIT_MIN_MAX(tmp_int1,-64 * STICK_GAIN, 64 * STICK_GAIN);
// reduce d-part when setvalue is changing
if((FC_StatusFlags & (FC_STATUS_VARIO_TRIM_UP|FC_STATUS_VARIO_TRIM_DOWN)) || (abs(HeightDeviation) > 200) ) tmp_int1 /= 4;
else if(ParamSet.Config2 & CFG2_HEIGHT_LIMIT) tmp_int1 /= 8; // reduce d-part in "Deckel" mode
else if(FCParam.Config2 & CFG2_HEIGHT_LIMIT) tmp_int1 /= 8; // reduce d-part in "Deckel" mode
GasReduction += tmp_int1;
} // EOF no baro range expanding
 
1878,7 → 1924,7
HCGas -= GasReduction; // apply gas reduction
 
// limit control output around the hover point
if( (!HeightTrimming) && (HoverGas > 0) ) // height setpoint is not changed and hover gas not zero
if( (!AltitudeSetpointTrimming) && (HoverGas > 0) ) // height setpoint is not changed and hover gas not zero
{
#define DEVIATION_THRESHOLD 60
int16_t tmp;
1916,7 → 1962,7
// limit height control gas pd-control output
LIMIT_MIN_MAX(FilterHCGas, ParamSet.HeightMinGas * STICK_GAIN, (ParamSet.GasMax - 20) * STICK_GAIN);
// set GasMixFraction to HeightControlGasFilter
if(ParamSet.Config2 & CFG2_HEIGHT_LIMIT)
if(FCParam.Config2 & CFG2_HEIGHT_LIMIT)
{ // limit gas to stick position when limiting height control version active
LIMIT_MAX(FilterHCGas, GasMixFraction);
GasMixFraction = FilterHCGas;
1925,7 → 1971,7
{
GasMixFraction = FilterHCGas + (GasMixFraction - HoverGas) / 4;
}
} // EOF if((ReadingHeight > SetPointHeight) || !(ParamSet.Config2 & CFG2_HEIGHT_LIMIT))
} // EOF if((ReadingHeight > SetPointHeight) || !(FCParam.Config2 & CFG2_HEIGHT_LIMIT))
}// EOF height control active
else // HC not active
{
1994,11 → 2040,11
HoverGasFilter = 0;
HoverGas = 0;
} // EOF not flying yet
}// EOF ParamSet.Config0 & CFG0_AIRPRESS_SENSOR
}// EOF FCParam.Config0 & CFG0_AIRPRESS_SENSOR
else
{ // set undefined state to indicate vario off
FC_StatusFlags |= (FC_STATUS_VARIO_TRIM_UP|FC_STATUS_VARIO_TRIM_DOWN);
} // EOF not (ParamSet.Config0 & CFG0_AIRPRESS_SENSOR)
} // EOF not (FCParam.Config0 & CFG0_AIRPRESS_SENSOR)
 
// limit gas to parameter setting
LIMIT_MIN_MAX(GasMixFraction, (int16_t)(ParamSet.GasMin + 10) * STICK_GAIN, (int16_t)(ParamSet.GasMax - 20) * STICK_GAIN);
2006,7 → 2052,7
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// all BL-Ctrl connected?
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(MissingMotor || Capacity.MinOfMaxPWM != 255)
if(MissingMotor || Capacity.MinOfMaxPWM != 255) // wait until all BL-Ctrls are started
{
// if we are in the lift off condition
if( (ModelIsFlying > 1) && (ModelIsFlying < 50) && (GasMixFraction > 0) )
2104,9 → 2150,25
else tmp += ((int32_t)YawMixFraction * Mixer.Motor[i][MIX_YAW] ) / 64L;
 
// Smoothing
if(tmp > MotorValue[i]) tmp = (MotorValue[i] + tmp) / 2;
else tmp = 2 * tmp - MotorValue[i];
//if(tmp > MotorValue[i]) tmp = (MotorValue[i] + tmp) / 2;
//else tmp = 2 * tmp - MotorValue[i];
 
if(tmp > MotorValue[i]) tmp = (MotorValue[i] + tmp) / 2; // increasing motor value
else // decresing motor value
{
if(ParamSet.MotorSmooth == 0)
{
tmp = 2 * tmp - MotorValue[i]; // original motor smoothing
}
else // 1 means tmp = tmp;
if(ParamSet.MotorSmooth > 1)
{
// If >= 2 then allow >= 50% of the intended step down to rapidly reach the intended value.
tmp = tmp + ((MotorValue[i] - tmp)/ParamSet.MotorSmooth);
}
}
 
 
LIMIT_MIN_MAX(tmp, 4 * (int16_t)ParamSet.GasMin, 4 * (int16_t)ParamSet.GasMax);
Motor[i].SetPoint = tmp / 4;
Motor[i].SetPointLowerBits = (tmp % 4)<<1; // remaining bits (3 bits total)
/beta/Code Redesign killagreg/fc.h
27,12 → 27,12
 
// shift for zero centered rc channel data to Poty and thrust values
#define RC_POTI_OFFSET 127
#define RC_GAS_OFFSET 120
#define RC_GAS_OFFSET 127
 
typedef struct
{
uint8_t HeightD;
uint8_t MaxHeight;
uint8_t HeightSwitch;
uint8_t HeightP;
uint8_t Height_ACC_Effect;
uint8_t Height_GPS_Z;
68,6 → 68,9
int8_t KalmanK;
int8_t KalmanMaxDrift;
int8_t KalmanMaxFusion;
uint8_t Config0;
uint8_t Config2;
uint8_t MaxAltitude;
} fc_param_t;
 
extern fc_param_t FCParam;
90,15 → 93,18
// compass navigation
extern int16_t CompassHeading;
extern int16_t CompassCourse;
extern int16_t CompassOffCourse;
//extern int16_t CompassOffCourse;
extern uint8_t CompassCalState;
extern int8_t CalculateCompassTimer;
extern uint8_t CompassFusion;
extern int32_t YawGyroHeading;
extern int16_t YawGyroHeadingDeg;
extern uint8_t CareFree;
 
// height control
extern int32_t SetPointHeight;
extern int16_t AltitudeSetpointTrimming;
extern int8_t WaypointTrimming;
extern int16_t ControlHeading;
 
// accelerations
129,6 → 135,7
extern int16_t StickNick;
extern int16_t StickRoll;
extern int16_t StickYaw;
extern int16_t StickGas;
// current GPS-stick values
extern int16_t GPSStickNick;
extern int16_t GPSStickRoll;
159,6 → 166,7
// FC STATUS FLAGS2
#define FC_STATUS2_CAREFREE 0x01
#define FC_STATUS2_ALTITUDE_CONTROL 0x02
#define FC_STATUS2_RC_FAILSAVE_ACTIVE 0x04
 
#endif //_FC_H
 
/beta/Code Redesign killagreg/hottmenu.c
4,123 → 4,616
#include "analog.h"
#include "spi.h"
#include "fc.h"
#include "rc.h"
#include "eeprom.h"
#include "capacity.h"
#include "hottmenu.h"
 
#define HoTT_printfxy(x,y,format, args...) { LIBFC_HoTT_SetPos(y * 21 + x); _printf_P(&LIBFC_HoTT_Putchar, PSTR(format) , ## args);}
#define HoTT_printf(format, args...) { _printf_P(&LIBFC_HoTT_Putchar, PSTR(format) , ## args);}
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
 
#define HoTT_printfxy_INV(x,y,format, args...) { LIBFC_HoTT_SetPos(y * 21 + x); _printf_P(&LIBFC_HoTT_Putchar_INV, PSTR(format) , ## args);}
#define HoTT_printf_INV(format, args...) { _printf_P(&LIBFC_HoTT_Putchar_INV, PSTR(format) , ## args);}
 
#define HoTT_printf(format, args...) { _printf_P(&LIBFC_HoTT_Putchar, PSTR(format) , ## args);}
#define HoTT_printfxy(x,y,format, args...) { LIBFC_HoTT_SetPos(y * 21 + x); _printf_P(&LIBFC_HoTT_Putchar, PSTR(format) , ## args);}
#define HoTT_printfxy_INV(x,y,format, args...) { LIBFC_HoTT_SetPos(y * 21 + x); _printf_P(&LIBFC_HoTT_Putchar_INV, PSTR(format) , ## args);}
#define HoTT_printfxy_BLINK(x,y,format, args...) { LIBFC_HoTT_SetPos(y * 21 + x); _printf_P(&LIBFC_HoTT_Putchar_BLINK, PSTR(format) , ## args);}
#define HoTT_printf_BLINK(format, args...) { _printf_P(&LIBFC_HoTT_Putchar_BLINK, PSTR(format) , ## args);}
#define HoTT_printf_INV(format, args...) { _printf_P(&LIBFC_HoTT_Putchar_INV, PSTR(format) , ## args);}
 
#define VOICE_MINIMALE_EINGANSSPANNUNG 16
#define VOICE_BEEP 5
#define HoTT_GRAD 96
#define HoTT_LINKS 123
#define HoTT_RECHTS 124
#define HoTT_OBEN 125
#define HoTT_UNTEN 126
 
 
GPSPacket_t GPSPacket;
VarioPacket_t VarioPacket;
ASCIIPacket_t ASCIIPacket;
ElectricAirPacket_t ElectricAirPacket;
HoTTGeneral_t HoTTGeneral;
 
 
uint8_t MaxBlTempertaure = 0;
uint8_t MinBlTempertaure = 0;
uint8_t HottestBl = 0;
 
void GetHottestBl(void)
{
static uint8_t search = 0, tmp_max = 0, tmp_min = 0, who;
 
if(Motor[search].Temperature > tmp_max)
{
tmp_max = Motor[search].Temperature;
who = search;
}
else if(Motor[search].Temperature)
{
if(Motor[search].Temperature < tmp_min)
{
tmp_min = Motor[search].Temperature;
}
}
if(++search > MAX_MOTORS)
{
search = 0;
if(tmp_min != 255) MinBlTempertaure = tmp_min; else MinBlTempertaure = 0;
MaxBlTempertaure = tmp_max;
HottestBl = who;
tmp_min = 255;
tmp_max = 0;
who = 0;
}
}
 
 
void Hott_ClearLine(uint8_t line)
{
HoTT_printfxy(0,line," ");
}
 
void HoTTMenu_Update(void)
uint8_t HoTT_Waring(void)
{
static uint8_t what;
switch(what++)
if(FC_StatusFlags & FC_STATUS_LOWBAT) return(VOICE_MINIMALE_EINGANSSPANNUNG);
if((FC_StatusFlags & FC_STATUS_MOTOR_RUN) && NCErrorCode) return(VOICE_BEEP);
return(0);
}
 
void NC_Fills_HoTT_Telemety(void)
{
uint8_t *ptr = 0;
uint8_t max = 0, i, z;
 
switch(FromNaviCtrl.Param.Byte[11])
{
case 0:
HoTT_printfxy(0,0,"%2i.%1iV ",UBat/10, UBat%10);
HoTT_printfxy(8,0,"%4imAh %2i:%02i",Capacity.UsedCapacity,FlightSeconds/60,FlightSeconds%60);
case HOTT_VARIO_PACKET_ID:
ptr = (uint8_t *) &VarioPacket;
max = sizeof(VarioPacket);
break;
case 1:
HoTT_printfxy(0,1,"Dir:%3d%c",(int16_t)(YawGyroHeading / GYRO_DEG_FACTOR), 0x60);
if(ParamSet.Config0 & CFG0_AIRPRESS_SENSOR)
{
HoTT_printfxy_INV(10,1,"Alt:%4im %c", (int16_t)(ReadingHeight/100),VarioCharacter)
}
else
{
HoTT_printfxy(10,1,"Alt: ---- ");
}
break;
case 2:
HoTT_printfxy(0,2,"I=%3i.%1iA %4iW ",Capacity.ActualCurrent/10, Capacity.ActualCurrent%10,Capacity.ActualPower);
case HOTT_GPS_PACKET_ID:
ptr = (uint8_t *) &GPSPacket;
max = sizeof(GPSPacket);
break;
case 3:
if(NCDataOkay)
{
HoTT_printfxy(0,3,"Home:%3dm %3d%c", GPSInfo.HomeDistance/10, GPSInfo.HomeBearing, 0x60);
}
else
{
Hott_ClearLine(3);
}
case HOTT_ELECTRIC_AIR_PACKET_ID:
ptr = (uint8_t *) &ElectricAirPacket;
max = sizeof(ElectricAirPacket);
break;
case 4:
if(NCDataOkay)
{
HoTT_printfxy(0,4,"GPS:%2um/s Sat:%d ",GPSInfo.Speed, GPSInfo.NumOfSats);
switch (GPSInfo.SatFix)
case HOTT_GENERAL_PACKET_ID:
ptr = (uint8_t *) &HoTTGeneral;
max = sizeof(HoTTGeneral);
break;
default:
ptr = 0;
max = 0;
break;
}
 
if(ptr)
{
z = FromNaviCtrl.Param.Byte[0]; // Data allocation
 
for(i=0; i < FromNaviCtrl.Param.Byte[1]; i++)
{
if(z >= max) break;
ptr[z] = FromNaviCtrl.Param.Byte[2+i];
z++;
}
}
}
 
uint16_t BuildHoTT_Vario(void)
{
uint16_t tmp;
if(WaypointTrimming == 0)
{
tmp = 30000 + (AltitudeSetpointTrimming * ParamSet.Height_Gain) / 3;
if(tmp < 30000 && tmp > 30000 - 50) tmp = 30000 - 50; // weil es erst bei < 0,5m/sek piept
}
else
if(WaypointTrimming > 0) tmp = 30000 + NCAltitudeSpeed * 10;
else tmp = 30000 - NCAltitudeSpeed * 10;
return(tmp);
}
 
 
uint8_t HoTT_Telemety(uint8_t packet_request)
{
 
switch(packet_request)
{
case HOTT_VARIO_PACKET_ID:
VarioPacket.Altitude = ReadingHeight/100 + 500;
VarioPacket.m_sec = BuildHoTT_Vario();
VarioPacket.m_3sec = VarioPacket.m_sec;
VarioPacket.m_10sec = VarioPacket.m_sec;
if (VarioPacket.Altitude < VarioPacket.MinAltitude) VarioPacket.MinAltitude = VarioPacket.Altitude;
if (VarioPacket.Altitude > VarioPacket.MaxAltitude) VarioPacket.MaxAltitude = VarioPacket.Altitude;
VarioPacket.WarnBeep = HoTT_Waring();
HoTT_DataPointer = (uint8_t *) &VarioPacket;
return(sizeof(VarioPacket));
break;
 
case HOTT_GPS_PACKET_ID:
GPSPacket.Altitude = ReadingHeight/100 + 500;
//GPSPacket.Distance = GPSInfo.HomeDistance/10; // macht die NC
//GPSPacket.Heading = GPSInfo.HomeBearing/2; // macht die NC
//GPSPacket.Speed = (GPSInfo.Speed * 36) / 10; // macht die NC
GPSPacket.m_sec = BuildHoTT_Vario();
GPSPacket.m_3sec = 120;
GPSPacket.m_10sec = 0;
GPSPacket.WarnBeep = HoTT_Waring();
HoTT_DataPointer = (uint8_t *) &GPSPacket;
return(sizeof(GPSPacket));
break;
 
case HOTT_ELECTRIC_AIR_PACKET_ID:
GetHottestBl();
 
ElectricAirPacket.Altitude = ReadingHeight/100 + 500;
ElectricAirPacket.Battery1 = UBat;
ElectricAirPacket.Battery2 = UBat;
ElectricAirPacket.VoltageCell1 = YawGyroHeadingDeg / 2;
ElectricAirPacket.VoltageCell8 = ElectricAirPacket.VoltageCell1;
ElectricAirPacket.VoltageCell7 = GPSInfo.HomeDistance/20;
ElectricAirPacket.VoltageCell14 = ElectricAirPacket.VoltageCell7;
ElectricAirPacket.m_sec = BuildHoTT_Vario();
ElectricAirPacket.m_3sec = 120;
ElectricAirPacket.InputVoltage = UBat;
ElectricAirPacket.Temperature1 = MinBlTempertaure + 20;
ElectricAirPacket.Temperature2 = MaxBlTempertaure + 20;
ElectricAirPacket.Capacity = Capacity.UsedCapacity/10;
ElectricAirPacket.WarnBeep = HoTT_Waring();
ElectricAirPacket.Current = Capacity.ActualCurrent;
HoTT_DataPointer = (uint8_t *) &ElectricAirPacket;
return(sizeof(ElectricAirPacket));
break;
 
case HOTT_GENERAL_PACKET_ID:
GetHottestBl();
HoTTGeneral.Rpm = GPSInfo.HomeDistance/100;
HoTTGeneral.VoltageCell1 = YawGyroHeadingDeg / 2;
HoTTGeneral.VoltageCell5 = GPSInfo.HomeDistance/20;
if(UBat > LowVoltageWarning + 5) HoTTGeneral.FuelPercent = (UBat - (LowVoltageWarning + 6)) * 3;
else HoTTGeneral.FuelPercent = 0;
HoTTGeneral.FuelCapacity = ReadingHeight/100; ;
HoTTGeneral.Altitude = ReadingHeight/100 + 500;
HoTTGeneral.Battery1 = UBat;
HoTTGeneral.Battery2 = UBat;
HoTTGeneral.m_sec = BuildHoTT_Vario();
HoTTGeneral.m_3sec = 120;
HoTTGeneral.InputVoltage = UBat;
HoTTGeneral.Temperature1 = MinBlTempertaure + 20;
HoTTGeneral.Temperature2 = MaxBlTempertaure + 20;
HoTTGeneral.Capacity = Capacity.UsedCapacity/10;
HoTTGeneral.WarnBeep = HoTT_Waring();
HoTTGeneral.Current = Capacity.ActualCurrent;
HoTT_DataPointer = (uint8_t *) &HoTTGeneral;
return(sizeof(HoTTGeneral));
break;
 
default: return(0);
}
}
 
 
void HoTT_Menu(void)
{
static uint8_t line = 0, page = 0;
if(page == 0)
{
switch(line++)
{
case 0:
if(FC_StatusFlags & FC_STATUS_LOWBAT)
{
case SATFIX_3D:
HoTT_printfxy(16,4," 3D ");
break;
HoTT_printfxy_BLINK(0,0," %2i.%1iV ",UBat/10, UBat%10);
}
else
{
HoTT_printfxy(0,0," %2i.%1iV ",UBat/10, UBat%10);
}
if(ParamSet.Config0 & CFG0_AIRPRESS_SENSOR)
{
if(FC_StatusFlags2 & FC_STATUS2_ALTITUDE_CONTROL)
{
HoTT_printfxy_INV(10,0,"ALT:%4im %c", (int16_t)(ReadingHeight/100), VarioCharacter);
}
else
{
HoTT_printfxy(10,0,"ALT:%4im ", (int16_t)(ReadingHeight/100));
}
}
else
{
HoTT_printfxy(10,0,"ALT:---- ");
}
break;
 
case SATFIX_2D:
case SATFIX_NONE:
default:
HoTT_printfxy(16,4,"NoFix");
break;
case 1:
if(FC_StatusFlags & FC_STATUS_LOWBAT)
{
HoTT_printfxy_BLINK(0,1," %2i:%02i ",FlightSeconds/60,FlightSeconds%60);
}
if(GPSInfo.Flags & FLAG_DIFFSOLN)
else
{
HoTT_printfxy(0,1," %2i:%02i ",FlightSeconds/60,FlightSeconds%60);
}
HoTT_printfxy(10,1,"DIR: %3d%c",YawGyroHeadingDeg, HoTT_GRAD);
if(FC_StatusFlags2 & FC_STATUS2_CAREFREE)
{
HoTT_printfxy(16,4,"DGPS ");
HoTT_printfxy(20,1,"C");
}
}
else
{ //012345678901234567890
HoTT_printfxy(0,4,"No NaviCtrl! ");
}
break;
case 5:
HoTT_printfxy(0,5,"%3i %3i %3i %3i%cC ", Motor[0].Temperature, Motor[1].Temperature, Motor[2].Temperature, Motor[3].Temperature,0x60);
break;
case 6:
if(RequiredMotors == 4) Hott_ClearLine(6);
else
if(RequiredMotors == 6) HoTT_printfxy(0,6,"%3i %3i%cC ", Motor[4].Temperature, Motor[5].Temperature,0x60)
{
HoTT_printfxy(20,1," ");
}
break;
 
case 2:
if(FC_StatusFlags & FC_STATUS_LOWBAT)
{
HoTT_printfxy_BLINK(0,2," %5i ",Capacity.UsedCapacity);
}
else
{
HoTT_printfxy(0,2," %5i ",Capacity.UsedCapacity);
}
HoTT_printfxy(12,2,"I:%2i.%1iA ",Capacity.ActualCurrent/10, Capacity.ActualCurrent%10);
break;
 
case 3:
HoTT_printfxy(9,0,"I");
HoTT_printfxy(9,1,"I");
HoTT_printfxy(9,2,"I");
HoTT_printfxy(0,3,"---------+-----------");
HoTT_printfxy(0,6,"---------------------");
break;
 
case 4:
if(NCDataOkay)
{
HoTT_printfxy(9,4,"I");
HoTT_printfxy(0,4,"SAT:%2d ",GPSInfo.NumOfSats);
HoTT_printfxy(10,4,"DIST:%3dm",GPSInfo.HomeDistance/10);
switch (GPSInfo.SatFix)
{
case SATFIX_3D:
if(GPSInfo.Flags & FLAG_DIFFSOLN) HoTT_printfxy(7,4,"D ")
else HoTT_printfxy(7,4,"3D");
break;
default:
HoTT_printfxy_BLINK(7,4,"!!");
break;
}
}
else
if(RequiredMotors > 6) HoTT_printfxy(0,6,"%3i %3i %3i %3i%cC ", Motor[4].Temperature, Motor[5].Temperature, Motor[6].Temperature, Motor[7].Temperature,0x6D);
{ //012345678901234567890
Hott_ClearLine(4);
}
break;
 
case 5:
if(NCDataOkay)
{
HoTT_printfxy(9,5,"I");
HoTT_printfxy(4,5,"%2um/s",GPSInfo.Speed);
HoTT_printfxy(12,5,"HM:%3d%c %c", GPSInfo.HomeBearing, HoTT_GRAD, NCGPSModeCharacter);
}
else Hott_ClearLine(5);
break;
 
case 6:
/*
if(RequiredMotors == 4) Hott_ClearLine(6);
else
if(RequiredMotors == 6) HoTT_printfxy(0,6,"%3i %3i%cC ", Motor[4].Temperature, Motor[5].Temperature, HoTT_GRAD)
else
if(RequiredMotors > 6) HoTT_printfxy(0,6,"%3i %3i %3i %3i%cC ", Motor[4].Temperature, Motor[5].Temperature, Motor[6].Temperature, Motor[7].Temperature, HoTT_GRAD);
*/
break;
 
case 7:
if(NCErrorCode)
{
if(HoTTBlink && NCErrorCode < MAX_ERR_NUMBER)
{
Hott_ClearLine(7);
HoTT_printfxy_INV(0,7,"ERR: %2d !",NCErrorCode);
}
else
{
HoTT_printfxy(0,7,"ERR: "); _printf_P(&LIBFC_HoTT_Putchar, NC_ERROR_TEXT[NCErrorCode], 0);
}
}
else HoTT_printfxy(0,7," www.MikroKopter.de ");
break;
 
case 8:
ASCIIPacket.WarnBeep = HoTT_Waring();
case 9:
case 10:
case 11:
case 12:
case 13:
case 14:
case 15:
case 16:
if(HottKeyboard == 8)
{
LIBFC_HoTT_Clear();
page = 1;
line = 0;
};
HottKeyboard = 0;
break;
 
default:
line = 0;
break;
} // EOF switch(line++)
} // EOF if(page == 0)
else if(page == 1)
{
switch(line++)
{
case 0:
if(FC_StatusFlags & FC_STATUS_LOWBAT)
{
HoTT_printfxy_BLINK(0,0," %2i:%02i %2i.%1iV %4imAh",FlightSeconds/60,FlightSeconds%60,UBat/10, UBat%10,Capacity.UsedCapacity);
}
else
{
HoTT_printfxy(0,0," %2i:%02i %2i.%1iV %4imAh",FlightSeconds/60,FlightSeconds%60,UBat/10, UBat%10,Capacity.UsedCapacity);
}
break;
 
case 1:
HoTT_printfxy(0,1,"DIR:%3d%c",CompassHeading, HoTT_GRAD);
if(ParamSet.Config0 & CFG0_AIRPRESS_SENSOR)
{
if(FC_StatusFlags2 & FC_STATUS2_ALTITUDE_CONTROL) HoTT_printfxy_INV(10,1,"ALT:%4im", (int16_t)(ReadingHeight/100))
else HoTT_printfxy(10,1,"ALT:%4im", (int16_t)(ReadingHeight/100))
}
else
{
HoTT_printfxy(10,1,"Alt: ---- ");
}
HoTT_printfxy(20,1,"%c",VarioCharacter);
break;
 
case 2:
if(NCDataOkay)
{
HoTT_printfxy(1,2,"HM:%3d%c DIST:%3dm %c", GPSInfo.HomeBearing, HoTT_GRAD, GPSInfo.HomeDistance/10, NCGPSModeCharacter);
}
else
{
Hott_ClearLine(2);
}
break;
case 7: if(NCErrorCode) HoTT_printfxy(0,7,"ERROR: %2d ",NCErrorCode)
else HoTT_printfxy(0,7," www.MikroKopter.de ");
break;
case 8:
case 9:
case 10:
case 11:
case 12:
case 13:
case 14:
case 15:
case 16:
break;
 
/*
012345678901234567890
+++++++++++++++++++++
13,8V 1234mAh 12:30 0
Dir:180° Alt: 123m + 1
GPS: 10Sat DGPS PH CF 2
Home: 280° 123m 3
I=23A P=123W Max=123 4
BL1-4: 11 22 33 44°C 5
BL5-8: 55 66 77 88°C 6
No Error 7
+++++++++++++++++++++
*/
default: what = 0;
break;
case 3:
HoTT_printfxy(0,3,"PWR:%2i.%1iA (%iW) ",Capacity.ActualCurrent/10, Capacity.ActualCurrent%10,Capacity.ActualPower);
break;
 
case 4:
if(NCDataOkay)
{
HoTT_printfxy(0,4,"GPS:%2um/s SAT:%d ",GPSInfo.Speed,GPSInfo.NumOfSats);
switch (GPSInfo.SatFix)
{
case SATFIX_3D:
HoTT_printfxy(16,4," 3D ");
break;
//case SATFIX_2D:
//case SATFIX_NONE:
default:
HoTT_printfxy_BLINK(16,4,"NOFIX");
break;
}
if(GPSInfo.Flags & FLAG_DIFFSOLN)
{
HoTT_printfxy(16,4,"DGPS ");
}
}
else
{ //012345678901234567890
HoTT_printfxy(0,4," No NaviCtrl ");
}
break;
 
case 5:
HoTT_printfxy(0,5,"%3i %3i %3i %3i%cC ", Motor[0].Temperature, Motor[1].Temperature, Motor[2].Temperature, Motor[3].Temperature, HoTT_GRAD);
if(FC_StatusFlags2 & FC_STATUS2_CAREFREE) HoTT_printfxy_INV(18,5,"CF") else HoTT_printfxy(18,5," ");
break;
 
case 6:
if(RequiredMotors == 4) Hott_ClearLine(6);
else
if(RequiredMotors == 6) HoTT_printfxy(0,6,"%3i %3i%cC ", Motor[4].Temperature, Motor[5].Temperature, HoTT_GRAD)
else
if(RequiredMotors > 6) HoTT_printfxy(0,6,"%3i %3i %3i %3i%cC ", Motor[4].Temperature, Motor[5].Temperature, Motor[6].Temperature, Motor[7].Temperature, HoTT_GRAD);
break;
 
case 7:
if(NCErrorCode)
{
if(HoTTBlink && NCErrorCode < MAX_ERR_NUMBER)
{
Hott_ClearLine(7);
HoTT_printfxy_INV(0,7,"ERR: %2d !",NCErrorCode);
}
else
{
HoTT_printfxy(0,7,"ERR: "); _printf_P(&LIBFC_HoTT_Putchar, NC_ERROR_TEXT[NCErrorCode], 0);
}
}
else HoTT_printfxy(0,7," www.MikroKopter.de ");
break;
 
case 8:
ASCIIPacket.WarnBeep = HoTT_Waring();
case 9:
case 10:
case 11:
case 12:
case 13:
case 14:
case 15:
case 16:
if(HottKeyboard == 8)
{
LIBFC_HoTT_Clear();
page = 2;
line = 0;
}
if(HottKeyboard == 1)
{
LIBFC_HoTT_Clear();
page = 0;
line = 0;
}
HottKeyboard = 0;
break;
 
default:
line = 0;
break;
} // EOF switch(line++)
} // EOF if(page == 1)
else if(page == 2)
{
switch(line++)
{
case 0:
HoTT_printfxy_INV(0,0,"Setting:%u %s ",GetActiveParamSet(), ParamSet.Name);
break;
 
case 1:
HoTT_printfxy(0,1,"Min:%2i.%1iV %s ",LowVoltageWarning/10, LowVoltageWarning%10, Mixer.Name);
break;
 
case 2:
HoTT_printfxy(0,2,"ALT:");
if(ParamSet.Config0 & CFG0_AIRPRESS_SENSOR)
{
if(!(ParamSet.Config0 & CFG0_HEIGHT_SWITCH))
{
HoTT_printf("POTI:%3u ", FCParam.HeightSwitch);
}
else
{
if(FCParam.HeightSwitch > 50) HoTT_printf("(ON) ")
else HoTT_printf("(OFF) ");
if((ParamSet.Config2 & CFG2_HEIGHT_LIMIT)) HoTT_printf("LIMIT", FCParam.HeightSwitch)
else HoTT_printf("VARIO");
}
}
else
{
HoTT_printf("DISABLED");
}
break;
 
case 3:
HoTT_printfxy(0,3,"CF:");
if(!ParamSet.CareFreeModeControl) HoTT_printf("DISABLED")
else
{
if(CareFree) HoTT_printf(" (ON) ")
else HoTT_printf(" (OFF)");
if(ParamSet.Config2 & CFG2_LEARNABLE_CAREFREE) HoTT_printf(" TEACH");
}
break;
 
case 4:
HoTT_printfxy(0,4,"GPS:");
if(!(ParamSet.Config0 & CFG0_GPS_ACTIVE))
{
HoTT_printf("DISABLED");
}
else
{
HoTT_printf("(%c)", NCGPSModeCharacter);
}
 
if(ParamSet.FailSafeTime) HoTT_printfxy(10,4," FS:%usek ",ParamSet.FailSafeTime);
break;
 
case 5:
HoTT_printfxy(0,5,"HOME ALT:");
if(ParamSet.ComingHomeAltitude) HoTT_printf("%um",ParamSet.ComingHomeAltitude)
else HoTT_printf("HOLD ");
break;
 
case 6:
HoTT_printfxy(0,6,"Ni:%4i Ro:%4i C:%3i",PPM_in[ParamSet.ChannelAssignment[CH_NICK]], PPM_in[ParamSet.ChannelAssignment[CH_ROLL]], FCParam.ServoNickControl);
HoTT_printfxy(0,7,"Gs:%4i Ya:%4i ",PPM_in[ParamSet.ChannelAssignment[CH_GAS]] + RC_GAS_OFFSET, PPM_in[ParamSet.ChannelAssignment[CH_YAW]]);
break;
 
case 7: //HoTT_printfxy(0,6,"WARNINGS:");
if(HoTTBlink)
{
LIBFC_HoTT_SetPos(6 * 21);
if(!(ParamSet.Config0 & CFG0_AXIS_COUPLING_ACTIVE)) HoTT_printf_BLINK("COUPLING OFF! ");
if(ParamSet.Config1 & (CFG1_LOOP_LEFT | CFG1_LOOP_RIGHT | CFG1_LOOP_DOWN | CFG1_LOOP_UP)) HoTT_printf_BLINK("LOOPING! ");
if(ParamSet.Config0 & CFG0_HEADING_HOLD) HoTT_printf_BLINK("HH! ");
if(!(ParamSet.Config0 & CFG0_COMPASS_ACTIVE)) HoTT_printf_BLINK("COMPASS OFF! ");
}
break;
 
case 8:
ASCIIPacket.WarnBeep = HoTT_Waring();
break;
case 9:
case 10:
case 11:
case 12:
case 13:
case 14:
case 15:
case 16:
if(HottKeyboard == 1)
{
LIBFC_HoTT_Clear();
page = 1;
line = 0;
}
HottKeyboard = 0;
break;
 
default:
line = 0;
break;
}
}
else page = 0;
}
 
#endif
 
 
 
 
 
/beta/Code Redesign killagreg/hottmenu.h
1,99 → 1,142
#ifndef _HOTTMENU_H
#define _HOTTMENU_H
 
extern void HoTTMenu_Update(void);
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
 
extern uint8_t HottKeyboard;
extern volatile uint8_t HoTTBlink;
extern volatile uint8_t *HoTT_DataPointer;
 
extern void HoTT_Menu(void);
extern uint8_t HoTT_Telemety(uint8_t);
extern uint8_t HoTT_Waring(void);
 
typedef struct
{
uint8_t StartByte; // 0x7C
uint8_t Packet_ID; // HOTT_ELECTRIC_AIR_PACKET_ID
uint8_t WarnBeep; // Anzahl der Töne 0..36
uint8_t VoltageCell1; // 208 = 4,16V (Voltage * 50 = Wert)
uint8_t VoltageCell2; // 209 = 4,18V
uint8_t VoltageCell3; //
uint8_t VoltageCell4; //
uint8_t VoltageCell5; //
uint8_t VoltageCell6; //
uint8_t VoltageCell7; //
uint8_t VoltageCell8; //
uint8_t VoltageCell9; //
uint8_t VoltageCell10; //
uint8_t VoltageCell11; //
uint8_t VoltageCell12; //
uint8_t VoltageCell13; //
uint8_t VoltageCell14; //
uint16_t Battery1; // 51 = 5,1V
uint16_t Battery2; // 51 = 5,1V
uint8_t Temperature1; // 44 = 24°C, 0 = -20°C
uint8_t Temperature2; // 44 = 24°C, 0 = -20°C
uint16_t Altitude;
uint16_t Current; // 1 = 0.1A
uint16_t InputVoltage; // 66 = 6,6V
uint16_t Capacity; // 1 = 10mAh
uint16_t m_sec; // 3000 = 0
uint16_t m_3sec; // 3000 = 0
uint8_t NullByte1; // 0x00
uint8_t NullByte2; // 0x00
uint8_t EndByte; // 0x7D
uint8_t StartByte; // 0x7C
uint8_t Packet_ID; // HOTT_GENERAL_PACKET_ID
uint8_t WarnBeep; // Anzahl der Töne 0..36
uint8_t VoltageCell1; // 208 = 4,16V (Voltage * 50 = Wert)
uint8_t VoltageCell2; // 209 = 4,18V
uint8_t VoltageCell3; //
uint8_t VoltageCell4; //
uint8_t VoltageCell5; //
uint8_t VoltageCell6; //
uint16_t Battery1; // 51 = 5,1V
uint16_t Battery2; // 51 = 5,1V
uint8_t Temperature1; // 44 = 24°C, 0 = -20°C
uint8_t Temperature2; // 44 = 24°C, 0 = -20°C
uint8_t FuelPercent;
uint16_t FuelCapacity;
uint16_t Rpm;
uint16_t Altitude;
uint16_t m_sec; // 30000 = 0
uint8_t m_3sec; // 120 = 0
uint16_t Current; // 1 = 0.1A
uint16_t InputVoltage; // 66 = 6,6V
uint16_t Capacity; // 1 = 10mAh
uint8_t NullByte1; // 0x00
uint8_t NullByte2; // 0x00
uint8_t EndByte; // 0x7D
} HoTTGeneral_t;
 
typedef struct
{
uint8_t StartByte; // 0x7C
uint8_t Packet_ID; // HOTT_ELECTRIC_AIR_PACKET_ID
uint8_t WarnBeep; // Anzahl der Töne 0..36
uint8_t VoltageCell1; // 208 = 4,16V (Voltage * 50 = Wert)
uint8_t VoltageCell2; // 209 = 4,18V
uint8_t VoltageCell3; //
uint8_t VoltageCell4; //
uint8_t VoltageCell5; //
uint8_t VoltageCell6; //
uint8_t VoltageCell7; //
uint8_t VoltageCell8; //
uint8_t VoltageCell9; //
uint8_t VoltageCell10; //
uint8_t VoltageCell11; //
uint8_t VoltageCell12; //
uint8_t VoltageCell13; //
uint8_t VoltageCell14; //
uint16_t Battery1; // 51 = 5,1V
uint16_t Battery2; // 51 = 5,1V
uint8_t Temperature1; // 44 = 24°C, 0 = -20°C
uint8_t Temperature2; // 44 = 24°C, 0 = -20°C
uint16_t Altitude; // 500 = 0m
uint16_t Current; // 1 = 0.1A
uint16_t InputVoltage; // 66 = 6,6V
uint16_t Capacity; // 1 = 10mAh
uint16_t m_sec; // 30000 = 0
uint16_t m_3sec; // 120 = 0
uint8_t NullByte1; // 0x00
uint8_t NullByte2; // 0x00
uint8_t EndByte; // 0x7D
} ElectricAirPacket_t;
 
typedef struct
{
uint8_t StartByte; // 0x7C
uint8_t Packet_ID; // 0x89 - Vario ID
uint8_t WarnBeep; // Anzahl der Töne 0..36
uint16_t Altitude; // 500 = 0m
uint16_t MaxAltitude; // 500 = 0m
uint16_t MinAltitude; // 500 = 0m
uint16_t m_sec; // 3000 = 0
uint16_t m_3sec; // 3000 = 0
uint16_t m_10sec; // 3000 = 0
uint8_t NullByte; // 0x00
uint8_t EndByte; // 0x7D
uint8_t StartByte; // 0x7C
uint8_t Packet_ID; // HOTT_VARIO_PACKET_ID
uint8_t WarnBeep; // Anzahl der Töne 0..36
uint16_t Altitude; // 500 = 0m
uint16_t MaxAltitude; // 500 = 0m
uint16_t MinAltitude; // 500 = 0m
uint16_t m_sec; // 30000 = 0
uint16_t m_3sec; // 120 = 0
uint16_t m_10sec; //
uint8_t NullByte; // 0x00
uint8_t EndByte; // 0x7D
} VarioPacket_t;
 
typedef struct
{
uint8_t StartByte; // 0x7C
uint8_t Packet_ID; // 0x89 - Vario ID
uint8_t WarnBeep; // Anzahl der Töne 0..36
uint8_t Heading; // 1 = 2°
uint16_t Speed; // in km/h
uint8_t Lat_G;
uint8_t Lat_M;
uint8_t Lat_Sek1;
uint8_t Lat_Sek2;
uint8_t Lon_G;
uint8_t Lon_M;
uint8_t Lon_Sek1;
uint8_t Lon_Sek2;
uint16_t Distance; // 9000 = 0m
uint16_t Hoehe; // 500 = 0m
uint16_t Altitude; // 500 = 0m
uint16_t m_sec; // 3000 = 0
uint16_t m_3sec; // 3000 = 0
uint16_t m_10sec; // 3000 = 0
uint8_t NullByte; // 0x00
uint8_t NullByte1; // 0x00
uint8_t EndByte; // 0x7D
uint8_t StartByte; // 0 // 0x7C
uint8_t Packet_ID; // 1 // HOTT_GPS_PACKET_ID
uint8_t WarnBeep; // 2 // Anzahl der Töne 0..36
uint8_t Heading; // 3 // 1 = 2°
uint16_t Speed; // 4+5 // in km/h
uint8_t Lat_North; // 6
uint8_t Lat_G; // 7
uint8_t Lat_M; // 8
uint8_t Lat_Sek1; // 9
uint8_t Lat_Sek2; // 10
uint8_t Lon_East; // 11
uint8_t Lon_G; // 12
uint8_t Lon_M; // 13
uint8_t Lon_Sek1; // 14
uint8_t Lon_Sek2; // 15
uint16_t Distance; // 16+17 // 9000 = 0m
uint16_t Altitude; // 18+19 // 500 = 0m
uint16_t m_sec; // 20+21 // 30000 = 0
uint16_t m_3sec; // 22+23 // 120 = 0
uint16_t m_10sec; // 24+25 //
uint8_t NullByte; // 0x00
uint8_t NullByte1; // 0x00
uint8_t EndByte; // 0x7D
} GPSPacket_t;
 
typedef struct
{
uint8_t StartByte; // 0x7B
uint8_t Packet_ID; // 0x00
uint8_t WarnBeep; // Anzahl der Töne 0..36
uint8_t Text[8*21];
uint8_t EndByte; // 0x7D
uint8_t StartByte; // 0x7B
uint8_t Packet_ID; //
uint8_t WarnBeep; // Anzahl der Töne 0..36
int8_t Text[8*21];
uint8_t EndByte; // 0x7D
} ASCIIPacket_t;
 
#define HOTT_VARIO_PACKET_ID 0x89
#define HOTT_GPS_PACKET_ID 0x8A
#define HOTT_ELECTRIC_AIR_PACKET_ID 0x8E
#define HOTT_GENERAL_PACKET_ID 0x8D
 
extern GPSPacket_t GPSPacket;
extern VarioPacket_t VarioPacket;
extern ASCIIPacket_t ASCIIPacket;
extern ElectricAirPacket_t ElectricAirPacket;
extern HoTTGeneral_t HoTTGeneral;
 
#define HOTT_VARIO_PACKET_ID 0x89
#define HOTT_GPS_PACKET_ID 0x8A
#define HOTT_ELECTRIC_AIR_PACKET_ID 0x8E
 
 
#endif
#endif
/beta/Code Redesign killagreg/jetimenu.c
7,6 → 7,7
#include "eeprom.h"
#include "main.h"
#include "capacity.h"
#include "timer0.h"
#ifdef USE_NAVICTRL
#include "spi.h"
#endif
31,22 → 32,44
JetiBox_printfxy(0,0,"%2i.%1iV",UBat/10, UBat%10);
if(NCDataOkay)
{
JetiBox_printfxy(6,0,"%3d%c %03dm",(int16_t)(YawGyroHeading / GYRO_DEG_FACTOR), 0xDF, GPSInfo.HomeDistance/10);
//JetiBox_printfxy(6,0,"%03dm %03d%c", GPSInfo.HomeDistance/10,GPSInfo.HomeBearing, 0xDF);
JetiBox_printfxy(6,0,"%3d%c %03dm%c",YawGyroHeadingDeg, 0xDF, GPSInfo.HomeDistance/10, NCGPSModeCharacter);
}
else
{
if(NCErrorCode)
JetiBox_printfxy(6,0,"Status")
}
 
if(NCErrorCode)
{
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
{
JetiBox_printfxy(6,0,"ERROR: %2d", NCErrorCode);
static uint16_t timer = 0;
static uint8_t toggle = 1;
// toggle each 1.5 seconds errot number and text
if(CheckDelay(timer))
{
if(toggle) toggle = 0;
else toggle = 1;
timer = SetDelay(1500);
}
if(toggle)
{
LIBFC_JetiBox_SetPos(0);
_printf_P(&LIBFC_JetiBox_Putchar, NC_ERROR_TEXT[NCErrorCode], 0);
}
else
{
JetiBox_printfxy(6,0,"ERROR: %2d ",NCErrorCode);
if(FC_StatusFlags & FC_STATUS_MOTOR_RUN) JetiBeep = 'O';
}
}
else
{
JetiBox_printfxy(6,0,"Status")
};
#else
JetiBox_printfxy(6,0,"ERROR: %2d ", NCErrorCode);
#endif
}
 
JetiBox_printfxy(0,1,"%4i %2i:%02i",Capacity.UsedCapacity,FlightSeconds/60,FlightSeconds%60);
if(ParamSet.Config0 & CFG0_AIRPRESS_SENSOR)
if(FCParam.Config0 & CFG0_AIRPRESS_SENSOR)
{
JetiBox_printfxy(10,1,"%4im%c", (int16_t)(ReadingHeight/100),VarioCharacter);
}
84,7 → 107,6
if(NCDataOkay)
{
JetiBox_printfxy(0,0,"%2um/s Sat:%2u",GPSInfo.Speed,GPSInfo.NumOfSats)
//JetiBox_printfxy(0,0,"Sat:%02d", GPSInfo.NumOfSats);
switch (GPSInfo.SatFix)
{
case SATFIX_3D:
102,7 → 124,7
{
JetiBox_printfxy(12,0,"DGPS");
}
JetiBox_printfxy(0,1,"Home:%3dm %3d%c", GPSInfo.HomeDistance/10, GPSInfo.HomeBearing, 0xDF); // 0xDF = °
JetiBox_printfxy(0,1,"Home:%3dm %3d%c %c", GPSInfo.HomeDistance/10, GPSInfo.HomeBearing, 0xDF, NCGPSModeCharacter); // 0xDF = °
}
else
{ //0123456789ABCDEF
/beta/Code Redesign killagreg/led.c
79,9 → 79,9
 
 
 
if(!delay--) // 10 ms intervall
if(!delay--) // 20 ms intervall
{
delay = 4;
delay = 9;
if( (FC_StatusFlags & (FC_STATUS_LOWBAT|FC_STATUS_EMERGENCY_LANDING)) || (UART_VersionInfo.HardwareError[1] & FC_ERROR1_I2C) )
{
if(ParamSet.J16Bitmask_Warning)
106,7 → 106,7
 
if(!J16Warn)
{
if( (ParamSet.Config1 & CFG1_MOTOR_BLINK) && !(FC_StatusFlags & FC_STATUS_MOTOR_RUN))
if( (ParamSet.Config1 & CFG1_MOTOR_BLINK1) && !(FC_StatusFlags & FC_STATUS_MOTOR_RUN))
{
if(ParamSet.Config1 & CFG1_MOTOR_OFF_LED1) J16_ON;
else J16_OFF;
116,7 → 116,7
if(J16Bitmask & 128) J16_ON;
else J16_OFF;
}
else if ((ParamSet.J16Timing > 247) && (FCParam.J16Timing < 10))
else if ((ParamSet.J16Timing > 247) && (FCParam.J16Timing == 5))
{
if(J16Bitmask & 128) J16_OFF;
else J16_ON;
123,7 → 123,7
}
else if(!J16Blinkcount--)
{
J16Blinkcount = FCParam.J16Timing - 1;
J16Blinkcount = FCParam.J16Timing / 2;
if(J16Mask == 1) J16Mask = 128; else J16Mask /= 2;
if(J16Mask & J16Bitmask) J16_ON; else J16_OFF;
}
137,7 → 137,7
 
if(!J17Warn)
{
if( (ParamSet.Config1 & CFG1_MOTOR_BLINK) && !(FC_StatusFlags & FC_STATUS_MOTOR_RUN))
if( (ParamSet.Config1 & CFG1_MOTOR_BLINK2) && !(FC_StatusFlags & FC_STATUS_MOTOR_RUN))
{
if(ParamSet.Config1 & CFG1_MOTOR_OFF_LED2) J17_ON;
else J17_OFF;
147,7 → 147,7
if(J17Bitmask & 128) J17_ON;
else J17_OFF;
}
else if ((ParamSet.J17Timing > 247) && (FCParam.J17Timing < 10))
else if ((ParamSet.J17Timing > 247) && (FCParam.J17Timing == 5))
{
if(J17Bitmask & 128) J17_OFF;
else J17_ON;
154,7 → 154,7
}
else if(!J17Blinkcount--)
{
J17Blinkcount = FCParam.J17Timing - 1;
J17Blinkcount = FCParam.J17Timing / 2;
if(J17Mask == 1) J17Mask = 128; else J17Mask /= 2;
if(J17Mask & J17Bitmask) J17_ON; else J17_OFF;
}
/beta/Code Redesign killagreg/libfc.h
17,8 → 17,11
extern void LIBFC_JetiBox_SetPos(uint8_t index);
extern void LIBFC_JetiBox_Clear(void);
 
extern void LIBFC_CheckSettings(void);
 
extern void LIBFC_HoTT_Putchar(char c);
extern void LIBFC_HoTT_Putchar_INV(char c); // print Invers
extern void LIBFC_HoTT_Putchar_BLINK(char c);
extern void LIBFC_HoTT_SetPos(uint8_t index);
extern void LIBFC_HoTT_Clear(void);
 
/beta/Code Redesign killagreg/libfc1284.a
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
/beta/Code Redesign killagreg/main.c
62,6 → 62,7
#include "uart0.h"
#include "led.h"
#include "menu.h"
#include "hottmenu.h"
#include "fc.h"
#include "rc.h"
#include "analog.h"
156,6 → 157,7
{
uint16_t timer, pollingtimer;
uint8_t i, FoundMotors = 0;
uint8_t DisableRcOffBeeping = 0;
 
// disable interrupts global
cli();
300,19 → 302,16
DebugOut.Status[0] = 0x01 | 0x02;
 
JetiBeep = 0;
if(ParamSet.Config2 & CFG2_NO_RCOFF_BEEPING) DisableRcOffBeeping = 1;
// begin of main loop
while (1)
{
if(JetiUpdateModeActive) while (1);
if(ReceiverUpdateModeActive) while (1);
 
if(CheckDelay(pollingtimer))
{
pollingtimer = SetDelay(1);
LIBFC_Polling();
}
 
//GRN_ON;
if(UpdateMotor && ADReady) // control interval
{
//GRN_OFF;
UpdateMotor = 0; // reset Flag, is enabled every 2 ms by ISR of timer0
 
//J4HIGH;
325,7 → 324,7
if(RC_Quality)
{
RC_Quality--;
UART_VersionInfo.HardwareError[1] &= ~FC_ERROR1_PPM;
//UART_VersionInfo.HardwareError[1] &= ~FC_ERROR1_PPM;
}
else
{
347,7 → 346,7
}
if((BeepModulation == 0xFFFF) && (FC_StatusFlags & FC_STATUS_MOTOR_RUN) )
{
BeepTime = 10000; // 1 second
BeepTime = 25000; // 2.5 seconds
BeepModulation = 0x0080;
}
}
354,9 → 353,11
else
{
RED_OFF;
if(!BeepTime) UART_VersionInfo.HardwareError[1] &= ~FC_ERROR1_I2C;
// if(!BeepTime) UART_VersionInfo.HardwareError[1] &= ~FC_ERROR1_I2C;
}
 
LIBFC_Polling();
 
// allow Serial Data Transmit if motors must not updated at this time
if( !UpdateMotor )
{
370,7 → 371,9
static uint16_t counter_minute = 0;
 
timer += 20; // every 20 ms
 
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
if(ParamSet.Receiver == RECEIVER_HOTT) HoTT_Menu();
#endif
if(MissingMotor)
{
UART_VersionInfo.HardwareError[1] |= FC_ERROR1_BL_MISSING;
378,12 → 381,22
}
else
{
UART_VersionInfo.HardwareError[1] &= ~FC_ERROR1_BL_MISSING;
if(I2CTimeout > 6) DebugOut.Status[1] &= ~0x02; // BL-Error-Status
if(!BeepTime)
{
//UART_VersionInfo.HardwareError[1] &= ~FC_ERROR1_BL_MISSING;
if(I2CTimeout > 6) DebugOut.Status[1] &= ~0x02; // BL-Error-Status
}
}
 
if(I2CTimeout > 6) UART_VersionInfo.HardwareError[1] &= ~FC_ERROR1_I2C;
//if(I2CTimeout > 6) if(!BeepTime) UART_VersionInfo.HardwareError[1] &= ~FC_ERROR1_I2C;
 
// if RC signal is ok and RCOff beeping is disabled
if(RC_Quality && DisableRcOffBeeping)
{ // enable RCOff beeping again
DisableRcOffBeeping = 0;
BeepTime = 5000;
}
 
if(PcAccess) PcAccess--;
else
{
391,10 → 404,14
ExternStickNick= 0;
ExternStickRoll = 0;
ExternStickYaw = 0;
if((BeepModulation == 0xFFFF) && (RC_Quality == 0))
if(!RC_Quality)
{
BeepTime = 15000; // 1.5 seconds
BeepModulation = 0x0C00;
if( (BeepModulation == 0xFFFF) && (DisableRcOffBeeping != 2) ) // do not beep when feature is disabled
{
BeepTime = 15000; // 1.5 seconds
BeepModulation = 0x0C00;
if(DisableRcOffBeeping) DisableRcOffBeeping = 2;
}
}
}
#ifdef USE_NAVICTRL
402,6 → 419,7
{
NCDataOkay--;
UART_VersionInfo.HardwareError[1] &= ~FC_ERROR1_SPI_RX;
NCErrorCode = 9; // "ERR: no NC communication"
}
else // no data from NC
{
417,6 → 435,10
// set gps control sticks neutral
GPSStickNick = 0;
GPSStickNick = 0;
NCGPSAidMode = 0;
GPSInfo.Flags = 0;
FromNaviCtrl.AccErrorN = 0;
FromNaviCtrl.AccErrorR = 0;
FromNaviCtrl.CompassHeading = -1;
NCDataOkay = 0;
}
465,6 → 487,7
LED_Update();
Capacity_Update();
} // EOF !UpdateMotor
//else DebugOut.Analog[26]++;
} // EOF Update Motor && ADReady
 
#ifdef USE_NAVICTRL
/beta/Code Redesign killagreg/main.h
3,7 → 3,9
 
#include <avr/io.h>
 
//#define ACT_S3D_SUMMENSIGNAL
//#define ACT_S3D_SUMSIGNAL
//#define RECEIVER_SPEKTRUM_DX7EXP
//#define RECEIVER_SPEKTRUM_DX8EXP
 
// neue Hardware
#define RED_OFF {if((BoardRelease == 10)||(BoardRelease >= 20)) PORTB &=~(1<<PORTB0); else PORTB |= (1<<PORTB0);}
/beta/Code Redesign killagreg/makefile
6,11 → 6,11
#-------------------------------------------------------------------
VERSION_MAJOR = 0
VERSION_MINOR = 85
VERSION_PATCH = 0
VERSION_PATCH = 18
 
VERSION_SERIAL_MAJOR = 11 # Serial Protocol Major Version
VERSION_SERIAL_MINOR = 0 # Serial Protocol Minor Version
NC_SPI_COMPATIBLE = 20 # SPI Protocol Version
NC_SPI_COMPATIBLE = 23 # SPI Protocol Version
 
#-------------------------------------------------------------------
#OPTIONS
/beta/Code Redesign killagreg/menu.c
56,6 → 56,7
#include "timer2.h"
#include "fc.h"
#include "rc.h"
#include "spi.h"
#include "uart0.h"
#include "printf_P.h"
#include "analog.h"
63,7 → 64,7
#include "capacity.h"
#include "menu.h"
 
uint8_t MaxMenuItem = 17;
uint8_t MaxMenuItem = 16;
uint8_t MenuItem = 0;
 
 
113,6 → 114,20
LCD_printfxy(0,0,"++ Flight-Ctrl ++");
LCD_printfxy(0,1,"HW:V%d.%d SW:%d.%d%c",BoardRelease/10,BoardRelease%10,VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH+'a');
LCD_printfxy(0,2,"Setting: %d %s", GetActiveParamSet(), Mixer.Name);
 
 
if(NCErrorCode)
{
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
LCD_printfxy(0,3,"ERR%2d:",NCErrorCode);
_printf_P(&Menu_Putchar, NC_ERROR_TEXT[NCErrorCode] , 0);
#else
LCD_printfxy(0,3,"! NC-ERR: %2d ! ",NCErrorCode);
#endif
}
else
 
 
if(UART_VersionInfo.HardwareError[0]) LCD_printfxy(0,3,"Hardware Error 1:%d !!",UART_VersionInfo.HardwareError[0])
else
if (MissingMotor)
127,7 → 142,7
if(I2CTimeout < 6) LCD_printfxy(0,3,"I2C ERROR!!!")
break;
case 1:// Height Control Menu Item
if(ParamSet.Config0 & CFG0_AIRPRESS_SENSOR)
if(FCParam.Config0 & CFG0_AIRPRESS_SENSOR)
{
LCD_printfxy(0,0,"Height: %5i",(int16_t)(ReadingHeight/5));
LCD_printfxy(0,1,"Setpoint: %5i",(int16_t)(SetPointHeight/5));
144,13 → 159,14
LCD_printfxy(0,0,"Attitude");
LCD_printfxy(0,1,"Nick: %5i",IntegralGyroNick/1024);
LCD_printfxy(0,2,"Roll: %5i",IntegralGyroRoll/1024);
LCD_printfxy(0,3,"Hdg: %5i",CompassHeading);
LCD_printfxy(0,3,"Hdg: %5i",YawGyroHeadingDeg);
break;
case 3:// Remote Control Channel Menu Item
LCD_printfxy(0,0,"C1:%4i C2:%4i",PPM_in[1],PPM_in[2]);
for(i=0;i<8;i+=2) LCD_printfxy(0,i/2,"C%i:%4i C%i:%4i ",i+1, PPM_in[i+1], i+2, PPM_in[i+2]);
/*LCD_printfxy(0,0,"C1:%4i C2:%4i",PPM_in[1],PPM_in[2]);
LCD_printfxy(0,1,"C3:%4i C4:%4i",PPM_in[3],PPM_in[4]);
LCD_printfxy(0,2,"C5:%4i C6:%4i",PPM_in[5],PPM_in[6]);
LCD_printfxy(0,3,"C7:%4i C8:%4i",PPM_in[7],PPM_in[8]);
LCD_printfxy(0,3,"C7:%4i C8:%4i",PPM_in[7],PPM_in[8]);*/
break;
case 4:// Remote Control Mapping Menu Item
LCD_printfxy(0,0,"Ni:%4i Ro:%4i",PPM_in[ParamSet.ChannelAssignment[CH_NICK]],PPM_in[ParamSet.ChannelAssignment[CH_ROLL]]);
208,21 → 224,27
break;
case 9:// Compass Menu Item
LCD_printfxy(0,0,"Compass");
LCD_printfxy(0,1,"Course: %5i",CompassCourse);
LCD_printfxy(0,2,"Heading: %5i",CompassHeading);
LCD_printfxy(0,3,"OffCourse: %5i",CompassOffCourse);
LCD_printfxy(0,1,"MagHead.: %5i",CompassHeading);
LCD_printfxy(0,2,"GyroHead.: %5i",YawGyroHeadingDeg);
LCD_printfxy(0,3,"Setpoint: %5i",CompassCourse);
break;
case 10:// Poti Menu Item
for(i=0;i<4;i++) LCD_printfxy(0,i,"Poti%i: %3i",i+1, Poti[i]);
/*
LCD_printfxy(0,0,"Poti1: %3i" ,Poti[0]);
LCD_printfxy(0,1,"Poti2: %3i" ,Poti[1]);
LCD_printfxy(0,2,"Poti3: %3i" ,Poti[2]);
LCD_printfxy(0,3,"Poti4: %3i" ,Poti[3]);
*/
break;
case 11:// Poti Menu Item
for(i=0;i<4;i++) LCD_printfxy(0,i,"Poti%i: %3i",i+5,Poti[i+4]);
/*
LCD_printfxy(0,0,"Poti5: %3i" ,Poti[4]);
LCD_printfxy(0,1,"Poti6: %3i" ,Poti[5]);
LCD_printfxy(0,2,"Poti7: %3i" ,Poti[6]);
LCD_printfxy(0,3,"Poti8: %3i" ,Poti[7]);
*/
break;
case 12:// Servo Menu Item
LCD_printfxy(0,0,"Servo" );
230,22 → 252,22
LCD_printfxy(0,2,"Position: %3i",ServoNickValue/4);
LCD_printfxy(0,3,"Range:%3i-%3i",ParamSet.ServoNickMin, ParamSet.ServoNickMax);
break;
case 13://Extern Control
LCD_printfxy(0,0,"ExternControl" );
LCD_printfxy(0,1,"Ni:%4i Ro:%4i",ExternControl.Nick, ExternControl.Roll);
LCD_printfxy(0,2,"Gs:%4i Ya:%4i",ExternControl.Gas, ExternControl.Yaw);
LCD_printfxy(0,3,"Hi:%4i Cf:%4i",ExternControl.Height, ExternControl.Config);
break;
 
case 14://BL Communication errors
case 13://BL Communication errors
LCD_printfxy(0,0,"BL-Ctrl Errors" );
for(i = 0; i < 3; i++)
{
j=i<<2;
LCD_printfxy(0,1+i," %3d %3d %3d %3d ",Motor[j].State & MOTOR_STATE_ERROR_MASK,Motor[1+j].State & MOTOR_STATE_ERROR_MASK,Motor[2+j].State & MOTOR_STATE_ERROR_MASK,Motor[3+j].State & MOTOR_STATE_ERROR_MASK);
LCD_printfxy(0,i+1," %3d %3d %3d %3d ",Motor[i*4].State & MOTOR_STATE_ERROR_MASK,Motor[i*4+1].State & MOTOR_STATE_ERROR_MASK,Motor[i*4+2].State & MOTOR_STATE_ERROR_MASK,Motor[i*4+3].State & MOTOR_STATE_ERROR_MASK);
//if(i*4 > RequiredMotors) break;
}
break;
 
case 14:// new BL infos
LCD_printfxy(0,0,"BL Temperature" );
for(i = 0; i < 3; i++)
{
LCD_printfxy(0,i+1,"%3i %3i %3i %3i ",Motor[i*4].Temperature, Motor[i*4+1].Temperature, Motor[i*4+2].Temperature, Motor[i*4+3].Temperature);
//if(4 + i*4 >= RequiredMotors) break;
}
break;
case 15://BL Overview
LCD_printfxy(0,0,"BL-Ctrl found" );
for(i = 0; i < 2; i++)
258,17 → 280,7
if(Motor[10].State>>7) LCD_printfxy(8,3,"11");
if(Motor[11].State>>7) LCD_printfxy(12,3,"12");
break;
 
case 16:// new BL infos
LCD_printfxy(0,0,"BL Temperature", Capacity.MinOfMaxPWM);
for(i = 0; i < 3; i++)
{
j=i<<2;
LCD_printfxy(0,i+1,"%3i %3i %3i %3i ",Motor[j].Temperature, Motor[j+1].Temperature, Motor[j+2].Temperature, Motor[j+3].Temperature);
}
break;
 
case 17:// flight time counter
case 16:// flight time counter
LCD_printfxy(0,0,"Flight-Time");
LCD_printfxy(0,1,"Total:%5u min",FlightMinutesTotal);
LCD_printfxy(0,2,"Trip: %5u min",FlightMinutes);
279,7 → 291,6
SetParamWord(PID_FLIGHT_MINUTES, FlightMinutes);
}
break;
 
default:
if(MenuItem == MaxMenuItem) MaxMenuItem--;
MenuItem = 0;
/beta/Code Redesign killagreg/menu.h
6,7 → 6,7
 
#define DISPLAYBUFFSIZE 80
 
#define LCD_printfxy(x,y,format, args...) { DispPtr = (y) * 20 + x; _printf_P(&Menu_Putchar, PSTR(format) , ## args);}
#define LCD_printfxy(x,y,format, args...) { DispPtr = (y) * 20 + (x); _printf_P(&Menu_Putchar, PSTR(format) , ## args);}
#define LCD_printf(format, args...) { _printf_P(&Menu_Putchar, PSTR(format) , ## args);}
 
#define KEY1 0x01
/beta/Code Redesign killagreg/mk3mag.c
112,7 → 112,7
{
if(PWMCount <10) CompassHeading = 0;
else CompassHeading = ((uint32_t)(PWMCount - 10) * 1049L)/1024; // correct timebase and offset
CompassOffCourse = ((540 + CompassHeading - CompassCourse) % 360) - 180;
//CompassOffCourse = ((540 + CompassHeading - CompassCourse) % 360) - 180;
PWMTimeout = 12; // if 12 periodes long no valid PWM was detected the data are invalid
// 12 * 362 counts * 102.4 us
}
/beta/Code Redesign killagreg/rc.c
63,6 → 63,7
volatile uint8_t RC_Channels; // number of received remote control channels
volatile int16_t PPM_in[MAX_CHANNELS];
volatile int16_t PPM_diff[MAX_CHANNELS];
uint16_t PPM_Neutral = 466;
volatile uint8_t NewPpmData = 1;
volatile uint8_t RC_Quality = 0;
 
81,7 → 82,8
 
for(i=0; i<MAX_CHANNELS; i++)
{
PPM_in[i] = 0;
if(i < 5) PPM_in[i] = 0;
else PPM_in[i] = -126;
PPM_diff[i] = 0;
}
 
230,7 → 232,7
if((signal > 250) && (signal < 687))
{
// shift signal to zero symmetric range -154 to 159
signal -= 466; // offset of 1.4912 ms ??? (469 * 3.2µs = 1.5008 ms)
signal -= PPM_Neutral; // offset of 1.4912 ms ??? (469 * 3.2µs = 1.5008 ms)
// check for stable signal
if(abs(signal - ppm_in[index]) < 6)
{
300,7 → 302,7
if((signal > 250) && (signal < 687))
{
// shift signal to zero symmetric range -154 to 159
signal -= 466; // offset of 1.4912 ms ??? (469 * 3.2µs = 1.5008 ms)
signal -= PPM_Neutral; // offset of 1.4912 ms ??? (469 * 3.2µs = 1.5008 ms)
// check for stable signal
if(abs(signal - PPM_in[index]) < 6)
{
/beta/Code Redesign killagreg/rc.h
25,6 → 25,7
extern void RC_Init (void);
extern volatile int16_t PPM_in[MAX_CHANNELS]; // the RC-Signal
extern volatile int16_t PPM_diff[MAX_CHANNELS]; // the RC-Signal change per 22.5 ms
extern uint16_t PPM_Neutral; // the neutral ppm offset
extern volatile uint8_t NewPpmData; // 0 indicates a new recieved PPM Frame
extern volatile uint8_t RC_Quality; // rc signal quality indicator (0 to 200)
extern volatile uint8_t RC_Channels; // number of received channels
/beta/Code Redesign killagreg/spektrum.c
2,13 → 2,15
#include <stdlib.h>
#include <avr/interrupt.h>
#include "spektrum.h"
#include "main.h"
#include "rc.h"
#include "eeprom.h"
#include "timer0.h"
 
//#define RECEIVER_SPEKTRUM_EXP
 
// define RECEIVER_SPEKTRUM_DX7EXP or RECEIVER_SPEKTRUM_DX8EXP is set in main.h
 
 
/*
Code derived from:
 
270,7 → 272,7
{
if(RC_Channels < index) RC_Channels = index;
// Stable Signal
#ifdef RECEIVER_SPEKTRUM_EXP
#if defined (RECEIVER_SPEKTRUM_DX7EXP) || defined (RECEIVER_SPEKTRUM_DX8EXP)
if (index == 2) index = 4; // Analog channel reassigment (2 <-> 4) for logical numbering (1,2,3,4)
else if (index == 4) index = 2;
#endif
291,7 → 293,7
if(tmp > signal+1) tmp--;
else if(tmp < signal-1) tmp++;
 
#ifdef RECEIVER_SPEKTRUM_EXP
#ifdef RECEIVER_SPEKTRUM_DX7EXP
if(index == 6) // FLIGHT-MODE - The channel used for our data uplink
{
if (signal > 100) // SYNC received
328,6 → 330,44
s_exparity = ~s_exparity; // Bit = 1 -> Invert parity bit
}
}
#elif defined RECEIVER_SPEKTRUM_DX8EXP
if(index == 6) // FLIGHT-MODE - The channel used for our data uplink
{
if (signal > 100) // SYNC received
{
if (s_exdata[s_excnt] == 125) s_exparity = ~s_exparity; // Bit = 1 -> Re-Invert parity bit
if (s_excnt == 9 && ((s_exparity == 0 && s_exdata[s_excnt] == -125) || (s_exparity != 0 && s_exdata[s_excnt] == 125))) // Parity check
{
if (s_exdata[1] == 125 && s_exdata[2] == -125) PPM_in[5] = -125; // Reconstruct tripole Flight-Mode value (CH5)
else if (s_exdata[1] == -125 && s_exdata[2] == -125) PPM_in[5] = 0; // Reconstruct tripole Flight-Mode value (CH5)
else if (s_exdata[1] == -125 && s_exdata[2] == 125) PPM_in[5] = 125; // Reconstruct tripole Flight-Mode value (CH5)
 
if (s_exdata[3] == 125 && s_exdata[6] == -125) PPM_in[6] = 125; // Reconstruct tripole Elev D/R value (CH6)
else if (s_exdata[3] == -125 && s_exdata[6] == -125) PPM_in[6] = 0; // Reconstruct tripole Elev D/R value (CH6)
else if (s_exdata[3] == -125 && s_exdata[6] == 125) PPM_in[6] = -125; // Reconstruct tripole Elev D/R value (CH6)
 
if (s_exdata[7] == 125 && s_exdata[8] == -125) PPM_in[9] = -125; // Reconstruct tripole AIL D/R value (CH9)
else if (s_exdata[7] == -125 && s_exdata[8] == -125) PPM_in[9] = 0; // Reconstruct tripole AIL D/R value (CH9)
else if (s_exdata[7] == -125 && s_exdata[8] == 125) PPM_in[9] = 125; // Reconstruct tripole AIL D/R value (CH9)
 
PPM_in[10] = s_exdata[5]; // Gear (CH10)
PPM_in[12] = s_exdata[4]; // Mix (CH12)
}
 
s_excnt = 0; // Reset bitcounter
s_exparity = 0; // Reset parity bit
}
 
if (signal < 10) s_exdata[++s_excnt] = -125; // Bit = 0 -> value = -125 (min)
if (s_excnt == 10) s_excnt = 0; // Overflow protection
if (signal < -100)
{
s_exdata[s_excnt] = 125; // Bit = 1 -> value = 125 (max)
s_exparity = ~s_exparity; // Bit = 1 -> Invert parity bit
}
 
}
 
#endif
 
// calculate signal difference on good signal level
334,10 → 374,15
if(RC_Quality >= 180) PPM_diff[index] = ((tmp - PPM_in[index]) / 3) * 3;
else PPM_diff[index] = 0;
 
#ifdef RECEIVER_SPEKTRUM_EXP
#ifdef RECEIVER_SPEKTRUM_DX7EXP
if (index < 5 ) PPM_in[index] = tmp; // Update normal potis (CH1-4)
else if (index == 5) PPM_in[7] = signal; // Gear (CH7)
else if (index == 7) PPM_in[9] = signal; // Hover Throttle (CH9)
#elif defined RECEIVER_SPEKTRUM_DX8EXP
if (index < 5 ) PPM_in[index] = tmp; // Update normal potis (CH1-4)
else if (index == 7) PPM_in[7] = signal; // R Trim (CH7)
else if (index == 5) PPM_in[8] = signal; // AUX2 (CH8)
else if (index == 8) PPM_in[11] = signal;
#else
PPM_in[index] = tmp;
#endif
/beta/Code Redesign killagreg/spi.c
172,7 → 172,39
int16_t NCCamNick = 0; // in 0.1°
int32_t NCSetPointHeight = 0;
int8_t NCAltitudeSpeed = 0;
uint8_t NCGPSModeCharacter = ' ';
uint8_t NCGPSAidMode = 0;
 
// NC error codes
uint8_t NCErrorCode = 0;
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
const int8_t PROGMEM NC_ERROR_TEXT[MAX_ERR_NUMBER][17] =
{
//0123456789123456
"No Error \0", // 0
"Not compatible \0", // 1
"MK3Mag not compa\0", // 2
"No FC communicat\0", // 3
"MK3Mag communica\0", // 4
"GPS communicatio\0", // 5
"compass value \0", // 6
"RC Signal lost \0", // 7
"FC spi rx error \0", // 8
"No NC communicat\0", // 9
"FC Nick Gyro \0", // 10
"FC Roll Gyro \0", // 11
"FC Yaw Gyro \0", // 12
"FC Nick ACC \0", // 13
"FC Roll ACC \0", // 14
"FC Z-ACC \0", // 15
"Pressure sensor \0", // 16
"FC FC->BL_Ctrl \0", // 17
"Bl Missing \0", // 18
"Mixer Error \0", // 19
"Carefree Error \0", // 20
"GPS Fix list \0" // 21
};
#endif
 
vector16_t MagVec = {0,0,0};
 
240,7 → 272,7
ToNaviCtrl.Param.Byte[8] = FC_StatusFlags;
FC_StatusFlags &= ~(FC_STATUS_CALIBRATE | FC_STATUS_START); // calibrate and start are temporal states that are cleared immediately after transmitting
ToNaviCtrl.Param.Byte[9] = GetActiveParamSet();
ToNaviCtrl.Param.Byte[10] = ControlHeading; // 0 to 180 in stepsof 2°
ToNaviCtrl.Param.Byte[10] = ParamSet.ComingHomeAltitude;
ToNaviCtrl.Param.Byte[11] = FC_StatusFlags2;
break;
 
255,7 → 287,7
ToNaviCtrl.Param.Byte[7] = ParamSet.NaviStickThreshold;
ToNaviCtrl.Param.Byte[8] = ParamSet.NaviOperatingRadius;
ToNaviCtrl.Param.Byte[9] = ParamSet.NaviWindCorrection;
ToNaviCtrl.Param.Byte[10] = ParamSet.NaviSpeedCompensation;
ToNaviCtrl.Param.Byte[10] = ParamSet.NaviAccCompensation;
ToNaviCtrl.Param.Byte[11] = ParamSet.NaviAngleLimitation;
break;
 
265,6 → 297,8
ToNaviCtrl.Param.Byte[4] = UBat; // 0.1V
ToNaviCtrl.Param.Byte[5] = ParamSet.LowVoltageWarning; //0.1V
ToNaviCtrl.Param.Byte[6] = VarioCharacter;
ToNaviCtrl.Param.Byte[7] = FCParam.Config0;
ToNaviCtrl.Param.Byte[8] = FCParam.Config2;
break;
 
case SPI_FCCMD_STICK:
312,10 → 346,13
ToNaviCtrl.Param.Byte[3] = NC_SPI_COMPATIBLE;
ToNaviCtrl.Param.Byte[4] = BoardRelease;
ToNaviCtrl.Param.Byte[5] = UART_VersionInfo.HardwareError[0];
UART_VersionInfo.HardwareError[0] = 0; // clear all errors after submission
ToNaviCtrl.Param.Byte[6] = UART_VersionInfo.HardwareError[1];
UART_VersionInfo.HardwareError[1] &= FC_ERROR1_MIXER; // clear all except MIXER error
ToNaviCtrl.Param.Byte[7] = UART_VersionInfo.HardwareError[2];
ToNaviCtrl.Param.Byte[8] = UART_VersionInfo.HardwareError[3];
ToNaviCtrl.Param.Byte[9] = UART_VersionInfo.HardwareError[4];
ToNaviCtrl.Param.Byte[10] = ParamSet.OrientationAngle;
break;
 
case SPI_FCCMD_SERVOS:
347,9 → 384,9
GPSStickRoll = FromNaviCtrl.GPSStickRoll;
}
// update compass readings
MagVec.x = FromNaviCtrl.MagVecX;
MagVec.y = FromNaviCtrl.MagVecY;
MagVec.z = FromNaviCtrl.MagVecZ;
//MagVec.x = FromNaviCtrl.MagVecX;
//MagVec.y = FromNaviCtrl.MagVecY;
//MagVec.z = FromNaviCtrl.MagVecZ;
 
// update compass readings
if(FromNaviCtrl.CompassHeading <= 360)
356,12 → 393,14
{
CompassHeading = FromNaviCtrl.CompassHeading;
}
if(CompassHeading < 0) CompassOffCourse = 0;
else CompassOffCourse = ((540 + CompassHeading - CompassCourse) % 360) - 180;
//if(CompassHeading < 0) CompassOffCourse = 0;
//else CompassOffCourse = ((540 + CompassHeading - CompassCourse) % 360) - 180;
 
// NaviCtrl wants to beep?
if (FromNaviCtrl.BeepTime > BeepTime /*&& !CompassCalState*/) BeepTime = FromNaviCtrl.BeepTime;
 
#define FLAG_GPS_AID 0x01
 
switch (FromNaviCtrl.Command)
{
 
373,6 → 412,7
NCGpsZ = FromNaviCtrl.Param.sByte[4];
NCRotate_C = FromNaviCtrl.Param.sByte[5];
NCRotate_S = FromNaviCtrl.Param.sByte[6];
if(FromNaviCtrl.Param.Byte[7] & FLAG_GPS_AID) NCGPSAidMode = 1; else NCGPSAidMode = 0;
if(CareFree && FromNaviCtrl.Param.sInt[4] >= 0)
{ // if CareFree then NC can set compass course and nick offset
CompassCourse = FromNaviCtrl.Param.sInt[4];
392,8 → 432,9
NC_Version.Compatible = FromNaviCtrl.Param.Byte[3];
NC_Version.Hardware = FromNaviCtrl.Param.Byte[4];
DebugOut.Status[0] |= FromNaviCtrl.Param.Byte[5];
NCErrorCode = FromNaviCtrl.Param.Byte[6];
DebugOut.Status[1] = (DebugOut.Status[1] & (0x01|0x02)) | (FromNaviCtrl.Param.Byte[6] & (0x04 | 0x08));
NCErrorCode = FromNaviCtrl.Param.Byte[7];
NCGPSModeCharacter = FromNaviCtrl.Param.Byte[8];
break;
 
case SPI_NCCMD_GPSINFO:
408,6 → 449,12
NCSetPointHeight = (int32_t)FromNaviCtrl.Param.sInt[5] * 10; // in steps of 1cm
break;
 
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
case SPI_NCCMD_HOTT_DATA:
if(ParamSet.Receiver == RECEIVER_HOTT) NC_Fills_HoTT_Telemety();
break;
#endif
 
default:
break;
}
/beta/Code Redesign killagreg/spi.h
2,8 → 2,8
#ifndef _SPI_H
#define _SPI_H
 
//#include <util/delay.h>
#include <inttypes.h>
#include <avr/pgmspace.h>
#include "vector.h"
 
 
44,12 → 44,10
 
 
 
#define SPI_NCCMD_OSD_DATA 100
#define SPI_NCCMD_GPS_POS 101
#define SPI_NCCMD_GPS_TARGET 102
#define SPI_NCCMD_KALMAN 103
#define SPI_NCCMD_VERSION 104
#define SPI_NCCMD_GPSINFO 105
#define SPI_NCCMD_HOTT_DATA 106
 
typedef struct
{
58,8 → 56,10
int16_t GPSStickRoll;
int16_t GPS_Yaw;
int16_t CompassHeading;
int16_t MagVecX;
int16_t MagVecY;
// int16_t MagVecX;
// int16_t MagVecY;
int16_t AccErrorN;
int16_t AccErrorR;
int16_t MagVecZ;
int16_t NCStatus;
uint16_t BeepTime;
105,7 → 105,12
#define FLAG_DIFFSOLN 0x02 // (is DGPS used)
#define FLAG_WKNSET 0x04 // (is Week Number valid)
#define FLAG_TOWSET 0x08 // (is Time of Week valid)
#define FLAG_GPS_NAVIGATION_ACT 0x10 // gps navigation active
#define FLAG_RES1 0x20
#define FLAG_RES2 0x40
#define FLAG_RES3 0x80
 
 
typedef struct
{
uint8_t Flags; // Status Flags
125,10 → 130,18
extern int16_t NCCamNick;
extern int32_t NCSetPointHeight;
extern int8_t NCAltitudeSpeed;
extern uint8_t NCErrorCode;
extern uint8_t NCGPSModeCharacter;
extern uint8_t NCGPSAidMode;
extern vector16_t MagVec;
 
// NC error codes
extern uint8_t NCErrorCode;
 
#if (defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__))
#define MAX_ERR_NUMBER 22
extern const int8_t PROGMEM NC_ERROR_TEXT[MAX_ERR_NUMBER][17];
#endif
 
void SPI_MasterInit(void);
void SPI_StartTransmitPacket(void);
void SPI_TransmitByte(void);
/beta/Code Redesign killagreg/timer0.c
196,7 → 196,7
 
#ifndef USE_NAVICTRL
// update compass value if this option is enabled in the settings
if(ParamSet.Config0 & (CFG0_COMPASS_ACTIVE|CFG0_GPS_ACTIVE))
if(FCParam.Config0 & (CFG0_COMPASS_ACTIVE|CFG0_GPS_ACTIVE))
{
#ifdef USE_MK3MAG
MK3MAG_Update(); // read out mk3mag pwm
/beta/Code Redesign killagreg/timer2.c
330,7 → 330,7
RemainingPulse = PPM_STOPPULSE;
// accumulate time for correct sync gap
ServoFrameTime += RemainingPulse;
if(ServoActive && RC_Quality > 180) HEF4017R_OFF; // disable HEF4017 reset
if(ServoActive && RC_Quality) HEF4017R_OFF; // disable HEF4017 reset
else HEF4017R_ON; // enable reset
ServoIndex++; // change to next servo channel
if(ServoIndex > ParamSet.ServoRefresh)
/beta/Code Redesign killagreg/uart0.c
71,6 → 71,10
#include "libfc.h"
#include "debug.h"
 
//Baud rate of the USART
#define USART0_BAUD 57600L
#define USART0_BAUD_HOTT 19700L
#define USART0_BAUD_JETI 38400L
 
#define FC_ADDRESS 1
#define NC_ADDRESS 2
102,7 → 106,7
volatile uint8_t ReceivedBytes = 0;
volatile uint8_t *pRxData = 0;
volatile uint8_t RxDataLen = 0;
volatile uint8_t JetiUpdateModeActive = 0;
volatile uint8_t ReceiverUpdateModeActive = 0; // 1 = Update 2 = JetiBox-Simulation
volatile uint8_t JetiByteBuffer = 0;
 
uint8_t PcAccess = 100;
164,7 → 168,7
"Capacity [mAh] ",
"Height Setpoint ",
"25 ", //25
"26 ",
"26 ", //CPU Overload
"CompassSetPoint ",
"I2C-Error ",
"BL Limit ",
291,13 → 295,13
 
c = UDR0; // catch the received byte
 
if(JetiUpdateModeActive == 1)
{ // forward byte direct to UART1
if(ReceiverUpdateModeActive == 1)
{ // forward byte direct to UART1 (update)
UDR1 = c;
return;
}
if(JetiUpdateModeActive == 2)
{ // buffer input byte for later forwarding
if(ReceiverUpdateModeActive == 2)
{ // buffer input byte for later forwarding (JetiBox-Simulation)
JetiByteBuffer = c;
return;
}
502,7 → 506,7
#ifdef USE_MK3MAG
case 'K':// compass value
CompassHeading = ((Heading_t *)pRxData)->Heading;
CompassOffCourse = ((540 + CompassHeading - CompassCourse) % 360) - 180;
//CompassOffCourse = ((540 + CompassHeading - CompassCourse) % 360) - 180;
break;
#endif
 
656,11 → 660,10
break;
 
case 'j':
if(FC_StatusFlags & FC_STATUS_MOTOR_RUN) break; // ignore receiver update when motors are running
tempchar1 = LIBFC_GetCPUType();
if((tempchar1 == CPU_ATMEGA644P) || (tempchar1 == CPU_ATMEGA1284P))
{
uint16_t ubrr = (uint16_t) ((uint32_t) F_CPU/ (8 * 38400L) - 1);
 
// disable all interrupts before configuration
cli();
 
676,10 → 679,20
while ( UCSR1A & (1<<RXC1) ) UDR1;
while ( UCSR0A & (1<<RXC0) ) UDR0;
 
if (pRxData[0] == 0)
if (pRxData[0] == 1)
{
JetiUpdateModeActive = 1;
ReceiverUpdateModeActive = 2;
}
else
{ // Jeti or HOTT update
 
ReceiverUpdateModeActive = 1;
 
// calculate baudrate register
uint16_t ubrr;
if(pRxData[0] == 100) ubrr = (uint16_t) ((uint32_t) F_CPU/(8 * USART0_BAUD_HOTT) - 1); // HoTT
else ubrr = (uint16_t) ((uint32_t) F_CPU/(8 * USART0_BAUD_JETI) - 1); // Jeti
 
// UART0 & UART1 set baudrate
UBRR1H = (uint8_t)(ubrr>>8);
UBRR1L = (uint8_t)ubrr;
693,7 → 706,6
UCSR1C |= (1 << UCSZ11);
UCSR1C |= (1 << UCSZ10);
}
else JetiUpdateModeActive = 2;
 
// UART1 clear 9th bit
UCSR1B &= ~(1<<TXB81);
/beta/Code Redesign killagreg/uart0.h
9,10 → 9,6
 
#include <inttypes.h>
 
//Baud rate of the USART
#define USART0_BAUD 57600
 
 
extern void USART0_Init (void);
extern void USART0_TransmitTxData(void);
extern void USART0_ProcessRxData(void);
28,7 → 24,7
extern uint8_t MotorTest_Active;
extern uint8_t MotorTest[16];
 
extern volatile uint8_t JetiUpdateModeActive;
extern volatile uint8_t ReceiverUpdateModeActive;
extern volatile uint8_t JetiByteBuffer;
 
typedef struct
/beta/Code Redesign killagreg/version.txt
448,12 → 448,48
- Kanaloffset für Potis von 110 auf 127 erhöht, damit es gleich ist mit allen anderen Kanälen
- POI-Richtung (Soll-Himmelsrichtung) bezieht sich auf den Kamera-Winkel
 
0.85 H.Buss
- Variable "JetiBeep" wird gelöscht, wenn an den Empfänger gesendet wurde
- wenn GPS deaktiviert ist, keinen Fehler bringen, wenn GPS fehlt. Auch dann nicht piepsen
- GPS-Sollwertverschiebung
- Empfangs-Piepen unterdrücken -> einstellbar
- MotorSmooth einstellbar
- Höhenregler: keine 'harte' IstWert-Übernahme bei Bewegen des Sticks in die Hoover-Position
- Coming Home mit Höhenvorgabe
- Coming Home als Failsafe
- Einführung des GPS-Characters (- / W H D P)
- neue Fehlermeldung: NC_ErrorCode = 9 "ERR: no NC communication"
- Klartext bei den Jeti-Fehlermeldungen
- Jeti-Beep "3*kurz" bei NC-Errors
- Jeti-LCD-Aufruf nur noch alle 300ms, weil die Werte zu unruhig waren
- Mixer-Settings werden nicht gelöscht, wenn sich die Parameter-Revision ändert
- GPS-Angle limit von 100 auf 140
- GPS-I-Limit von 75 auf 85
- GAS-Offset von 120 auf 127 erhöht, damit es für alle Kanäle gleich ist
- EE_Parameter.Hoehe_StickNeutralPoint auf Werte zwischen 80 und 180 begrenzt (70/150?)
- PPM_Neutral eingeführt, um den Offset bei HoTT auszugleichen;
- LED_Update() nun nur noch alle 20ms, weil die schnellste Ausgabe (bei Potivorgabe) ohnehin nur 40ms sind
- Jeti & HoTT: Nur beim Fehler auch JetiBeep, wenn die Motoren laufen -> sonst nervt das bei der Fehlerbehebung (Compass-Kalibrieren usw.)
- Error-Text auch im virtuellen Display des Koptertools
- virtuelles LCD-Menü:
- "ExternControl" aus Platzgründen aus dem virtuellen LCD-Menü entfernt.
- keine BL-Temperaturen und I2C-Fehler anzeigen, wenn die BL-Regler nicht verwendet werden
- nach dem Gieren nicht den Ersatzkompass auf den Kompasswert stellen, die Umschaltung war zu hart
- ACC Correction eingeführt
- I2C Fehler kamen nicht bei der NC an, weil die zu kurz waren
- Fehlermeldungen stehen jetzt mind. so lange an, bis sie an die Nc gesendet wurden
- neue Fehlermeldung: "GPS Fix lost"
- LED: Schaltfläche "nur bei Motor start" bei beiden getrennt
- Ausbau der HoTT-Telemetrie
- Variable "KompassRichtung" entfernt
- ErsatzKompassInGrad sinvoll genutzt
- HoTT-Update per Uart-Durchschleifen
- AltitudeSetpointTrimming eingeführt
- Vario-Anzeige für HoT
 
Anpassungen bzgl. V0.85h
G.Stobrawa 31.08.2011 (trunk SVN 1943, private SVN 551)
 
 
Anpassungen bzgl. V0.83
G.Stobrawa 22.03.2011
 
- Code stärker modularisiert und restrukturiert
- viele Kommentare zur Erklärug eingefügt
- konsequent englische Variablennamen