Subversion Repositories FlightCtrl

Compare Revisions

Ignore whitespace Rev 1979 → Rev 1980

/branches/dongfang_FC_rewrite/attitude.c
142,6 → 142,8
// int32_t dynamicCalPitch, dynamicCalRoll, dynamicCalYaw;
// int16_t dynamicCalCount;
 
uint16_t accVector;
 
/************************************************************************
* Set inclination angles from the acc. sensor data.
* If acc. sensors are not used, set to zero.
296,7 → 298,9
debugOut.digital[0] &= ~DEBUG_ACC0THORDER;
debugOut.digital[1] &= ~DEBUG_ACC0THORDER;
 
if (1 /*controlActivity <= dynamicParams.maxControlActivityForAcc*/) {
if (accVector <= dynamicParams.maxAccVector) {
debugOut.digital[0] |= DEBUG_ACC0THORDER;
uint8_t permilleAcc = staticParams.zerothOrderCorrection;
int32_t accDerived;
 
313,7 → 317,7
 
if (controlActivity > 10000) { // reduce effect during stick control activity
permilleAcc /= 4;
debugOut.digital[0] |= DEBUG_ACC0THORDER;
debugOut.digital[1] |= DEBUG_ACC0THORDER;
if (controlActivity > 20000) { // reduce effect during stick control activity
permilleAcc /= 4;
debugOut.digital[1] |= DEBUG_ACC0THORDER;
381,11 → 385,23
}
}
 
void calculateAccVector(void) {
uint16_t temp;
temp = filteredAcc[0]/4;
accVector = temp * temp;
temp = filteredAcc[1]/4;
accVector += temp * temp;
temp = filteredAcc[2]/4;
accVector += temp * temp;
debugOut.analog[19] = accVector;
}
 
/************************************************************************
* Main procedure.
************************************************************************/
void calculateFlightAttitude(void) {
getAnalogData();
calculateAccVector();
integrate();
 
#ifdef ATTITUDE_USE_ACC_SENSORS
/branches/dongfang_FC_rewrite/attitude.h
103,6 → 103,7
extern int16_t yawGyroHeadingInDeg;
extern uint8_t updateCompassCourse;
extern uint16_t ignoreCompassTimer;
extern uint16_t accVector;
 
void updateCompass(void);
 
/branches/dongfang_FC_rewrite/configuration.c
92,7 → 92,7
SET_POT(dynamicParams.axisCoupling2, staticParams.axisCoupling2);
SET_POT(dynamicParams.axisCouplingYawCorrection, staticParams.axisCouplingYawCorrection);
SET_POT(dynamicParams.dynamicStability,staticParams.dynamicStability);
SET_POT(dynamicParams.maxControlActivityForAcc,staticParams.maxControlActivityForAcc);
SET_POT(dynamicParams.maxAccVector,staticParams.maxAccVector);
 
SET_POT_MM(dynamicParams.heightP, staticParams.heightP,0,100);
SET_POT_MM(dynamicParams.heightD, staticParams.heightD,0,100);
245,16 → 245,16
staticParams.compassYawEffect = 128;
 
// Servos
staticParams.servoCount = 7;
staticParams.servoManualMaxSpeed = 10;
for (uint8_t i=0; i<2; i++) {
staticParams.servoConfigurations[i].manualControl = 128;
staticParams.servoConfigurations[i].manualMaxSpeed = 10;
staticParams.servoConfigurations[i].compensationFactor = 100;
staticParams.servoConfigurations[i].stabilizationFactor = 0;
staticParams.servoConfigurations[i].minValue = 32;
staticParams.servoConfigurations[i].maxValue = 224;
staticParams.servoConfigurations[i].flags = 0;
}
staticParams.servoCount = 7;
 
// Battery warning and emergency flight
staticParams.batteryVoltageWarning = 101; // 3.7 each for 3S
staticParams.emergencyThrottle = 35;
266,8 → 266,8
staticParams.outputFlash[1].bitmask = 3; //0b11110011;
staticParams.outputFlash[1].timing = 15;
 
staticParams.outputDebugMask = 16;
staticParams.outputOptions = 8;
staticParams.outputDebugMask = 0;
staticParams.outputOptions = 8;
}
 
/***************************************************/
/branches/dongfang_FC_rewrite/configuration.h
23,7 → 23,7
/* P */uint8_t axisCoupling2;
/* P */uint8_t axisCouplingYawCorrection;
/* P */uint8_t dynamicStability;
uint8_t maxControlActivityForAcc;
uint8_t maxAccVector;
 
// Height control
/*PMM*/uint8_t heightP;
71,14 → 71,13
 
typedef struct {
uint8_t manualControl;
uint8_t manualMaxSpeed;
uint8_t compensationFactor;
uint8_t stabilizationFactor;
uint8_t minValue;
uint8_t maxValue;
uint8_t flags;
} servo_t;
 
#define SERVO_COMPENSATION_REVERSE 1
#define SERVO_STABILIZATION_REVERSE 1
 
typedef struct {
uint8_t bitmask;
108,7 → 107,7
uint8_t minThrottle; // Value : 0-32
uint8_t maxThrottle; // Value : 33-250
uint8_t externalControl; // for serial Control
uint8_t maxControlActivityForAcc;
uint8_t maxAccVector;
 
// IMU
uint8_t gyroPIDFilterConstant;
134,8 → 133,9
uint8_t compassYawEffect; // Value : 0-32
 
// Servos
uint8_t servoCount;
uint8_t servoManualMaxSpeed;
servo_t servoConfigurations[2]; // [PITCH, ROLL]
uint8_t servoCount;
 
// Battery warning and emergency flight
uint8_t batteryVoltageWarning; // Value : 0-250
166,12 → 166,12
#define MKFLAG_RESERVE3 (1<<7)
 
// bit mask for staticParams.bitConfig
#define CFG_SIMPLE_HEIGHT_CONTROL (1<<0)
#define CFG_SIMPLE_HEIGHT_CONTROL (1<<0)
#define CFG_SIMPLE_HC_HOLD_SWITCH (1<<1)
#define CFG_HEADING_HOLD (1<<2)
#define CFG_COMPASS_ACTIVE (1<<3)
#define CFG_COMPASS_FIX (1<<4)
#define CFG_GPS_ACTIVE (1<<5)
#define CFG_HEADING_HOLD (1<<2)
#define CFG_COMPASS_ACTIVE (1<<3)
#define CFG_COMPASS_FIX (1<<4)
#define CFG_GPS_ACTIVE (1<<5)
#define CFG_AXIS_COUPLING_ACTIVE (1<<6)
#define CFG_GYRO_SATURATION_PREVENTION (1<<7)
 
/branches/dongfang_FC_rewrite/controlMixer.c
193,12 → 193,14
if (controlMixer_getSignalQuality() >= SIGNAL_GOOD) {
controlMixer_updateVariables();
configuration_applyVariablesToParams();
controlMixer_didReceiveSignal = 1;
} else { // Signal is not OK
// Could handle switch to emergency flight here.
// throttle is handled elsewhere.
}
 
// We can safely do this even with a bad signal - the variables will not have been updated then.
configuration_applyVariablesToParams();
// part1a end.
/branches/dongfang_FC_rewrite/heightControl.c
89,9 → 89,9
 
// height, in meters (so the division factor is: 100)
// debugOut.analog[30] = filteredAirPressure / 10;
debugOut.analog[30] = (125200 - filteredAirPressure) / 100;
debugOut.analog[30] = (117100 - filteredAirPressure) / 100;
// Calculated 0 alt number: 108205
// Experimental 0 alt number: 125200
// Experimental 0 alt number: 117100
}
 
// takes 180-200 usec (with integral term). That is too heavy!!!
/branches/dongfang_FC_rewrite/made
0,0 → 1,10
 
-------- begin --------
avr-gcc (GCC) 3.4.6 (www.mikrokopter.de)
Copyright (C) 2006 Free Software Foundation, Inc.
This is free software; see the source for copying conditions. There is NO
warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
 
 
Compiling: main.c
avr-gcc -c -mmcu=atmega644p -I. -O2 -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums -Wall -Wstrict-prototypes -DGYRO=ENC-03_FC1.3 -Wa,-adhlns=main.lst -std=gnu99 -DF_CPU=20000000 -DVERSION_MAJOR=0 -DVERSION_MINOR=1 -DVERSION_PATCH=0 -DVERSION_SERIAL_MAJOR=10 -DVERSION_SERIAL_MINOR=1 -DNC_SPI_COMPATIBLE=6 -DGYRO_HW_NAME=ENC -DGYRO_HW_FACTOR=1.304f -DGYRO_PITCHROLL_CORRECTION=1.0f -DGYRO_YAW_CORRECTION=1.0f main.c -o main.o
/branches/dongfang_FC_rewrite/main.c
254,6 → 254,12
#endif
 
calculateServoValues();
if (runFlightControl) { // control interval
debugOut.digital[1] |= DEBUG_MAINLOOP_TIMER;
} else {
debugOut.digital[1] &= ~DEBUG_MAINLOOP_TIMER;
}
}
}
return (1);
/branches/dongfang_FC_rewrite/timer2.c
55,10 → 55,30
#include "rc.h"
#include "attitude.h"
 
