/branches/dongfang_FC_rewrite/attitude.c |
---|
74,10 → 74,6 |
// For Servo_On / Off |
// #include "timer2.h" |
#ifdef USE_MK3MAG |
#include "mk3mag.h" |
#include "gps.h" |
#endif |
#define CHECK_MIN_MAX(value, min, max) {if(value < min) value = min; else if(value > max) value = max;} |
/* |
113,13 → 109,22 |
int readingHeight = 0; |
// compass course |
int16_t compassHeading = -1; // negative angle indicates invalid data. |
int16_t compassCourse = -1; |
int16_t compassOffCourse = 0; |
uint16_t updateCompassCourse = 0; |
uint8_t compassCalState = 0; |
uint16_t badCompassHeading = 500; |
// Yaw angle and compass stuff. |
// This is updated/written from MM3. Negative angle indicates invalid data. |
int16_t compassHeading = -1; |
// This is NOT updated from MM3. Negative angle indicates invalid data. |
int16_t compassCourse = -1; |
// The difference between the above 2 (heading - course) on a -180..179 degree interval. |
// Not necessary. Never read anywhere. |
// int16_t compassOffCourse = 0; |
uint8_t updateCompassCourse = 0; |
uint8_t compassCalState = 0; |
uint16_t ignoreCompassTimer = 500; |
int32_t yawGyroHeading; // Yaw Gyro Integral supported by compass |
int16_t yawGyroDrift; |
127,15 → 132,15 |
#define PITCHROLLOVER360 (GYRO_DEG_FACTOR_PITCHROLL * 360L) |
#define YAWOVER360 (GYRO_DEG_FACTOR_YAW * 360L) |
int16_t correctionSum[2] = {0,0}; |
int16_t correctionSum[2] = { 0, 0 }; |
// For NaviCTRL use. |
int16_t averageAcc[2] = {0,0}, averageAccCount = 0; |
int16_t averageAcc[2] = { 0, 0 }, averageAccCount = 0; |
/* |
* Experiment: Compensating for dynamic-induced gyro biasing. |
*/ |
int16_t driftComp[2] = {0,0}, driftCompYaw = 0; |
int16_t driftComp[2] = { 0, 0 }, driftCompYaw = 0; |
// int16_t savedDynamicOffsetPitch = 0, savedDynamicOffsetRoll = 0; |
// int32_t dynamicCalPitch, dynamicCalRoll, dynamicCalYaw; |
// int16_t dynamicCalCount; |
151,15 → 156,15 |
************************************************************************/ |
int32_t getAngleEstimateFromAcc(uint8_t axis) { |
return GYRO_ACC_FACTOR * (int32_t)filteredAcc[axis]; |
return GYRO_ACC_FACTOR * (int32_t) filteredAcc[axis]; |
} |
void setStaticAttitudeAngles(void) { |
#ifdef ATTITUDE_USE_ACC_SENSORS |
angle[PITCH] = getAngleEstimateFromAcc(PITCH); |
angle[ROLL] = getAngleEstimateFromAcc(ROLL); |
angle[PITCH] = getAngleEstimateFromAcc(PITCH); |
angle[ROLL] = getAngleEstimateFromAcc(ROLL); |
#else |
angle[PITCH] = angle[ROLL] = 0; |
angle[PITCH] = angle[ROLL] = 0; |
#endif |
} |
167,29 → 172,29 |
* Neutral Readings |
************************************************************************/ |
void attitude_setNeutral(void) { |
// Servo_Off(); // disable servo output. TODO: Why bother? The servos are going to make a jerk anyway. |
dynamicParams.AxisCoupling1 = dynamicParams.AxisCoupling2 = 0; |
// Servo_Off(); // disable servo output. TODO: Why bother? The servos are going to make a jerk anyway. |
dynamicParams.AxisCoupling1 = dynamicParams.AxisCoupling2 = 0; |
driftComp[PITCH] = driftComp[ROLL] = yawGyroDrift = driftCompYaw = 0; |
correctionSum[PITCH] = correctionSum[ROLL] = 0; |
// Calibrate hardware. |
analog_calibrate(); |
// reset gyro readings |
// rate_ATT[PITCH] = rate_ATT[ROLL] = yawRate = 0; |
driftComp[PITCH] = driftComp[ROLL] = yawGyroDrift = driftCompYaw = 0; |
correctionSum[PITCH] = correctionSum[ROLL] = 0; |
// reset gyro integrals to acc guessing |
setStaticAttitudeAngles(); |
yawAngleDiff = 0; |
// Calibrate hardware. |
analog_calibrate(); |
// update compass course to current heading |
compassCourse = compassHeading; |
// reset gyro readings |
// rate_ATT[PITCH] = rate_ATT[ROLL] = yawRate = 0; |
// Inititialize YawGyroIntegral value with current compass heading |
yawGyroHeading = (int32_t)compassHeading * GYRO_DEG_FACTOR_YAW; |
// reset gyro integrals to acc guessing |
setStaticAttitudeAngles(); |
yawAngleDiff = 0; |
// Servo_On(); //enable servo output |
// update compass course to current heading |
compassCourse = compassHeading; |
// Inititialize YawGyroIntegral value with current compass heading |
yawGyroHeading = (int32_t) compassHeading * GYRO_DEG_FACTOR_YAW; |
// Servo_On(); //enable servo output |
} |
/************************************************************************ |
199,22 → 204,24 |
* The rate variable end up in a range of about [-1024, 1023]. |
*************************************************************************/ |
void getAnalogData(void) { |
uint8_t axis; |
for (axis=PITCH; axis <=ROLL; axis++) { |
rate_PID[axis] = (gyro_PID[axis] + driftComp[axis]) / HIRES_GYRO_INTEGRATION_FACTOR; |
rate_ATT[axis] = (gyro_ATT[axis] + driftComp[axis]) / HIRES_GYRO_INTEGRATION_FACTOR; |
differential[axis] = gyroD[axis]; |
averageAcc[axis] += acc[axis]; |
} |
uint8_t axis; |
averageAccCount++; |
yawRate = yawGyro + driftCompYaw; |
for (axis = PITCH; axis <= ROLL; axis++) { |
rate_PID[axis] = (gyro_PID[axis] + driftComp[axis]) |
/ HIRES_GYRO_INTEGRATION_FACTOR; |
rate_ATT[axis] = (gyro_ATT[axis] + driftComp[axis]) |
/ HIRES_GYRO_INTEGRATION_FACTOR; |
differential[axis] = gyroD[axis]; |
averageAcc[axis] += acc[axis]; |
} |
// We are done reading variables from the analog module. |
// Interrupt-driven sensor reading may restart. |
analogDataReady = 0; |
analog_start(); |
averageAccCount++; |
yawRate = yawGyro + driftCompYaw; |
// We are done reading variables from the analog module. |
// Interrupt-driven sensor reading may restart. |
analogDataReady = 0; |
analog_start(); |
} |
/* |
224,54 → 231,59 |
* changed accordingly. |
*/ |
void trigAxisCoupling(void) { |
int16_t cospitch = int_cos(angle[PITCH]); |
int16_t cosroll = int_cos(angle[ROLL]); |
int16_t sinroll = int_sin(angle[ROLL]); |
int16_t tanpitch = int_tan(angle[PITCH]); |
int16_t cospitch = int_cos(angle[PITCH]); |
int16_t cosroll = int_cos(angle[ROLL]); |
int16_t sinroll = int_sin(angle[ROLL]); |
int16_t tanpitch = int_tan(angle[PITCH]); |
#define ANTIOVF 512 |
ACRate[PITCH] = ((int32_t) rate_ATT[PITCH] * cosroll - (int32_t)yawRate * sinroll) / (int32_t)MATH_UNIT_FACTOR; |
ACRate[ROLL] = rate_ATT[ROLL] + (((int32_t)rate_ATT[PITCH] * sinroll / ANTIOVF * tanpitch + (int32_t)yawRate * int_cos(angle[ROLL]) / ANTIOVF * tanpitch) / ((int32_t)MATH_UNIT_FACTOR / ANTIOVF * MATH_UNIT_FACTOR)); |
ACYawRate = ((int32_t) rate_ATT[PITCH] * sinroll) / cospitch + ((int32_t)yawRate * cosroll) / cospitch; |
ACRate[PITCH] = ((int32_t) rate_ATT[PITCH] * cosroll - (int32_t) yawRate |
* sinroll) / (int32_t) MATH_UNIT_FACTOR; |
ACRate[ROLL] = rate_ATT[ROLL] + (((int32_t) rate_ATT[PITCH] * sinroll |
/ ANTIOVF * tanpitch + (int32_t) yawRate * int_cos(angle[ROLL]) |
/ ANTIOVF * tanpitch) / ((int32_t) MATH_UNIT_FACTOR / ANTIOVF |
* MATH_UNIT_FACTOR)); |
ACYawRate = ((int32_t) rate_ATT[PITCH] * sinroll) / cospitch |
+ ((int32_t) yawRate * cosroll) / cospitch; |
} |
// 480 usec with axis coupling - almost no time without. |
void integrate(void) { |
// First, perform axis coupling. If disabled xxxRate is just copied to ACxxxRate. |
uint8_t axis; |
if(!looping && (staticParams.GlobalConfig & CFG_AXIS_COUPLING_ACTIVE)) { |
// The rotary rate limiter bit is abused for selecting axis coupling algorithm instead. |
trigAxisCoupling(); |
} else { |
ACRate[PITCH] = rate_ATT[PITCH]; |
ACRate[ROLL] = rate_ATT[ROLL]; |
ACYawRate = yawRate; |
} |
// First, perform axis coupling. If disabled xxxRate is just copied to ACxxxRate. |
uint8_t axis; |
if (!looping && (staticParams.GlobalConfig & CFG_AXIS_COUPLING_ACTIVE)) { |
// The rotary rate limiter bit is abused for selecting axis coupling algorithm instead. |
trigAxisCoupling(); |
} else { |
ACRate[PITCH] = rate_ATT[PITCH]; |
ACRate[ROLL] = rate_ATT[ROLL]; |
ACYawRate = yawRate; |
} |
/* |
* Yaw |
* Calculate yaw gyro integral (~ to rotation angle) |
* Limit yawGyroHeading proportional to 0 deg to 360 deg |
*/ |
yawGyroHeading += ACYawRate; |
yawAngleDiff += yawRate; |
if(yawGyroHeading >= YAWOVER360) { |
yawGyroHeading -= YAWOVER360; // 360 deg. wrap |
} else if(yawGyroHeading < 0) { |
yawGyroHeading += YAWOVER360; |
} |
/* |
* Yaw |
* Calculate yaw gyro integral (~ to rotation angle) |
* Limit yawGyroHeading proportional to 0 deg to 360 deg |
*/ |
yawGyroHeading += ACYawRate; |
yawAngleDiff += yawRate; |
/* |
* Pitch axis integration and range boundary wrap. |
*/ |
for (axis=PITCH; axis<=ROLL; axis++) { |
angle[axis] += ACRate[axis]; |
if(angle[axis] > PITCHROLLOVER180) { |
angle[axis] -= PITCHROLLOVER360; |
} else if (angle[axis] <= -PITCHROLLOVER180) { |
angle[axis] += PITCHROLLOVER360; |
} |
} |
if (yawGyroHeading >= YAWOVER360) { |
yawGyroHeading -= YAWOVER360; // 360 deg. wrap |
} else if (yawGyroHeading < 0) { |
yawGyroHeading += YAWOVER360; |
} |
/* |
* Pitch axis integration and range boundary wrap. |
*/ |
for (axis = PITCH; axis <= ROLL; axis++) { |
angle[axis] += ACRate[axis]; |
if (angle[axis] > PITCHROLLOVER180) { |
angle[axis] -= PITCHROLLOVER360; |
} else if (angle[axis] <= -PITCHROLLOVER180) { |
angle[axis] += PITCHROLLOVER360; |
} |
} |
} |
/************************************************************************ |
282,57 → 294,60 |
* That should only be necessary with drifty gyros like ENC-03. |
************************************************************************/ |
void correctIntegralsByAcc0thOrder(void) { |
// TODO: Consider changing this to: Only correct when integrals are less than ...., or only correct when angular velocities |
// are less than ....., or reintroduce Kalman. |
// Well actually the Z axis acc. check is not so silly. |
uint8_t axis; |
int32_t correction; |
if(!looping && acc[Z] >= -dynamicParams.UserParams[7] && acc[Z] <= dynamicParams.UserParams[7]) { |
DebugOut.Digital[0] |= DEBUG_ACC0THORDER; |
uint8_t permilleAcc = staticParams.GyroAccFactor; // NOTE!!! The meaning of this value has changed!! |
uint8_t debugFullWeight = 1; |
int32_t accDerived; |
if((controlYaw < -64) || (controlYaw > 64)) { // reduce further if yaw stick is active |
permilleAcc /= 2; |
debugFullWeight = 0; |
} |
// TODO: Consider changing this to: Only correct when integrals are less than ...., or only correct when angular velocities |
// are less than ....., or reintroduce Kalman. |
// Well actually the Z axis acc. check is not so silly. |
uint8_t axis; |
int32_t correction; |
if (!looping && acc[Z] >= -dynamicParams.UserParams[7] && acc[Z] |
<= dynamicParams.UserParams[7]) { |
DebugOut.Digital[0] |= DEBUG_ACC0THORDER; |
if((maxControl[PITCH] > 64) || (maxControl[ROLL] > 64)) { // reduce effect during stick commands |
permilleAcc /= 2; |
debugFullWeight = 0; |
} |
if (debugFullWeight) |
DebugOut.Digital[1] |= DEBUG_ACC0THORDER; |
else |
DebugOut.Digital[1] &= ~DEBUG_ACC0THORDER; |
uint8_t permilleAcc = staticParams.GyroAccFactor; // NOTE!!! The meaning of this value has changed!! |
uint8_t debugFullWeight = 1; |
int32_t accDerived; |
/* |
* Add to each sum: The amount by which the angle is changed just below. |
*/ |
for (axis=PITCH; axis<=ROLL; axis++) { |
accDerived = getAngleEstimateFromAcc(axis); |
DebugOut.Analog[9 + axis] = (10 * accDerived) / GYRO_DEG_FACTOR_PITCHROLL; |
if ((controlYaw < -64) || (controlYaw > 64)) { // reduce further if yaw stick is active |
permilleAcc /= 2; |
debugFullWeight = 0; |
} |
// 1000 * the correction amount that will be added to the gyro angle in next line. |
correction = angle[axis]; //(permilleAcc * (accDerived - angle[axis])) / 1000; |
angle[axis] = ((int32_t)(1000L - permilleAcc) * angle[axis] + (int32_t)permilleAcc * accDerived) / 1000L; |
correctionSum[axis] += angle[axis] - correction; |
DebugOut.Analog[16+axis] = angle[axis] - correction; |
} |
} else { |
DebugOut.Digital[0] &= ~DEBUG_ACC0THORDER; |
DebugOut.Digital[1] &= ~DEBUG_ACC0THORDER; |
DebugOut.Analog[9] = 0; |
DebugOut.Analog[10] = 0; |
if ((maxControl[PITCH] > 64) || (maxControl[ROLL] > 64)) { // reduce effect during stick commands |
permilleAcc /= 2; |
debugFullWeight = 0; |
} |
DebugOut.Analog[16] = 0; |
DebugOut.Analog[17] = 0; |
// experiment: Kill drift compensation updates when not flying smooth. |
correctionSum[PITCH] = correctionSum[ROLL] = 0; |
} |
if (debugFullWeight) |
DebugOut.Digital[1] |= DEBUG_ACC0THORDER; |
else |
DebugOut.Digital[1] &= ~DEBUG_ACC0THORDER; |
/* |
* Add to each sum: The amount by which the angle is changed just below. |
*/ |
for (axis = PITCH; axis <= ROLL; axis++) { |
accDerived = getAngleEstimateFromAcc(axis); |
DebugOut.Analog[9 + axis] = (10 * accDerived) |
/ GYRO_DEG_FACTOR_PITCHROLL; |
// 1000 * the correction amount that will be added to the gyro angle in next line. |
correction = angle[axis]; //(permilleAcc * (accDerived - angle[axis])) / 1000; |
angle[axis] = ((int32_t) (1000L - permilleAcc) * angle[axis] |
+ (int32_t) permilleAcc * accDerived) / 1000L; |
correctionSum[axis] += angle[axis] - correction; |
DebugOut.Analog[16 + axis] = angle[axis] - correction; |
} |
} else { |
DebugOut.Digital[0] &= ~DEBUG_ACC0THORDER; |
DebugOut.Digital[1] &= ~DEBUG_ACC0THORDER; |
DebugOut.Analog[9] = 0; |
DebugOut.Analog[10] = 0; |
DebugOut.Analog[16] = 0; |
DebugOut.Analog[17] = 0; |
// experiment: Kill drift compensation updates when not flying smooth. |
correctionSum[PITCH] = correctionSum[ROLL] = 0; |
} |
} |
/************************************************************************ |
348,108 → 363,127 |
// 2 times / sec. = 488/2 |
#define DRIFTCORRECTION_TIME 256L |
void driftCorrection(void) { |
static int16_t timer = DRIFTCORRECTION_TIME; |
int16_t deltaCorrection; |
uint8_t axis; |
if (! --timer) { |
timer = DRIFTCORRECTION_TIME; |
for (axis=PITCH; axis<=ROLL; axis++) { |
// Take the sum of corrections applied, add it to delta |
deltaCorrection = (correctionSum[axis] * HIRES_GYRO_INTEGRATION_FACTOR + DRIFTCORRECTION_TIME / 2) / DRIFTCORRECTION_TIME; |
// Add the delta to the compensation. So positive delta means, gyro should have higher value. |
driftComp[axis] += deltaCorrection / staticParams.GyroAccTrim; |
CHECK_MIN_MAX(driftComp[axis], -staticParams.DriftComp, staticParams.DriftComp); |
// DebugOut.Analog[11 + axis] = correctionSum[axis]; |
static int16_t timer = DRIFTCORRECTION_TIME; |
int16_t deltaCorrection; |
uint8_t axis; |
if (!--timer) { |
timer = DRIFTCORRECTION_TIME; |
for (axis = PITCH; axis <= ROLL; axis++) { |
// Take the sum of corrections applied, add it to delta |
deltaCorrection = (correctionSum[axis] |
* HIRES_GYRO_INTEGRATION_FACTOR + DRIFTCORRECTION_TIME / 2) |
/ DRIFTCORRECTION_TIME; |
// Add the delta to the compensation. So positive delta means, gyro should have higher value. |
driftComp[axis] += deltaCorrection / staticParams.GyroAccTrim; |
CHECK_MIN_MAX(driftComp[axis], -staticParams.DriftComp, staticParams.DriftComp); |
// DebugOut.Analog[11 + axis] = correctionSum[axis]; |
DebugOut.Analog[18+axis] = deltaCorrection / staticParams.GyroAccTrim; |
DebugOut.Analog[28+axis] = driftComp[axis]; |
DebugOut.Analog[18 + axis] = deltaCorrection |
/ staticParams.GyroAccTrim; |
DebugOut.Analog[28 + axis] = driftComp[axis]; |
correctionSum[axis] = 0; |
} |
} |
correctionSum[axis] = 0; |
} |
} |
} |
/************************************************************************ |
* Main procedure. |
************************************************************************/ |
void calculateFlightAttitude(void) { |
// part1: 550 usec. |
// part1a: 550 usec. |
// part1b: 60 usec. |
getAnalogData(); |
// end part1b |
integrate(); |
// end part1a |
void calculateFlightAttitude(void) { |
// part1: 550 usec. |
// part1a: 550 usec. |
// part1b: 60 usec. |
getAnalogData(); |
// end part1b |
integrate(); |
// end part1a |
DebugOut.Analog[6] = ACRate[PITCH]; |
DebugOut.Analog[7] = ACRate[ROLL]; |
DebugOut.Analog[8] = ACYawRate; |
DebugOut.Analog[3] = rate_PID[PITCH]; |
DebugOut.Analog[4] = rate_PID[ROLL]; |
DebugOut.Analog[5] = yawRate; |
DebugOut.Analog[6] = ACRate[PITCH]; |
DebugOut.Analog[7] = ACRate[ROLL]; |
DebugOut.Analog[8] = ACYawRate; |
DebugOut.Analog[3] = rate_PID[PITCH]; |
DebugOut.Analog[4] = rate_PID[ROLL]; |
DebugOut.Analog[5] = yawRate; |
#ifdef ATTITUDE_USE_ACC_SENSORS |
correctIntegralsByAcc0thOrder(); |
driftCorrection(); |
correctIntegralsByAcc0thOrder(); |
driftCorrection(); |
#endif |
// end part1 |
// end part1 |
} |
void updateCompass(void) { |
int16_t w, v, r,correction, error; |
if(compassCalState && !(MKFlags & MKFLAG_MOTOR_RUN)) { |
if (controlMixer_testCompassCalState()) { |
compassCalState++; |
if(compassCalState < 5) beepNumber(compassCalState); |
else beep(1000); |
} |
} else { |
// get maximum attitude angle |
w = abs(angle[PITCH] / 512); |
v = abs(angle[ROLL] / 512); |
if(v > w) w = v; |
correction = w / 8 + 1; |
// calculate the deviation of the yaw gyro heading and the compass heading |
if (compassHeading < 0) error = 0; // disable yaw drift compensation if compass heading is undefined |
else error = ((540 + compassHeading - (yawGyroHeading / GYRO_DEG_FACTOR_YAW)) % 360) - 180; |
if(abs(yawRate) > 128) { // spinning fast |
error = 0; |
} |
if(!badCompassHeading && w < 25) { |
yawGyroDrift += error; |
if(updateCompassCourse) { |
beep(200); |
yawGyroHeading = (int32_t)compassHeading * GYRO_DEG_FACTOR_YAW; |
compassCourse = compassHeading; //(int16_t)(yawGyroHeading / GYRO_DEG_FACTOR_YAW); |
updateCompassCourse = 0; |
} |
} |
yawGyroHeading += (error * 8) / correction; |
w = (w * dynamicParams.CompassYawEffect) / 32; |
w = dynamicParams.CompassYawEffect - w; |
if(w >= 0) { |
if(!badCompassHeading) { |
v = 64 + (maxControl[PITCH] + maxControl[ROLL]) / 8; |
// calc course deviation |
r = ((540 + (yawGyroHeading / GYRO_DEG_FACTOR_YAW) - compassCourse) % 360) - 180; |
v = (r * w) / v; // align to compass course |
// limit yaw rate |
w = 3 * dynamicParams.CompassYawEffect; |
if (v > w) v = w; |
else if (v < -w) v = -w; |
yawAngleDiff += v; |
} |
else |
{ // wait a while |
badCompassHeading--; |
int16_t w, v, r, correction, error; |
if (compassCalState && !(MKFlags & MKFLAG_MOTOR_RUN)) { |
if (controlMixer_testCompassCalState()) { |
compassCalState++; |
if (compassCalState < 5) |
beepNumber(compassCalState); |
else |
beep(1000); |
} |
} else { |
// get maximum attitude angle |
w = abs(angle[PITCH] / 512); |
v = abs(angle[ROLL] / 512); |
if (v > w) |
w = v; |
correction = w/8 + 1; |
// calculate the deviation of the yaw gyro heading and the compass heading |
if (compassHeading < 0) |
error = 0; // disable yaw drift compensation if compass heading is undefined |
else |
if (abs(yawRate) > 128) { // spinning fast |
error = 0; |
} else { |
// compassHeading - yawGyroHeading, on a -180..179 deg interval. |
error = ((540 + compassHeading - (yawGyroHeading / GYRO_DEG_FACTOR_YAW)) % 360) - 180; |
} |
if (!ignoreCompassTimer && w < 25) { |
yawGyroDrift += error; |
// Basically this gets set if we are in "fix" mode, and when starting. |
if (updateCompassCourse) { |
beep(200); |
yawGyroHeading = (int32_t) compassHeading * GYRO_DEG_FACTOR_YAW; |
compassCourse = compassHeading; //(int16_t)(yawGyroHeading / GYRO_DEG_FACTOR_YAW); |
updateCompassCourse = 0; |
} |
} |
yawGyroHeading += (error * 8) / correction; |
/* |
w = (w * dynamicParams.CompassYawEffect) / 32; |
w = dynamicParams.CompassYawEffect - w; |
*/ |
w = dynamicParams.CompassYawEffect - (w * dynamicParams.CompassYawEffect) / 32; |
// As readable formula: |
// w = dynamicParams.CompassYawEffect * (1-w/32); |
if (w >= 0) { // maxAttitudeAngle < 32 |
if (!ignoreCompassTimer) { |
v = 64 + (maxControl[PITCH] + maxControl[ROLL]) / 8; |
// yawGyroHeading - compassCourse on a -180..179 degree interval. |
r = ((540 + yawGyroHeading / GYRO_DEG_FACTOR_YAW - compassCourse) % 360) - 180; |
v = (r * w) / v; // align to compass course |
// limit yaw rate |
w = 3 * dynamicParams.CompassYawEffect; |
if (v > w) |
v = w; |
else if (v < -w) |
v = -w; |
yawAngleDiff += v; |
} else { // wait a while |
ignoreCompassTimer--; |
} |
} else { // ignore compass at extreme attitudes for a while |
ignoreCompassTimer = 500; |
} |
} |
} else { // ignore compass at extreme attitudes for a while |
badCompassHeading = 500; |
} |
} |
} |
/* |
461,32 → 495,32 |
* speed unfortunately... must find a better way) |
*/ |
/* |
void attitude_startDynamicCalibration(void) { |
dynamicCalPitch = dynamicCalRoll = dynamicCalYaw = dynamicCalCount = 0; |
savedDynamicOffsetPitch = savedDynamicOffsetRoll = 1000; |
} |
void attitude_startDynamicCalibration(void) { |
dynamicCalPitch = dynamicCalRoll = dynamicCalYaw = dynamicCalCount = 0; |
savedDynamicOffsetPitch = savedDynamicOffsetRoll = 1000; |
} |
void attitude_continueDynamicCalibration(void) { |
// measure dynamic offset now... |
dynamicCalPitch += hiResPitchGyro; |
dynamicCalRoll += hiResRollGyro; |
dynamicCalYaw += rawYawGyroSum; |
dynamicCalCount++; |
// Param6: Manual mode. The offsets are taken from Param7 and Param8. |
if (dynamicParams.UserParam6 || 1) { // currently always enabled. |
// manual mode |
driftCompPitch = dynamicParams.UserParam7 - 128; |
driftCompRoll = dynamicParams.UserParam8 - 128; |
} else { |
// use the sampled value (does not seem to work so well....) |
driftCompPitch = savedDynamicOffsetPitch = -dynamicCalPitch / dynamicCalCount; |
driftCompRoll = savedDynamicOffsetRoll = -dynamicCalRoll / dynamicCalCount; |
driftCompYaw = -dynamicCalYaw / dynamicCalCount; |
} |
// keep resetting these meanwhile, to avoid accumulating errors. |
setStaticAttitudeIntegrals(); |
yawAngle = 0; |
} |
*/ |
void attitude_continueDynamicCalibration(void) { |
// measure dynamic offset now... |
dynamicCalPitch += hiResPitchGyro; |
dynamicCalRoll += hiResRollGyro; |
dynamicCalYaw += rawYawGyroSum; |
dynamicCalCount++; |
// Param6: Manual mode. The offsets are taken from Param7 and Param8. |
if (dynamicParams.UserParam6 || 1) { // currently always enabled. |
// manual mode |
driftCompPitch = dynamicParams.UserParam7 - 128; |
driftCompRoll = dynamicParams.UserParam8 - 128; |
} else { |
// use the sampled value (does not seem to work so well....) |
driftCompPitch = savedDynamicOffsetPitch = -dynamicCalPitch / dynamicCalCount; |
driftCompRoll = savedDynamicOffsetRoll = -dynamicCalRoll / dynamicCalCount; |
driftCompYaw = -dynamicCalYaw / dynamicCalCount; |
} |
// keep resetting these meanwhile, to avoid accumulating errors. |
setStaticAttitudeIntegrals(); |
yawAngle = 0; |
} |
*/ |
/branches/dongfang_FC_rewrite/attitude.h |
---|
96,12 → 96,12 |
*/ |
extern int16_t compassHeading; |
extern int16_t compassCourse; |
extern int16_t compassOffCourse; |
// extern int16_t compassOffCourse; |
extern uint8_t compassCalState; |
extern int32_t yawGyroHeading; |
extern int16_t yawGyroHeadingInDeg; |
extern uint16_t updateCompassCourse; |
extern uint16_t badCompassHeading; |
extern uint8_t updateCompassCourse; |
extern uint16_t ignoreCompassTimer; |
void updateCompass(void); |
/branches/dongfang_FC_rewrite/configuration.c |
---|
92,7 → 92,8 |
SET_POT(dynamicParams.DynamicStability,staticParams.DynamicStability); |
SET_POT_MM(dynamicParams.J16Timing,staticParams.J16Timing,1,255); |
SET_POT_MM(dynamicParams.J17Timing,staticParams.J17Timing,1,255); |
#if defined (USE_MK3MAG) |
#if defined (USE_NAVICTRL) |
SET_POT(dynamicParams.NaviGpsModeControl,staticParams.NaviGpsModeControl); |
SET_POT(dynamicParams.NaviGpsGain,staticParams.NaviGpsGain); |
SET_POT(dynamicParams.NaviGpsP,staticParams.NaviGpsP); |
/branches/dongfang_FC_rewrite/flight.c |
---|
265,7 → 265,7 |
/* Yawing */ |
/************************************************************************/ |
if(abs(controlYaw) > 4 * staticParams.StickYawP) { // yaw stick is activated |
badCompassHeading = 1000; |
ignoreCompassTimer = 1000; |
if(!(staticParams.GlobalConfig & CFG_COMPASS_FIX)) { |
updateCompassCourse = 1; |
} |
288,7 → 288,7 |
updateCompass(); |
} |
#if defined (USE_MK3MAG) |
#if defined (USE_NAVICTRL) |
/************************************************************************/ |
/* GPS is currently not supported. */ |
/************************************************************************/ |
295,8 → 295,7 |
if(staticParams.GlobalConfig & CFG_GPS_ACTIVE) { |
GPS_Main(); |
MKFlags &= ~(MKFLAG_CALIBRATE | MKFLAG_START); |
} |
else { |
} else { |
// GPSStickPitch = 0; |
// GPSStickRoll = 0; |
} |
/branches/dongfang_FC_rewrite/gps.c |
---|
56,122 → 56,129 |
#include "rc.h" |
#include "eeprom.h" |
typedef enum |
{ |
GPS_FLIGHT_MODE_UNDEF, |
GPS_FLIGHT_MODE_FREE, |
GPS_FLIGHT_MODE_AID, |
GPS_FLIGHT_MODE_HOME, |
} FlightMode_t; |
typedef enum { |
GPS_FLIGHT_MODE_UNDEF, |
GPS_FLIGHT_MODE_FREE, |
GPS_FLIGHT_MODE_AID, |
GPS_FLIGHT_MODE_HOME, |
} FlightMode_t; |
#define GPS_POSINTEGRAL_LIMIT 32000 |
#define GPS_STICK_LIMIT 45 // limit of gps stick control to avoid critical flight attitudes |
#define GPS_P_LIMIT 25 |
typedef struct |
{ |
int32_t Longitude; |
int32_t Latitude; |
int32_t Altitude; |
Status_t Status; |
typedef struct { |
int32_t Longitude; |
int32_t Latitude; |
int32_t Altitude; |
Status_t Status; |
} GPS_Pos_t; |
// GPS coordinates for hold position |
GPS_Pos_t HoldPosition = {0,0,0,INVALID}; |
GPS_Pos_t HoldPosition = { 0, 0, 0, INVALID }; |
// GPS coordinates for home position |
GPS_Pos_t HomePosition = {0,0,0,INVALID}; |
GPS_Pos_t HomePosition = { 0, 0, 0, INVALID }; |
// the current flight mode |
FlightMode_t FlightMode = GPS_FLIGHT_MODE_UNDEF; |
// --------------------------------------------------------------------------------- |
void GPS_UpdateParameter(void) { |
static FlightMode_t FlightModeOld = GPS_FLIGHT_MODE_UNDEF; |
if((RC_Quality < 100) || (MKFlags & MKFLAG_EMERGENCY_LANDING)) { |
FlightMode = GPS_FLIGHT_MODE_FREE; |
} else { |
if (dynamicParams.NaviGpsModeControl < 50) FlightMode = GPS_FLIGHT_MODE_AID; |
else if(dynamicParams.NaviGpsModeControl < 180) FlightMode = GPS_FLIGHT_MODE_FREE; |
else FlightMode = GPS_FLIGHT_MODE_HOME; |
} |
static FlightMode_t FlightModeOld = GPS_FLIGHT_MODE_UNDEF; |
if (FlightMode != FlightModeOld) { |
BeepTime = 100; |
} |
FlightModeOld = FlightMode; |
if ((RC_Quality < 100) || (MKFlags & MKFLAG_EMERGENCY_LANDING)) { |
FlightMode = GPS_FLIGHT_MODE_FREE; |
} else { |
if (dynamicParams.NaviGpsModeControl < 50) |
FlightMode = GPS_FLIGHT_MODE_AID; |
else if (dynamicParams.NaviGpsModeControl < 180) |
FlightMode = GPS_FLIGHT_MODE_FREE; |
else |
FlightMode = GPS_FLIGHT_MODE_HOME; |
} |
if (FlightMode != FlightModeOld) { |
BeepTime = 100; |
} |
FlightModeOld = FlightMode; |
} |
// --------------------------------------------------------------------------------- |
// This function defines a good GPS signal condition |
uint8_t GPS_IsSignalOK(void) { |
static uint8_t GPSFix = 0; |
if( (GPSInfo.status != INVALID) && (GPSInfo.satfix == SATFIX_3D) && (GPSInfo.flags & FLAG_GPSFIXOK) && ((GPSInfo.satnum >= staticParams.NaviGpsMinSat) || GPSFix)) { |
GPSFix = 1; |
return 1; |
} |
else return (0); |
static uint8_t GPSFix = 0; |
if ((GPSInfo.status != INVALID) && (GPSInfo.satfix == SATFIX_3D) |
&& (GPSInfo.flags & FLAG_GPSFIXOK) && ((GPSInfo.satnum |
>= staticParams.NaviGpsMinSat) || GPSFix)) { |
GPSFix = 1; |
return 1; |
} else |
return (0); |
} |
// --------------------------------------------------------------------------------- |
// rescale xy-vector length to limit |
uint8_t GPS_LimitXY(int32_t *x, int32_t *y, int32_t limit) { |
uint8_t retval = 0; |
int32_t len; |
len = (int32_t)c_sqrt(*x * *x + *y * *y); |
if (len > limit) { |
// normalize control vector components to the limit |
*x = (*x * limit) / len; |
*y = (*y * limit) / len; |
retval = 1; |
} |
return(retval); |
uint8_t retval = 0; |
int32_t len; |
len = (int32_t) c_sqrt(*x * *x + *y * *y); |
if (len > limit) { |
// normalize control vector components to the limit |
*x = (*x * limit) / len; |
*y = (*y * limit) / len; |
retval = 1; |
} |
return (retval); |
} |
// checks nick and roll sticks for manual control |
uint8_t GPS_IsManualControlled(void) { |
if ((abs(PPM_in[staticParams.ChannelAssignment[CH_NICK]]) < staticParams.NaviStickThreshold) && (abs(PPM_in[staticParams.ChannelAssignment[CH_ROLL]]) < staticParams.NaviStickThreshold)) return 0; |
else return 1; |
if ((abs(PPM_in[staticParams.ChannelAssignment[CH_NICK]]) |
< staticParams.NaviStickThreshold) |
&& (abs(PPM_in[staticParams.ChannelAssignment[CH_ROLL]]) |
< staticParams.NaviStickThreshold)) |
return 0; |
else |
return 1; |
} |
// set given position to current gps position |
uint8_t GPS_SetCurrPosition(GPS_Pos_t * pGPSPos) { |
uint8_t retval = 0; |
if(pGPSPos == NULL) return(retval); // bad pointer |
uint8_t retval = 0; |
if (pGPSPos == NULL) |
return (retval); // bad pointer |
if(GPS_IsSignalOK()) { // is GPS signal condition is fine |
pGPSPos->Longitude = GPSInfo.longitude; |
pGPSPos->Latitude = GPSInfo.latitude; |
pGPSPos->Altitude = GPSInfo.altitude; |
pGPSPos->Status = NEWDATA; |
retval = 1; |
} else { // bad GPS signal condition |
pGPSPos->Status = INVALID; |
retval = 0; |
} |
return(retval); |
if (GPS_IsSignalOK()) { // is GPS signal condition is fine |
pGPSPos->Longitude = GPSInfo.longitude; |
pGPSPos->Latitude = GPSInfo.latitude; |
pGPSPos->Altitude = GPSInfo.altitude; |
pGPSPos->Status = NEWDATA; |
retval = 1; |
} else { // bad GPS signal condition |
pGPSPos->Status = INVALID; |
retval = 0; |
} |
return (retval); |
} |
// clear position |
uint8_t GPS_ClearPosition(GPS_Pos_t * pGPSPos) { |
uint8_t retval = 0; |
if(pGPSPos == NULL) |
return retval; // bad pointer |
else { |
pGPSPos->Longitude = 0; |
pGPSPos->Latitude = 0; |
pGPSPos->Altitude = 0; |
pGPSPos->Status = INVALID; |
retval = 1; |
} |
return (retval); |
uint8_t retval = 0; |
if (pGPSPos == NULL) |
return retval; // bad pointer |
else { |
pGPSPos->Longitude = 0; |
pGPSPos->Latitude = 0; |
pGPSPos->Altitude = 0; |
pGPSPos->Status = INVALID; |
retval = 1; |
} |
return (retval); |
} |
// disable GPS control sticks |
void GPS_Neutral(void) { |
GPSStickNick = 0; |
GPSStickRoll = 0; |
GPSStickNick = 0; |
GPSStickRoll = 0; |
} |
// calculates the GPS control stick values from the deviation to target position |
178,255 → 185,241 |
// if the pointer to the target positin is NULL or is the target position invalid |
// then the P part of the controller is deactivated. |
void GPS_PIDController(GPS_Pos_t *pTargetPos) { |
static int32_t PID_Nick, PID_Roll; |
int32_t coscompass, sincompass; |
int32_t GPSPosDev_North, GPSPosDev_East; // Position deviation in cm |
int32_t P_North = 0, D_North = 0, P_East = 0, D_East = 0, I_North = 0, I_East = 0; |
int32_t PID_North = 0, PID_East = 0; |
static int32_t cos_target_latitude = 1; |
static int32_t GPSPosDevIntegral_North = 0, GPSPosDevIntegral_East = 0; |
static GPS_Pos_t *pLastTargetPos = 0; |
static int32_t PID_Nick, PID_Roll; |
int32_t coscompass, sincompass; |
int32_t GPSPosDev_North, GPSPosDev_East; // Position deviation in cm |
int32_t P_North = 0, D_North = 0, P_East = 0, D_East = 0, I_North = 0, |
I_East = 0; |
int32_t PID_North = 0, PID_East = 0; |
static int32_t cos_target_latitude = 1; |
static int32_t GPSPosDevIntegral_North = 0, GPSPosDevIntegral_East = 0; |
static GPS_Pos_t *pLastTargetPos = 0; |
// if GPS data and Compass are ok |
if( GPS_IsSignalOK() && (CompassHeading >= 0)) { |
if(pTargetPos != NULL) // if there is a target position |
{ |
if(pTargetPos->Status != INVALID) // and the position data are valid |
{ |
// if the target data are updated or the target pointer has changed |
if ((pTargetPos->Status != PROCESSED) || (pTargetPos != pLastTargetPos) ) |
{ |
// if GPS data and Compass are ok |
if (GPS_IsSignalOK() && (CompassHeading >= 0)) { |
if (pTargetPos != NULL) // if there is a target position |
{ |
if (pTargetPos->Status != INVALID) // and the position data are valid |
{ |
// if the target data are updated or the target pointer has changed |
if ((pTargetPos->Status != PROCESSED) || (pTargetPos |
!= pLastTargetPos)) { |
// reset error integral |
GPSPosDevIntegral_North = 0; |
GPSPosDevIntegral_East = 0; |
// recalculate latitude projection |
cos_target_latitude = (int32_t) c_cos_8192( |
(int16_t) (pTargetPos->Latitude / 10000000L)); |
// remember last target pointer |
pLastTargetPos = pTargetPos; |
// mark data as processed |
pTargetPos->Status = PROCESSED; |
} |
// calculate position deviation from latitude and longitude differences |
GPSPosDev_North = (GPSInfo.latitude - pTargetPos->Latitude); // to calculate real cm we would need *111/100 additionally |
GPSPosDev_East = (GPSInfo.longitude - pTargetPos->Longitude); // to calculate real cm we would need *111/100 additionally |
// calculate latitude projection |
GPSPosDev_East *= cos_target_latitude; |
GPSPosDev_East /= 8192; |
} else {// no valid target position available |
// reset error |
GPSPosDev_North = 0; |
GPSPosDev_East = 0; |
// reset error integral |
GPSPosDevIntegral_North = 0; |
GPSPosDevIntegral_East = 0; |
} |
} else { // no target position available |
// reset error |
GPSPosDev_North = 0; |
GPSPosDev_East = 0; |
// reset error integral |
GPSPosDevIntegral_North = 0; |
GPSPosDevIntegral_East = 0; |
} |
//Calculate PID-components of the controller |
// D-Part |
D_North = ((int32_t) dynamicParams.NaviGpsD * GPSInfo.velnorth) / 512; |
D_East = ((int32_t) dynamicParams.NaviGpsD * GPSInfo.veleast) / 512; |
// P-Part |
P_North = ((int32_t) dynamicParams.NaviGpsP * GPSPosDev_North) / 2048; |
P_East = ((int32_t) dynamicParams.NaviGpsP * GPSPosDev_East) / 2048; |
// I-Part |
I_North = ((int32_t) dynamicParams.NaviGpsI * GPSPosDevIntegral_North) |
/ 8192; |
I_East = ((int32_t) dynamicParams.NaviGpsI * GPSPosDevIntegral_East) |
/ 8192; |
// combine P & I |
PID_North = P_North + I_North; |
PID_East = P_East + I_East; |
if (!GPS_LimitXY(&PID_North, &PID_East, GPS_P_LIMIT)) { |
GPSPosDevIntegral_North += GPSPosDev_North / 16; |
GPSPosDevIntegral_East += GPSPosDev_East / 16; |
GPS_LimitXY(&GPSPosDevIntegral_North, &GPSPosDevIntegral_East, |
GPS_POSINTEGRAL_LIMIT); |
} |
// combine PI- and D-Part |
PID_North += D_North; |
PID_East += D_East; |
// scale combination with gain. |
PID_North = (PID_North * (int32_t) dynamicParams.NaviGpsGain) / 100; |
PID_East = (PID_East * (int32_t) dynamicParams.NaviGpsGain) / 100; |
// GPS to nick and roll settings |
// A positive nick angle moves head downwards (flying forward). |
// A positive roll angle tilts left side downwards (flying left). |
// If compass heading is 0 the head of the copter is in north direction. |
// A positive nick angle will fly to north and a positive roll angle will fly to west. |
// In case of a positive north deviation/velocity the |
// copter should fly to south (negative nick). |
// In case of a positive east position deviation and a positive east velocity the |
// copter should fly to west (positive roll). |
// The influence of the GPSStickNick and GPSStickRoll variable is contrarily to the stick values |
// in the flight.c. Therefore a positive north deviation/velocity should result in a positive |
// GPSStickNick and a positive east deviation/velocity should result in a negative GPSStickRoll. |
coscompass = (int32_t) c_cos_8192(YawGyroHeading / GYRO_DEG_FACTOR); |
sincompass = (int32_t) c_sin_8192(YawGyroHeading / GYRO_DEG_FACTOR); |
PID_Nick = (coscompass * PID_North + sincompass * PID_East) / 8192; |
PID_Roll = (sincompass * PID_North - coscompass * PID_East) / 8192; |
// limit resulting GPS control vector |
GPS_LimitXY(&PID_Nick, &PID_Roll, GPS_STICK_LIMIT); |
GPSStickNick = (int16_t) PID_Nick; |
GPSStickRoll = (int16_t) PID_Roll; |
} else { // invalid GPS data or bad compass reading |
GPS_Neutral(); // do nothing |
// reset error integral |
GPSPosDevIntegral_North = 0; |
GPSPosDevIntegral_East = 0; |
// recalculate latitude projection |
cos_target_latitude = (int32_t)c_cos_8192((int16_t)(pTargetPos->Latitude/10000000L)); |
// remember last target pointer |
pLastTargetPos = pTargetPos; |
// mark data as processed |
pTargetPos->Status = PROCESSED; |
} |
// calculate position deviation from latitude and longitude differences |
GPSPosDev_North = (GPSInfo.latitude - pTargetPos->Latitude); // to calculate real cm we would need *111/100 additionally |
GPSPosDev_East = (GPSInfo.longitude - pTargetPos->Longitude); // to calculate real cm we would need *111/100 additionally |
// calculate latitude projection |
GPSPosDev_East *= cos_target_latitude; |
GPSPosDev_East /= 8192; |
} |
else // no valid target position available |
{ |
// reset error |
GPSPosDev_North = 0; |
GPSPosDev_East = 0; |
// reset error integral |
GPSPosDevIntegral_North = 0; |
GPSPosDevIntegral_East = 0; |
} |
} |
else // no target position available |
{ |
// reset error |
GPSPosDev_North = 0; |
GPSPosDev_East = 0; |
// reset error integral |
GPSPosDevIntegral_North = 0; |
GPSPosDevIntegral_East = 0; |
} |
//Calculate PID-components of the controller |
// D-Part |
D_North = ((int32_t)dynamicParams.NaviGpsD * GPSInfo.velnorth)/512; |
D_East = ((int32_t)dynamicParams.NaviGpsD * GPSInfo.veleast)/512; |
// P-Part |
P_North = ((int32_t)dynamicParams.NaviGpsP * GPSPosDev_North)/2048; |
P_East = ((int32_t)dynamicParams.NaviGpsP * GPSPosDev_East)/2048; |
// I-Part |
I_North = ((int32_t)dynamicParams.NaviGpsI * GPSPosDevIntegral_North)/8192; |
I_East = ((int32_t)dynamicParams.NaviGpsI * GPSPosDevIntegral_East)/8192; |
// combine P & I |
PID_North = P_North + I_North; |
PID_East = P_East + I_East; |
if(!GPS_LimitXY(&PID_North, &PID_East, GPS_P_LIMIT)) |
{ |
GPSPosDevIntegral_North += GPSPosDev_North/16; |
GPSPosDevIntegral_East += GPSPosDev_East/16; |
GPS_LimitXY(&GPSPosDevIntegral_North, &GPSPosDevIntegral_East, GPS_POSINTEGRAL_LIMIT); |
} |
// combine PI- and D-Part |
PID_North += D_North; |
PID_East += D_East; |
// scale combination with gain. |
PID_North = (PID_North * (int32_t)dynamicParams.NaviGpsGain) / 100; |
PID_East = (PID_East * (int32_t)dynamicParams.NaviGpsGain) / 100; |
// GPS to nick and roll settings |
// A positive nick angle moves head downwards (flying forward). |
// A positive roll angle tilts left side downwards (flying left). |
// If compass heading is 0 the head of the copter is in north direction. |
// A positive nick angle will fly to north and a positive roll angle will fly to west. |
// In case of a positive north deviation/velocity the |
// copter should fly to south (negative nick). |
// In case of a positive east position deviation and a positive east velocity the |
// copter should fly to west (positive roll). |
// The influence of the GPSStickNick and GPSStickRoll variable is contrarily to the stick values |
// in the flight.c. Therefore a positive north deviation/velocity should result in a positive |
// GPSStickNick and a positive east deviation/velocity should result in a negative GPSStickRoll. |
coscompass = (int32_t)c_cos_8192(YawGyroHeading / GYRO_DEG_FACTOR); |
sincompass = (int32_t)c_sin_8192(YawGyroHeading / GYRO_DEG_FACTOR); |
PID_Nick = (coscompass * PID_North + sincompass * PID_East) / 8192; |
PID_Roll = (sincompass * PID_North - coscompass * PID_East) / 8192; |
// limit resulting GPS control vector |
GPS_LimitXY(&PID_Nick, &PID_Roll, GPS_STICK_LIMIT); |
GPSStickNick = (int16_t)PID_Nick; |
GPSStickRoll = (int16_t)PID_Roll; |
} |
else // invalid GPS data or bad compass reading |
{ |
GPS_Neutral(); // do nothing |
// reset error integral |
GPSPosDevIntegral_North = 0; |
GPSPosDevIntegral_East = 0; |
} |
} |
} |
void GPS_Main(void) { |
static uint8_t GPS_P_Delay = 0; |
static uint16_t beep_rythm = 0; |
static uint8_t GPS_P_Delay = 0; |
static uint16_t beep_rythm = 0; |
GPS_UpdateParameter(); |
GPS_UpdateParameter(); |
// store home position if start of flight flag is set |
if(MKFlags & MKFLAG_CALIBRATE) { |
if(GPS_SetCurrPosition(&HomePosition)) BeepTime = 700; |
} |
switch(GPSInfo.status) { |
case INVALID: // invalid gps data |
GPS_Neutral(); |
if(FlightMode != GPS_FLIGHT_MODE_FREE) { |
BeepTime = 100; // beep if signal is neccesary |
} |
break; |
case PROCESSED: // if gps data are already processed do nothing |
// downcount timeout |
if(GPSTimeout) GPSTimeout--; |
// if no new data arrived within timeout set current data invalid |
// and therefore disable GPS |
else |
{ |
GPS_Neutral(); |
GPSInfo.status = INVALID; |
} |
break; |
case NEWDATA: // new valid data from gps device |
// if the gps data quality is good |
beep_rythm++; |
if (GPS_IsSignalOK()) |
{ |
switch(FlightMode) // check what's to do |
{ |
case GPS_FLIGHT_MODE_FREE: |
// update hold position to current gps position |
GPS_SetCurrPosition(&HoldPosition); // can get invalid if gps signal is bad |
// disable gps control |
GPS_Neutral(); |
break; |
case GPS_FLIGHT_MODE_AID: |
if(HoldPosition.Status != INVALID) |
{ |
if( GPS_IsManualControlled() ) // MK controlled by user |
{ |
// update hold point to current gps position |
GPS_SetCurrPosition(&HoldPosition); |
// disable gps control |
GPS_Neutral(); |
GPS_P_Delay = 0; |
} |
else // GPS control active |
{ |
if(GPS_P_Delay < 7) |
{ // delayed activation of P-Part for 8 cycles (8*0.25s = 2s) |
GPS_P_Delay++; |
GPS_SetCurrPosition(&HoldPosition); // update hold point to current gps position |
GPS_PIDController(NULL); // activates only the D-Part |
} |
else GPS_PIDController(&HoldPosition);// activates the P&D-Part |
} |
} |
else // invalid Hold Position |
{ // try to catch a valid hold position from gps data input |
GPS_SetCurrPosition(&HoldPosition); |
// store home position if start of flight flag is set |
if (MKFlags & MKFLAG_CALIBRATE) { |
if (GPS_SetCurrPosition(&HomePosition)) |
BeepTime = 700; |
} |
switch (GPSInfo.status) { |
case INVALID: // invalid gps data |
GPS_Neutral(); |
} |
break; |
case GPS_FLIGHT_MODE_HOME: |
if(HomePosition.Status != INVALID) |
{ |
// update hold point to current gps position |
// to avoid a flight back if home comming is deactivated |
GPS_SetCurrPosition(&HoldPosition); |
if( GPS_IsManualControlled() ) // MK controlled by user |
{ |
GPS_Neutral(); |
} |
else // GPS control active |
{ |
GPS_PIDController(&HomePosition); |
} |
} |
else // bad home position |
{ |
BeepTime = 50; // signal invalid home position |
// try to hold at least the position as a fallback option |
if (HoldPosition.Status != INVALID) |
{ |
if( GPS_IsManualControlled() ) // MK controlled by user |
{ |
if (FlightMode != GPS_FLIGHT_MODE_FREE) { |
BeepTime = 100; // beep if signal is neccesary |
} |
break; |
case PROCESSED: // if gps data are already processed do nothing |
// downcount timeout |
if (GPSTimeout) |
GPSTimeout--; |
// if no new data arrived within timeout set current data invalid |
// and therefore disable GPS |
else { |
GPS_Neutral(); |
} |
else // GPS control active |
{ |
GPS_PIDController(&HoldPosition); |
} |
} |
else |
{ // try to catch a valid hold position |
GPS_SetCurrPosition(&HoldPosition); |
GPS_Neutral(); |
} |
} |
break; // eof TSK_HOME |
default: // unhandled task |
GPS_Neutral(); |
break; // eof default |
} // eof switch GPS_Task |
} // eof gps data quality is good |
else // gps data quality is bad |
{ // disable gps control |
GPS_Neutral(); |
if(FlightMode != GPS_FLIGHT_MODE_FREE) |
{ |
// beep if signal is not sufficient |
if(!(GPSInfo.flags & FLAG_GPSFIXOK) && !(beep_rythm % 5)) BeepTime = 100; |
else if (GPSInfo.satnum < staticParams.NaviGpsMinSat && !(beep_rythm % 5)) BeepTime = 10; |
} |
} |
// set current data as processed to avoid further calculations on the same gps data |
GPSInfo.status = PROCESSED; |
break; |
} // eof GPSInfo.status |
GPSInfo.status = INVALID; |
} |
break; |
case NEWDATA: // new valid data from gps device |
// if the gps data quality is good |
beep_rythm++; |
if (GPS_IsSignalOK()) { |
switch (FlightMode) { // check what's to do |
case GPS_FLIGHT_MODE_FREE: |
// update hold position to current gps position |
GPS_SetCurrPosition(&HoldPosition); // can get invalid if gps signal is bad |
// disable gps control |
GPS_Neutral(); |
break; |
case GPS_FLIGHT_MODE_AID: |
if (HoldPosition.Status != INVALID) { |
if (GPS_IsManualControlled()) { // MK controlled by user |
// update hold point to current gps position |
GPS_SetCurrPosition(&HoldPosition); |
// disable gps control |
GPS_Neutral(); |
GPS_P_Delay = 0; |
} else { // GPS control active |
if (GPS_P_Delay < 7) { |
// delayed activation of P-Part for 8 cycles (8*0.25s = 2s) |
GPS_P_Delay++; |
GPS_SetCurrPosition(&HoldPosition); // update hold point to current gps position |
GPS_PIDController(NULL); // activates only the D-Part |
} else |
GPS_PIDController(&HoldPosition);// activates the P&D-Part |
} |
} else // invalid Hold Position |
{ // try to catch a valid hold position from gps data input |
GPS_SetCurrPosition(&HoldPosition); |
GPS_Neutral(); |
} |
break; |
case GPS_FLIGHT_MODE_HOME: |
if (HomePosition.Status != INVALID) { |
// update hold point to current gps position |
// to avoid a flight back if home comming is deactivated |
GPS_SetCurrPosition(&HoldPosition); |
if (GPS_IsManualControlled()) // MK controlled by user |
{ |
GPS_Neutral(); |
} else // GPS control active |
{ |
GPS_PIDController(&HomePosition); |
} |
} else // bad home position |
{ |
BeepTime = 50; // signal invalid home position |
// try to hold at least the position as a fallback option |
if (HoldPosition.Status != INVALID) { |
if (GPS_IsManualControlled()) // MK controlled by user |
{ |
GPS_Neutral(); |
} else // GPS control active |
{ |
GPS_PIDController(&HoldPosition); |
} |
} else { // try to catch a valid hold position |
GPS_SetCurrPosition(&HoldPosition); |
GPS_Neutral(); |
} |
} |
break; // eof TSK_HOME |
default: // unhandled task |
GPS_Neutral(); |
break; // eof default |
} // eof switch GPS_Task |
} // eof gps data quality is good |
else // gps data quality is bad |
{ // disable gps control |
GPS_Neutral(); |
if (FlightMode != GPS_FLIGHT_MODE_FREE) { |
// beep if signal is not sufficient |
if (!(GPSInfo.flags & FLAG_GPSFIXOK) && !(beep_rythm % 5)) |
BeepTime = 100; |
else if (GPSInfo.satnum < staticParams.NaviGpsMinSat |
&& !(beep_rythm % 5)) |
BeepTime = 10; |
} |
} |
// set current data as processed to avoid further calculations on the same gps data |
GPSInfo.status = PROCESSED; |
break; |
} // eof GPSInfo.status |
} |
/branches/dongfang_FC_rewrite/main.c |
---|
136,14 → 136,14 |
// Instead, while away the time by flashing the 2 outputs: |
// First J16, then J17. Makes it easier to see which is which. |
timer = SetDelay(200); |
OUTPUT_ON(0); |
OUTPUT_SET(0,1); |
GRN_OFF; |
RED_ON; |
while(!CheckDelay(timer)); |
timer = SetDelay(200); |
OUTPUT_OFF(0); |
OUTPUT_ON(1); |
OUTPUT_SET(0,0); |
OUTPUT_SET(1,1); |
RED_OFF; |
GRN_ON; |
while(!CheckDelay(timer)); |
150,7 → 150,7 |
timer = SetDelay(200); |
while(!CheckDelay(timer)); |
OUTPUT_OFF(1); |
OUTPUT_SET(1,0); |
twi_diagnostics(); |
/branches/dongfang_FC_rewrite/makefile |
---|
143,7 → 143,7 |
SRC += eeprom.c uart1.c heightControl.c configuration.c attitudeControl.c commands.c $(GYRO).c |
ifeq ($(EXT), MK3MAG) |
SRC += mk3mag.c gps.c ubx.c |
SRC += mk3mag.c |
#mymath.c |
endif |
ifeq ($(EXT), NAVICTRL) |
/branches/dongfang_FC_rewrite/menu.c |
---|
60,10 → 60,11 |
#include "twimaster.h" |
#include "attitude.h" |
#if (!defined (USE_MK3MAG)) |
#if (!defined (USE_NAVICTRL)) |
uint8_t MaxMenuItem = 13; |
#else |
#ifdef USE_MK3MAG |
#ifdef USE_NAVICTRL |
#include "gps.c" |
uint8_t MaxMenuItem = 14; |
#endif |
#endif |
84,8 → 85,7 |
/************************************/ |
/* Clear LCD Buffer */ |
/************************************/ |
void LCD_Clear(void) |
{ |
void LCD_Clear(void) { |
uint8_t i; |
for( i = 0; i < DISPLAYBUFFSIZE; i++) DisplayBuff[i] = ' '; |
} |
202,7 → 202,7 |
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,3,"OffCourse: %5i", ((540 + compassHeading - compassCourse) % 360) - 180); |
break; |
case 9:// Poti Menu Item |
LCD_printfxy(0,0,"Po1: %3i Po5: %3i" ,variables[0], variables[4]); //PPM24-Extesion |
242,7 → 242,7 |
if(motor[11].Present) LCD_printfxy(12,3,"12"); |
break; |
#if (defined (USE_MK3MAG)) |
#if (defined (USE_NAVICTRL)) |
case 14://GPS Lat/Lon coords |
if (GPSInfo.status == INVALID) { |
LCD_printfxy(0,0,"No GPS data!"); |
/branches/dongfang_FC_rewrite/mk3mag.c |
---|
87,9 → 87,13 |
// in other words 100us/° with a +1ms offset. |
// The signal goes low for 65ms between pulses, |
// so the cycle time is 65mS + the pulse width. |
// pwm is high |
if (debugCounter++ == 5000) { |
DebugOut.Digital[0] ^= DEBUG_MK3MAG; |
debugCounter = 0; |
} |
if (PINC & (1 << PINC4)) { |
// If PWM signal is high increment PWM high counter |
// This counter is incremented by a periode of 102.4us, |
103,26 → 107,34 |
PWMCount = 0; // reset PWM Counter |
} |
} else { // pwm is low |
// ignore pwm values values of 0 and higher than 37 ms; |
// ignore pwm values values of 0 and higher than 37 ms; |
if ((PWMCount) && (PWMCount < 362)) { // 362 * 102.4us = 37.0688 ms |
if (PWMCount < 10) |
compassHeading = 0; |
else |
else { |
compassHeading = ((uint32_t) (PWMCount - 10) * 1049L) / 1024; // correct timebase and offset |
compassOffCourse = ((540 + compassHeading - compassCourse) % 360) - 180; |
DebugOut.Digital[1] ^= DEBUG_MK3MAG; // correct signal recd. |
} |
/* |
compassHeading - compassCourse on a -180..179 range. |
compassHeading 20 compassCourse 30 --> ((540 - 10)%360) - 180 = -10 |
compassHeading 30 compassCourse 20 --> ((540 + 10)%360) - 180 = 10 |
compassHeading 350 compassCourse 10 --> ((540 + 340)%360) - 180 = -20 |
compassHeading 10 compassCourse 350 --> ((540 - 340)%360) - 180 = 20 |
*/ |
//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 |
} |
PWMCount = 0; // reset pwm counter |
DebugOut.Digital[0] ^= DEBUG_MK3MAG; |
DebugOut.Digital[1] &= ~DEBUG_MK3MAG; |
} if (!PWMTimeout) { |
} |
if (!PWMTimeout) { |
if (CheckDelay(BeepDelay)) { |
if (!BeepTime) |
BeepTime = 100; // make noise with 10Hz to signal the compass problem |
BeepDelay = SetDelay(100); |
DebugOut.Digital[1] |= DEBUG_MK3MAG; |
} |
} |
} |
/branches/dongfang_FC_rewrite/output.c |
---|
59,7 → 59,7 |
void output_init(void) { |
// set PC2 & PC3 as output (control of J16 & J17) |
DDRC |= (1<<DDC2)|(1<<DDC3); |
OUTPUT_OFF(0); OUTPUT_OFF(1); |
OUTPUT_SET(0,0); OUTPUT_SET(1,0); |
flashCnt[0] = flashCnt[1] = 0; |
flashMask[0] = flashMask[1] = 128; |
} |
94,25 → 94,12 |
*/ |
#define DIGITAL_DEBUG_MASK DEBUG_MK3MAG |
// invert means: An "1" bit in digital debug data will feed NO base current to output transistor. |
#define DIGITAL_DEBUG_INVERT 0 |
void output_update(void) { |
uint8_t output0, output1; |
if (!DIGITAL_DEBUG_MASK) |
flashingLights(); |
else { |
if (DIGITAL_DEBUG_MASK == DEBUG_LEDTEST) { |
// Show the state for a SET bit. If inverse, then invert. |
output0 = output1 = ~DIGITAL_DEBUG_INVERT; |
} else if (DIGITAL_DEBUG_INVERT) { |
output0 = (~DebugOut.Digital[0]) & DIGITAL_DEBUG_MASK; |
output1 = (~DebugOut.Digital[1]) & DIGITAL_DEBUG_MASK; |
} else { |
output0 = DebugOut.Digital[0] & DIGITAL_DEBUG_MASK; |
output1 = DebugOut.Digital[1] & DIGITAL_DEBUG_MASK; |
} |
OUTPUT_SET(0, output0); |
OUTPUT_SET(1, output1); |
OUTPUT_SET(0, DebugOut.Digital[0] & DIGITAL_DEBUG_MASK); |
OUTPUT_SET(1, DebugOut.Digital[1] & DIGITAL_DEBUG_MASK); |
} |
} |
/branches/dongfang_FC_rewrite/output.h |
---|
7,9 → 7,12 |
// PORTbit = 0 --> LED on. |
// To use the normal transistor set-up where 1 --> transistor conductive, reverse the |
// ON and OFF statements. |
#define OUTPUT_ON(num) {PORTC |= (4 << (num));} |
#define OUTPUT_OFF(num) {PORTC &= ~(4 << (num));} |
#define OUTPUT_SET(num, state) {if ((state)) OUTPUT_ON(num) else OUTPUT_OFF(num)} |
// invert means: An "1" bit in digital debug data make a LOW on the output. |
#define DIGITAL_DEBUG_INVERT 1 |
#define OUTPUT_HIGH(num) {PORTC |= (4 << (num));} |
#define OUTPUT_LOW(num) {PORTC &= ~(4 << (num));} |
#define OUTPUT_SET(num, state) {if (DIGITAL_DEBUG_INVERT){if(state) OUTPUT_LOW(num) else OUTPUT_HIGH(num)} else {if(state) OUTPUT_HIGH(num) else OUTPUT_LOW(num)}} |
#define OUTPUT_TOGGLE(num) ( {PORTC ^= (4 << (num));} |
#define DEBUG_LEDTEST 256 |
/branches/dongfang_FC_rewrite/spi.c |
---|
292,8 → 292,8 |
if(fromNaviCtrl.CompassHeading <= 360) { |
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; |
/branches/dongfang_FC_rewrite/timer0.c |
---|
54,7 → 54,7 |
#include "eeprom.h" |
#include "analog.h" |
// for degugging! |
// for debugging! |
#include "rc.h" |
#ifdef USE_MK3MAG |