volatile int16_t ServoPitchValue = 0;
volatile int16_t ServoRollValue = 0;
volatile uint8_t ServoActive = 0;
#define SLOW 1
 
#ifdef SLOW
#define NEUTRAL_PULSELENGTH 938
#define SERVOLIMIT 500
#define SCALE_FACTOR 4
#define CS2 ((1<<CS21)|(1<<CS20))
#else
#define NEUTRAL_PULSELENGTH 3750
#define SERVOLIMIT 2000
#define SCALE_FACTOR 16
#define CS2 (<<CS21)
#endif
 
#define MAX_SERVOS 8
#define FRAMELEN ((NEUTRAL_PULSELENGTH + SERVOLIMIT) * staticParams.servoCount + 128)
#define MIN_PULSELENGTH (NEUTRAL_PULSELENGTH - SERVOLIMIT)
#define MAX_PULSELENGTH (NEUTRAL_PULSELENGTH + SERVOLIMIT)
 
//volatile uint8_t servoActive = 0;
volatile uint8_t recalculateServoTimes = 0;
volatile uint16_t servoValues[MAX_SERVOS];
volatile uint16_t previousManualValues[2];
 
#define HEF4017R_ON PORTC |= (1<<PORTC6)
#define HEF4017R_OFF PORTC &= ~(1<<PORTC6)
 
65,8 → 85,6
/*****************************************************
* Initialize Timer 2
*****************************************************/
// The timer 2 is used to generate the PWM at PD7 (J7)
// to control a camera servo for pitch compensation.
void timer2_init(void) {
uint8_t sreg = SREG;
 
78,220 → 96,155
PORTD &= ~(1 << PORTD7); // set PD7 to low
 
DDRC |= (1 << DDC6); // set PC6 as output (Reset for HEF4017)
//PORTC &= ~(1<<PORTC6); // set PC6 to low
HEF4017R_ON; // enable reset
 
// Timer/Counter 2 Control Register A
// Timer Mode is CTC (Bits: WGM22 = 0, WGM21 = 1, WGM20 = 0)
// PD7: Output OCR2 match, (Bits: COM2A1 = 1, COM2A0 = 0)
// PD6: Normal port operation, OC2B disconnected, (Bits: COM2B1 = 0, COM2B0 = 0)
TCCR2A &= ~((1 << COM2A0) | (1 << COM2B1) | (1 << COM2B0) | (1 << WGM20) | (1 << WGM22));
TCCR2A |= (1 << COM2A1) | (1 << WGM21);
// Timer/Counter 2 Control Register B
// Set clock divider for timer 2 to 20MHz / 8 = 2.5 MHz
// The timer increments from 0x00 to 0xFF with an update rate of 2.5 kHz or 0.4 us
// hence the timer overflow interrupt frequency is 625 kHz / 256 = 9.765 kHz or 0.1024ms
TCCR2B &= ~((1 << FOC2A) | (1 << FOC2B) | (1 << CS20) | (1 << CS21) | (1 << CS22));
TCCR2B |= CS2;
// Initialize the Timer/Counter 2 Register
TCNT2 = 0;
// Initialize the Output Compare Register A used for signal generation on port PD7.
OCR2A = 255;
 
// Timer Mode is FastPWM with timer reload at OCR2A (Bits: WGM22 = 1, WGM21 = 1, WGM20 = 1)
// PD7: Normal port operation, OC2A disconnected, (Bits: COM2A1 = 0, COM2A0 = 0)
// PD6: Normal port operation, OC2B disconnected, (Bits: COM2B1 = 0, COM2B0 = 0)
TCCR2A &= ~((1 << COM2A1) | (1 << COM2A0) | (1 << COM2B1) | (1 << COM2B0));
TCCR2A |= (1 << WGM21) | (1 << WGM20);
 
// Timer/Counter 2 Control Register B
 
// Set clock divider for timer 2 to SYSKLOCK/32 = 20MHz / 32 = 625 kHz
// The timer increments from 0x00 to 0xFF with an update rate of 625 kHz or 1.6 us
// hence the timer overflow interrupt frequency is 625 kHz / 256 = 2.44 kHz or 0.4096 ms
 
// divider 32 (Bits: CS022 = 0, CS21 = 1, CS20 = 1)
TCCR2B &= ~((1 << FOC2A) | (1 << FOC2B) | (1 << CS22));
TCCR2B |= (1 << CS21) | (1 << CS20) | (1 << WGM22);
 
// Initialize the Timer/Counter 2 Register
TCNT2 = 0;
 
// Initialize the Output Compare Register A used for PWM generation on port PD7.
OCR2A = 255;
TCCR2A |= (1 << COM2A1); // set or clear at compare match depends on value of COM2A0
 
// Timer/Counter 2 Interrupt Mask Register
// Enable timer output compare match A Interrupt only
TIMSK2 &= ~((1 << OCIE2B) | (1 << TOIE2));
TIMSK2 |= (1 << OCIE2A);
 
for (uint8_t axis=0; axis<2; axis++)
previousManualValues[axis] = dynamicParams.servoManualControl[axis] * SCALE_FACTOR;
SREG = sreg;
}
 
void Servo_On(void) {
ServoActive = 1;
/*
void servo_On(void) {
servoActive = 1;
}
 
void Servo_Off(void) {
ServoActive = 0;
void servo_Off(void) {
servoActive = 0;
HEF4017R_ON; // enable reset
}
*/
 
/*****************************************************
* Control Servo Position
*****************************************************/
ISR(TIMER2_COMPA_vect)
{
// frame len 22.5 ms = 14063 * 1.6 us
// stop pulse: 0.3 ms = 188 * 1.6 us
// min servo pulse: 0.6 ms = 375 * 1.6 us
// max servo pulse: 2.4 ms = 1500 * 1.6 us
// resolution: 1500 - 375 = 1125 steps
 
#define PPM_STOPPULSE 188
#define PPM_FRAMELEN (1757 * .ServoRefresh) // 22.5 ms / 8 Channels = 2.8125ms per Servo Channel
#define MINSERVOPULSE 375
#define MAXSERVOPULSE 1500
#define SERVORANGE (MAXSERVOPULSE - MINSERVOPULSE)
/*typedef struct {
uint8_t manualControl;
uint8_t compensationFactor;
uint8_t minValue;
uint8_t maxValue;
uint8_t flags;
} servo_t;*/
 
#if defined(USE_NON_4017_SERVO_OUTPUTS) || defined(USE_4017_SERVO_OUTPUTS)
static uint8_t isGeneratingPulse = 0;
static uint16_t remainingPulseLength = 0;
static uint16_t ServoFrameTime = 0;
static uint8_t ServoIndex = 0;
int16_t calculateStabilizedServoAxis(uint8_t axis) {
int32_t value = angle[axis] / 64L; // between -500000 to 500000 extreme limits. Just about
// With full blast on stabilization gain (255) we want to convert a delta of, say, 125000 to 2000.
// That is a divisor of about 1<<14. Same conclusion as H&I.
value *= staticParams.servoConfigurations[axis].stabilizationFactor;
value /= 256L;
if (staticParams.servoConfigurations[axis].flags & SERVO_STABILIZATION_REVERSE)
return -value;
return value;
}
 
#define MULTIPLIER 4
static int16_t ServoPitchOffset = (255 / 2) * MULTIPLIER; // initial value near center position
static int16_t ServoRollOffset = (255 / 2) * MULTIPLIER; // initial value near center position
#endif
#ifdef USE_NON_4017_SERVO_OUTPUTS
//---------------------------
// Pitch servo state machine
//---------------------------
if (!isGeneratingPulse) { // pulse output complete on _next_ interrupt
if(TCCR2A & (1<<COM2A0)) { // we are still outputting a high pulse
TCCR2A &= ~(1<<COM2A0); // make a low pulse on _next_ interrupt, and now
remainingPulseLength = MINSERVOPULSE + SERVORANGE / 2; // center position ~ 1.5ms
ServoPitchOffset = (ServoPitchOffset * 3 + (int16_t)dynamicParams.ServoPitchControl) / 4; // lowpass offset
if(staticParams.ServoPitchCompInvert & 0x01) {
// inverting movement of servo
// todo: function.
ServoPitchValue = ServoPitchOffset + (int16_t)(((int32_t)staticParams.ServoPitchComp (integralGyroPitch / 128L )) / (256L));
} else {
// todo: function.
// non inverting movement of servo
ServoPitchValue = ServoPitchOffset - (int16_t)(((int32_t)staticParams.ServoPitchComp (integralGyroPitch / 128L )) / (256L));
}
// limit servo value to its parameter range definition
if(ServoPitchValue < (int16_t)staticParams.ServoPitchMin) {
ServoPitchValue = (int16_t)staticParams.ServoPitchMin;
} else if(ServoPitchValue > (int16_t)staticParams.ServoPitchMax) {
ServoPitchValue = (int16_t)staticParams.ServoPitchMax;
}
// With constant-speed limitation.
uint16_t calculateManualServoAxis(uint8_t axis, uint16_t manualValue) {
int16_t diff = manualValue - previousManualValues[axis];
uint8_t maxSpeed = staticParams.servoManualMaxSpeed;
if (diff > maxSpeed) diff = maxSpeed;
else if (diff < -maxSpeed) diff = -maxSpeed;
manualValue = previousManualValues[axis] + diff;
previousManualValues[axis] = manualValue;
return manualValue;
}
 
remainingPulseLength = (ServoPitchValue - 256 / 2) * MULTIPLIER; // shift ServoPitchValue to center position
// add stabilization and manual, apply soft position limits.
// All in a [0..255*SCALE_FACTOR] space (despite signed types used internally)
int16_t featuredServoValue(uint8_t axis) {
int16_t value = calculateManualServoAxis(axis, dynamicParams.servoManualControl[axis] * SCALE_FACTOR);
value += calculateStabilizedServoAxis(axis);
int16_t limit = staticParams.servoConfigurations[axis].minValue * SCALE_FACTOR;
if (value < limit) value = limit;
limit = staticParams.servoConfigurations[axis].maxValue * SCALE_FACTOR;
if (value > limit) value = limit;
return value;
}
 
// range servo pulse width
if(remainingPulseLength > MAXSERVOPULSE ) remainingPulseLength = MAXSERVOPULSE; // upper servo pulse limit
else if(remainingPulseLength < MINSERVOPULSE) remainingPulseLength = MINSERVOPULSE; // lower servo pulse limit
uint16_t servoValue(uint8_t axis) {
int16_t value;
if (axis<2) value = featuredServoValue(axis);
else value = 128 * SCALE_FACTOR; // dummy. Replace by something useful for servos 3..8.
// Shift out of the [0..255*SCALE_FACTOR] space
value -= (128 * SCALE_FACTOR);
if (value < -SERVOLIMIT) value = -SERVOLIMIT;
else if (value > SERVOLIMIT) value = SERVOLIMIT;
// Shift into the [NEUTRAL_PULSELENGTH-SERVOLIMIT..NEUTRAL_PULSELENGTH+SERVOLIMIT] space.
return value + NEUTRAL_PULSELENGTH;
}
 
// accumulate time for correct update rate
ServoFrameTime = remainingPulseLength;
} else { // we had a high pulse
TCCR2A |= (1<<COM2A0); // make a low pulse
remainingPulseLength = PPM_FRAMELEN - ServoFrameTime;
}
// set pulse output active
isGeneratingPulse = 1;
} // EOF Pitch servo state machine
void calculateServoValues(void) {
if (!recalculateServoTimes) return;
for (uint8_t axis=0; axis<MAX_SERVOS; axis++) {
servoValues[axis] = servoValue(axis);
}
recalculateServoTimes = 0;
}
 
#elseif defined(USE_4017_SERVOS)
//-----------------------------------------------------
// PPM state machine, onboard demultiplexed by HEF4017
//-----------------------------------------------------
if(!isGeneratingPulse) { // pulse output complete
if(TCCR2A & (1<<COM2A0)) { // we had a low pulse
TCCR2A &= ~(1<<COM2A0);// make a high pulse
ISR(TIMER2_COMPA_vect) {
static uint16_t remainingPulseTime;
static uint8_t servoIndex = 0;
static uint16_t sumOfPulseTimes = 0;
if (!remainingPulseTime) {
// Pulse is over, and the next pulse has already just started. Calculate length of next pulse.
if (servoIndex < staticParams.servoCount) {
// There are more signals to output.
sumOfPulseTimes += (remainingPulseTime = servoValues[servoIndex]);
servoIndex++;
} else {
// There are no more signals. Reset the counter and make this pulse cover the missing frame time.
remainingPulseTime = FRAMELEN - sumOfPulseTimes;
sumOfPulseTimes = servoIndex = 0;
recalculateServoTimes = 1;
HEF4017R_ON;
}
}
 
if(ServoIndex == 0) { // if we are at the sync gap
remainingPulseLength = PPM_FRAMELEN - ServoFrameTime; // generate sync gap by filling time to full frame time
ServoFrameTime = 0; // reset servo frame time
HEF4017R_ON; // enable HEF4017 reset
} else { // servo channels
remainingPulseLength = MINSERVOPULSE + SERVORANGE/2; // center position ~ 1.5ms
switch(ServoIndex) { // map servo channels
case 1: // Pitch Compensation Servo
ServoPitchOffset = (ServoPitchOffset * 3 + (int16_t)dynamicParams.ServoPitchControl * MULTIPLIER) / 4; // lowpass offset
ServoPitchValue = ServoPitchOffset; // offset (Range from 0 to 255 * 3 = 765)
if(staticParams.ServoPitchCompInvert & 0x01) {
// inverting movement of servo
ServoPitchValue += (int16_t)( ( (int32_t)staticParams.ServoPitchComp * MULTIPLIER * (integralGyroPitch / 128L ) ) / (256L) );
} else { // non inverting movement of servo
ServoPitchValue -= (int16_t)( ( (int32_t)staticParams.ServoPitchComp * MULTIPLIER * (integralGyroPitch / 128L ) ) / (256L) );
}
// limit servo value to its parameter range definition
if(ServoPitchValue < ((int16_t)staticParams.ServoPitchMin * MULTIPLIER)) {
ServoPitchValue = (int16_t)staticParams.ServoPitchMin * MULTIPLIER;
} else if(ServoPitchValue > ((int16_t)staticParams.ServoPitchMax * MULTIPLIER)) {
ServoPitchValue = (int16_t)staticParams.ServoPitchMax * MULTIPLIER;
}
remainingPulseLength += ServoPitchValue - (256 / 2) * MULTIPLIER; // shift ServoPitchValue to center position
ServoPitchValue /= MULTIPLIER;
break;
 
case 2: // Roll Compensation Servo
ServoRollOffset = (ServoRollOffset * 3 + (int16_t)80 * MULTIPLIER) / 4; // lowpass offset
ServoRollValue = ServoRollOffset; // offset (Range from 0 to 255 * 3 = 765)
//if(staticParams.ServoRollCompInvert & 0x01)
{ // inverting movement of servo
ServoRollValue += (int16_t)( ( (int32_t) 50 * MULTIPLIER * (integralGyroRoll / 128L ) ) / (256L) );
}
/* else
{ // non inverting movement of servo
ServoRollValue -= (int16_t)( ( (int32_t) 40 * MULTIPLIER * (IntegralGyroRoll / 128L ) ) / (256L) );
}
*/// limit servo value to its parameter range definition
if(ServoRollValue < ((int16_t)staticParams.ServoPitchMin * MULTIPLIER)) {
ServoRollValue = (int16_t)staticParams.ServoPitchMin * MULTIPLIER;
} else if(ServoRollValue > ((int16_t)staticParams.ServoPitchMax * MULTIPLIER)) {
ServoRollValue = (int16_t)staticParams.ServoPitchMax * MULTIPLIER;
}
remainingPulseLength += ServoRollValue - (256 / 2) * MULTIPLIER; // shift ServoRollValue to center position
ServoRollValue /= MULTIPLIER;
break;
 
default: // other servo channels
remainingPulseLength += 2 * PPM_in[ServoIndex]; // add channel value, factor of 2 because timer 1 increments 3.2µs
break;
}
// range servo pulse width
if(remainingPulseLength > MAXSERVOPULSE) remainingPulseLength = MAXSERVOPULSE; // upper servo pulse limit
else if(remainingPulseLength < MINSERVOPULSE) remainingPulseLength = MINSERVOPULSE; // lower servo pulse limit
// substract stop pulse width
remainingPulseLength -= PPM_STOPPULSE;
// accumulate time for correct sync gap
ServoFrameTime += remainingPulseLength;
}
} else { // we had a high pulse
TCCR2A |= (1<<COM2A0); // make a low pulse
// set pulsewidth to stop pulse width
remainingPulseLength = PPM_STOPPULSE;
// accumulate time for correct sync gap
ServoFrameTime += remainingPulseLength;
if(ServoActive && RC_Quality > 180) HEF4017R_OFF; // disable HEF4017 reset
ServoIndex++; // change to next servo channel
if(ServoIndex > staticParams.ServoRefresh) ServoIndex = 0; // reset to the sync gap
}
// set pulse output active
isGeneratingPulse = 1;
}
#endif
 
/*
* Cases:
* 1) 255 + 128 <= remainingPulseLength --> delta = 255
* 2) 255 <= remainingPulseLength < 255 + 128 --> delta = 255 - 128
* this is to avoid a too short delta on the last cycle, which would cause
* an interupt-on-interrupt condition and the loss of the last interrupt.
* 3) remainingPulseLength < 255 --> delta = remainingPulseLength
*/
#if defined(USE_NON_4017_SERVO_OUTPUTS) || defined(USE_4017_SERVO_OUTPUTS)
uint8_t delta;
if (remainingPulseLength >= (255 + 128)) {
delta = 255;
} else if (remainingPulseLength >= 255) {
delta = 255- 128;
} else {
delta = remainingPulseLength;
isGeneratingPulse = 0; // trigger to stop pulse
}
OCR2A = delta;
remainingPulseLength -= delta;
#endif
// Schedule the next OCR2A event. The counter is already reset at this time.
if (remainingPulseTime > 256+128) {
// Set output to reset to zero at next OCR match. It does not really matter when the output is set low again,
// as long as it happens once per pulse. This will, because all pulses are > 255+128 long.
OCR2A = 255;
TCCR2A &= ~(1<<COM2A0);
remainingPulseTime-=256;
} else if (remainingPulseTime > 256) {
// Remaining pulse lengths in the range [256..256+128] might cause trouble if handled the standard
// way, which is in chunks of 256. The remainder would be very small, possibly causing an interrupt on interrupt
// condition. Instead we now make a chunk of 128. The remaining chunk will then be in [128..255] which is OK.
remainingPulseTime-=128;
OCR2A=127;
} else {
// Set output to high at next OCR match. This is when the 4017 counter will advance by one. Also set reset low
TCCR2A |= (1<<COM2A0);
OCR2A = remainingPulseTime-1;
remainingPulseTime=0;
HEF4017R_OFF; // implement servo-disable here, by only removing the reset signal if ServoEnabled!=0.
}
}
/branches/dongfang_FC_rewrite/uart0.c
137,11 → 137,11
"Pitch Term ",
"Roll Term ",
"Yaw Term ",
"ca debug ", //15
"Throttle Term ", //15
"gyroP ",
"gyroI ",
"gyroD ",
"unused ",
"Acc Vector ",
"dHeightThrottle ", //20
"hoverThrottle ",
"M1 ",
494,7 → 494,7
// if data in the rxd buffer are not locked immediately return
if (!rxd_buffer_locked)
return;
uint8_t tempchar1, tempchar2;
uint8_t tempchar[3];
Decode64(); // decode data block in rxd_buffer
 
switch (rxd_buffer[1] - 'a') {
529,11 → 529,11
mixerMatrix_writeToEEProm();
while (!txd_complete)
; // wait for previous frame to be sent
tempchar1 = 1;
tempchar[0] = 1;
} else {
tempchar1 = 0;
tempchar[0] = 0;
}
SendOutData('M', FC_ADDRESS, 1, &tempchar1, 1);
SendOutData('M', FC_ADDRESS, 1, &tempchar, 1);
break;
 
case 'p': // get PPM channels
551,13 → 551,12
pRxData[0] = 5; // limit to 5
// load requested parameter set
paramSet_readFromEEProm(pRxData[0]);
tempchar1 = pRxData[0];
tempchar2 = EEPARAM_REVISION;
tempchar[0] = pRxData[0];
tempchar[1] = EEPARAM_REVISION;
tempchar[2] = sizeof(staticParams);
while (!txd_complete)
; // wait for previous frame to be sent
SendOutData('Q', FC_ADDRESS, 3, &tempchar1, sizeof(tempchar1),
&tempchar2, sizeof(tempchar2), (uint8_t *) &staticParams,
sizeof(staticParams));
SendOutData('Q', FC_ADDRESS, 2, &tempchar, 3, (uint8_t *) &staticParams, sizeof(staticParams));
break;
 
case 's': // save settings
568,14 → 567,14
{
memcpy(&staticParams, (uint8_t*) &pRxData[2], sizeof(staticParams));
paramSet_writeToEEProm(pRxData[0]);
tempchar1 = getActiveParamSet();
beepNumber(tempchar1);
tempchar[0] = getActiveParamSet();
beepNumber(tempchar[0]);
} else {
tempchar1 = 0; //indicate bad data
tempchar[0] = 0; //indicate bad data
}
while (!txd_complete)
; // wait for previous frame to be sent
SendOutData('S', FC_ADDRESS, 1, &tempchar1, sizeof(tempchar1));
SendOutData('S', FC_ADDRESS, 1, &tempchar, 1);
}
break;