forked from AeroQuad/AeroQuad
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Receiver.h
645 lines (571 loc) · 21.6 KB
/
Receiver.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
/*
AeroQuad v2.1 - October 2010
www.AeroQuad.com
Copyright (c) 2010 Ted Carancho. All rights reserved.
An Open Source Arduino based multicopter.
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
class Receiver {
public:
int receiverData[6];
int transmitterCommand[6];
int transmitterCommandSmooth[6];
int transmitterZero[3];
int transmitterTrim[3];
// Controls the strength of the commands sent from the transmitter
// xmitFactor ranges from 0.01 - 1.0 (0.01 = weakest, 1.0 - strongest)
float xmitFactor; // Read in from EEPROM
float transmitterSmooth[6];
float mTransmitter[6];
float bTransmitter[6];
Receiver(void) {
transmitterCommand[ROLL] = 1500;
transmitterCommand[PITCH] = 1500;
transmitterCommand[YAW] = 1500;
transmitterCommand[THROTTLE] = 1000;
transmitterCommand[MODE] = 1000;
transmitterCommand[AUX] = 1000;
for (channel = ROLL; channel < LASTCHANNEL; channel++)
transmitterCommandSmooth[channel] = 0;
for (channel = ROLL; channel < THROTTLE; channel++)
transmitterZero[channel] = 1500;
}
// ******************************************************************
// The following function calls must be defined in any new subclasses
// ******************************************************************
virtual void initialize(void);
virtual void read(void);
// **************************************************************
// The following functions are common between all Gyro subclasses
// **************************************************************
void _initialize(void) {
xmitFactor = readFloat(XMITFACTOR_ADR);
mTransmitter[ROLL] = readFloat(ROLLSCALE_ADR);
bTransmitter[ROLL] = readFloat(ROLLOFFSET_ADR);
mTransmitter[PITCH] = readFloat(PITCHSCALE_ADR);
bTransmitter[PITCH] = readFloat(PITCHOFFSET_ADR);
mTransmitter[YAW] = readFloat(YAWSCALE_ADR);
bTransmitter[YAW] = readFloat(YAWOFFSET_ADR);
mTransmitter[THROTTLE] = readFloat(THROTTLESCALE_ADR);
bTransmitter[THROTTLE] = readFloat(THROTTLEOFFSET_ADR);
mTransmitter[MODE] = readFloat(MODESCALE_ADR);
bTransmitter[MODE] = readFloat(MODEOFFSET_ADR);
mTransmitter[AUX] = readFloat(AUXSCALE_ADR);
bTransmitter[AUX] = readFloat(AUXOFFSET_ADR);
transmitterSmooth[THROTTLE] = readFloat(THROTTLESMOOTH_ADR);
transmitterSmooth[ROLL] = readFloat(ROLLSMOOTH_ADR);
transmitterSmooth[PITCH] = readFloat(PITCHSMOOTH_ADR);
transmitterSmooth[YAW] = readFloat(YAWSMOOTH_ADR);
transmitterSmooth[MODE] = readFloat(MODESMOOTH_ADR);
transmitterSmooth[AUX] = readFloat(AUXSMOOTH_ADR);
}
const int getRaw(byte channel) {
return receiverData[channel];
}
const int getData(byte channel) {
// reduce sensitivity of transmitter input by xmitFactor
return transmitterCommand[channel];
}
const int getTrimData(byte channel) {
return receiverData[channel] - transmitterTrim[channel];
}
const int getZero(byte channel) {
return transmitterZero[channel];
}
void setZero(byte channel, int value) {
transmitterZero[channel] = value;
}
const int getTransmitterTrim(byte channel) {
return transmitterTrim[channel];
}
void setTransmitterTrim(byte channel, int value) {
transmitterTrim[channel] = value;
}
const float getSmoothFactor(byte channel) {
return transmitterSmooth[channel];
}
void setSmoothFactor(byte channel, float value) {
transmitterSmooth[channel] = value;
}
const float getXmitFactor(void) {
return xmitFactor;
}
void setXmitFactor(float value) {
xmitFactor = value;
}
const float getTransmitterSlope(byte channel) {
return mTransmitter[channel];
}
void setTransmitterSlope(byte channel, float value) {
mTransmitter[channel] = value;
}
const float getTransmitterOffset(byte channel) {
return bTransmitter[channel];
}
void setTransmitterOffset(byte channel, float value) {
bTransmitter[channel] = value;
}
const float getAngle(byte channel) {
// Scale 1000-2000 usecs to -45 to 45 degrees
// m = 0.09, b = -135
// reduce transmitterCommand by xmitFactor to lower sensitivity of transmitter input
return (0.09 * transmitterCommand[channel]) - 135;
}
};
/*************************************************/
/*************** AeroQuad PCINT ******************/
/*************************************************/
#if defined(AeroQuad_v1) || defined(AeroQuad_v18) || defined(AeroQuad_Wii)
volatile uint8_t *port_to_pcmask[] = {
&PCMSK0,
&PCMSK1,
&PCMSK2
};
volatile static uint8_t PCintLast[3];
// Channel data
typedef struct {
byte edge;
unsigned long riseTime;
unsigned long fallTime;
unsigned long lastGoodWidth;
} pinTimingData;
volatile static pinTimingData pinData[24];
// Attaches PCINT to Arduino Pin
void attachPinChangeInterrupt(uint8_t pin) {
uint8_t bit = digitalPinToBitMask(pin);
uint8_t port = digitalPinToPort(pin);
uint8_t slot;
volatile uint8_t *pcmask;
// map pin to PCIR register
if (port == NOT_A_PORT) {
return;
}
else {
port -= 2;
pcmask = port_to_pcmask[port];
}
// set the mask
*pcmask |= bit;
// enable the interrupt
PCICR |= 0x01 << port;
}
// ISR which records time of rising or falling edge of signal
static void measurePulseWidthISR(uint8_t port) {
uint8_t bit;
uint8_t curr;
uint8_t mask;
uint8_t pin;
uint32_t currentTime;
uint32_t time;
// get the pin states for the indicated port.
curr = *portInputRegister(port+2);
mask = curr ^ PCintLast[port];
PCintLast[port] = curr;
// mask is pins that have changed. screen out non pcint pins.
if ((mask &= *port_to_pcmask[port]) == 0) {
return;
}
currentTime = micros();
// mask is pcint pins that have changed.
for (uint8_t i=0; i < 8; i++) {
bit = 0x01 << i;
if (bit & mask) {
pin = port * 8 + i;
// for each pin changed, record time of change
if (bit & PCintLast[port]) {
time = currentTime - pinData[pin].fallTime;
pinData[pin].riseTime = currentTime;
if ((time >= MINOFFWIDTH) && (time <= MAXOFFWIDTH))
pinData[pin].edge = RISING_EDGE;
else
pinData[pin].edge == FALLING_EDGE; // invalid rising edge detected
}
else {
time = currentTime - pinData[pin].riseTime;
pinData[pin].fallTime = currentTime;
if ((time >= MINONWIDTH) && (time <= MAXONWIDTH) && (pinData[pin].edge == RISING_EDGE)) {
pinData[pin].lastGoodWidth = time;
pinData[pin].edge = FALLING_EDGE;
}
}
}
}
}
SIGNAL(PCINT0_vect) {
measurePulseWidthISR(0);
}
SIGNAL(PCINT1_vect) {
measurePulseWidthISR(1);
}
SIGNAL(PCINT2_vect) {
measurePulseWidthISR(2);
}
class Receiver_AeroQuad : public Receiver {
private:
int receiverChannel[6];
int receiverPin[6];
public:
Receiver_AeroQuad() : Receiver(){
// Receiver pin definitions
// To pick your own PCINT pins look at page 2 of Atmega 328 data sheet and the Duemilanove data sheet and match the PCINT pin with the Arduino pinout
// These pins need to correspond to the ROLL/PITCH/YAW/THROTTLE/MODE/AUXPIN below
// Pin 2=18, Pin 3=19, Pin 4=20, Pin 5=21, Pin 6=22, Pin 7=23
receiverChannel[ROLL] = 2;
receiverChannel[PITCH] = 5;
receiverChannel[YAW] = 6;
receiverChannel[THROTTLE] = 4;
receiverChannel[MODE] = 7;
receiverChannel[AUX] = 8;
// defines ATmega328P pins (Arduino pins converted to ATmega328P pinouts)
receiverPin[ROLL] = 18;
receiverPin[PITCH] = 21;
receiverPin[YAW] = 22;
receiverPin[THROTTLE] = 20;
receiverPin[MODE] = 23;
receiverPin[AUX] = 0;
}
// Configure each receiver pin for PCINT
void initialize() {
this->_initialize(); // load in calibration xmitFactor from EEPROM
for (channel = ROLL; channel < LASTCHANNEL; channel++) {
pinMode(receiverChannel[channel], INPUT);
pinData[receiverChannel[channel]].edge = FALLING_EDGE;
attachPinChangeInterrupt(receiverChannel[channel]);
}
}
// Calculate PWM pulse width of receiver data
// If invalid PWM measured, use last known good time
void read(void) {
uint16_t data[6];
uint8_t oldSREG;
oldSREG = SREG;
cli();
// Buffer receiver values read from pin change interrupt handler
//for (channel = ROLL; channel < LASTCHANNEL; channel++) {
// data[channel] = pinData[receiverPin[channel]].lastGoodWidth;
//}
data[ROLL] = pinData[receiverPin[ROLL]].lastGoodWidth;
data[PITCH] = pinData[receiverPin[PITCH]].lastGoodWidth;
data[THROTTLE] = pinData[receiverPin[THROTTLE]].lastGoodWidth;
data[YAW] = pinData[receiverPin[YAW]].lastGoodWidth;
data[MODE] = pinData[receiverPin[MODE]].lastGoodWidth;
data[AUX] = pinData[receiverPin[AUX]].lastGoodWidth;
SREG = oldSREG;
for(channel = ROLL; channel < LASTCHANNEL; channel++) {
// Apply transmitter calibration adjustment
receiverData[channel] = (mTransmitter[channel] * data[channel]) + bTransmitter[channel];
// Smooth the flight control transmitter inputs
transmitterCommandSmooth[channel] = smooth(receiverData[channel], transmitterCommandSmooth[channel], transmitterSmooth[channel]);
}
// Reduce transmitter commands using xmitFactor and center around 1500
for (channel = ROLL; channel < THROTTLE; channel++)
transmitterCommand[channel] = ((transmitterCommandSmooth[channel] - transmitterZero[channel]) * xmitFactor) + transmitterZero[channel];
// No xmitFactor reduction applied for throttle, mode and
for (channel = THROTTLE; channel < LASTCHANNEL; channel++)
transmitterCommand[channel] = transmitterCommandSmooth[channel];
}
};
#endif
/******************************************************/
/*************** AeroQuad Mega PCINT ******************/
/******************************************************/
#if defined(AeroQuadMega_v1) || defined(AeroQuadMega_v2) || defined(AeroQuadMega_Wii)
volatile uint8_t *port_to_pcmask[] = {
&PCMSK0,
&PCMSK1,
&PCMSK2
};
volatile static uint8_t PCintLast[3];
// Channel data
typedef struct {
byte edge;
unsigned long riseTime;
unsigned long fallTime;
unsigned long lastGoodWidth;
} pinTimingData;
volatile static pinTimingData pinData[24];
static void MegaPcIntISR() {
uint8_t bit;
uint8_t curr;
uint8_t mask;
uint8_t pin;
uint32_t currentTime;
uint32_t time;
//curr = PORTK;
curr = *portInputRegister(11);
mask = curr ^ PCintLast[0];
PCintLast[0] = curr;
//Serial.println(curr,DEC);
// mask is pins that have changed. screen out non pcint pins.
if ((mask &= PCMSK2) == 0) {
return;
}
currentTime = micros();
// mask is pcint pins that have changed.
for (uint8_t i=0; i < 8; i++) {
bit = 0x01 << i;
if (bit & mask) {
pin = i;
// for each pin changed, record time of change
if (bit & PCintLast[0]) {
time = currentTime - pinData[pin].fallTime;
pinData[pin].riseTime = currentTime;
if ((time >= MINOFFWIDTH) && (time <= MAXOFFWIDTH))
pinData[pin].edge = RISING_EDGE;
else
pinData[pin].edge = FALLING_EDGE; // invalid rising edge detected
}
else {
time = currentTime - pinData[pin].riseTime;
pinData[pin].fallTime = currentTime;
if ((time >= MINONWIDTH) && (time <= MAXONWIDTH) && (pinData[pin].edge == RISING_EDGE)) {
pinData[pin].lastGoodWidth = time;
//Serial.println(pinData[4].lastGoodWidth);
pinData[pin].edge = FALLING_EDGE;
}
}
}
}
}
SIGNAL(PCINT2_vect) {
MegaPcIntISR();
}
class Receiver_AeroQuadMega : public Receiver {
private:
int receiverChannel[6];
int receiverPin[6];
//Receiver pin assignments for the Arduino Mega using an AeroQuad v1.x Shield
//The defines below are for documentation only of the Mega receiver input
//The real pin assignments happen in initializeMegaPcInt2()
//If you are using an AQ 1.x Shield, put a jumper wire between the Shield and Mega as indicated in the comments below
public:
Receiver_AeroQuadMega() : Receiver(){}
void initialize() {
this->_initialize(); // load in calibration xmitFactor from EEPROM
DDRK = 0;
PORTK = 0;
PCMSK2 |= 0x3F;
PCICR |= 0x1 << 2;
#ifdef AeroQuadMega_v1
receiverChannel[ROLL] = 67;
receiverChannel[PITCH] = 65;
receiverChannel[YAW] = 64;
receiverChannel[THROTTLE] = 66;
receiverChannel[MODE] = 63;
receiverChannel[AUX] = 62;
// defines ATmega328P pins (Arduino pins converted to ATmega328P pinouts)
receiverPin[ROLL] = 5;
receiverPin[PITCH] = 3;
receiverPin[YAW] = 2;
receiverPin[THROTTLE] = 4;
receiverPin[MODE] = 1;
receiverPin[AUX] = 0;
#else
receiverChannel[ROLL] = 63;
receiverChannel[PITCH] = 64;
receiverChannel[YAW] = 65;
receiverChannel[THROTTLE] = 62;
receiverChannel[MODE] = 66;
receiverChannel[AUX] = 67;
// defines ATmega328P pins (Arduino pins converted to ATmega328P pinouts)
receiverPin[ROLL] = 1;
receiverPin[PITCH] = 2;
receiverPin[YAW] = 3;
receiverPin[THROTTLE] = 0;
receiverPin[MODE] = 4;
receiverPin[AUX] = 5;
#endif
for (channel = ROLL; channel < LASTCHANNEL; channel++)
pinData[receiverChannel[channel]].edge = FALLING_EDGE;
}
// Calculate PWM pulse width of receiver data
// If invalid PWM measured, use last known good time
void read(void) {
uint16_t data[6];
uint8_t oldSREG;
oldSREG = SREG;
cli();
// Buffer receiver values read from pin change interrupt handler
for (channel = ROLL; channel < LASTCHANNEL; channel++)
data[channel] = pinData[receiverPin[channel]].lastGoodWidth;
SREG = oldSREG;
for(channel = ROLL; channel < LASTCHANNEL; channel++) {
// Apply transmitter calibration adjustment
receiverData[channel] = (mTransmitter[channel] * data[channel]) + bTransmitter[channel];
// Smooth the flight control transmitter inputs
transmitterCommandSmooth[channel] = smooth(receiverData[channel], transmitterCommandSmooth[channel], transmitterSmooth[channel]);
//transmitterCommandSmooth[channel] = transmitterFilter[channel].filter(receiverData[channel]);
}
// Reduce transmitter commands using xmitFactor and center around 1500
for (channel = ROLL; channel < THROTTLE; channel++)
transmitterCommand[channel] = ((transmitterCommandSmooth[channel] - transmitterZero[channel]) * xmitFactor) + transmitterZero[channel];
// No xmitFactor reduction applied for throttle, mode and AUX
for (channel = THROTTLE; channel < LASTCHANNEL; channel++)
transmitterCommand[channel] = transmitterCommandSmooth[channel];
}
};
#endif
/*********************************************/
/********** ArduCopter PPM Input *************/
/*********************************************/
#ifdef ArduCopter
#include <avr/interrupt.h>
volatile unsigned int Start_Pulse = 0;
volatile unsigned int Stop_Pulse = 0;
volatile unsigned int Pulse_Width = 0;
volatile byte PPM_Counter=0;
volatile int PWM_RAW[8] = {2400,2400,2400,2400,2400,2400,2400,2400};
/****************************************************
Interrupt Vector
****************************************************/
ISR(TIMER4_CAPT_vect)//interrupt.
{
if(((1<<ICES4)&TCCR4B) >= 0x01)
{
if(Start_Pulse>Stop_Pulse) //Checking if the Stop Pulse overflow the register, if yes i normalize it.
{
Stop_Pulse+=40000; //Nomarlizing the stop pulse.
}
Pulse_Width=Stop_Pulse-Start_Pulse; //Calculating pulse
if(Pulse_Width>5000) //Verify if this is the sync pulse
{
PPM_Counter=0; //If yes restart the counter
}
else
{
PWM_RAW[PPM_Counter]=Pulse_Width; //Saving pulse.
PPM_Counter++;
}
Start_Pulse=ICR4;
TCCR4B &=(~(1<<ICES4)); //Changing edge detector.
}
else
{
Stop_Pulse=ICR4; //Capturing time stop of the drop edge
TCCR4B |=(1<<ICES4); //Changing edge detector.
//TCCR4B &=(~(1<<ICES4));
}
//Counter++;
}
class Receiver_ArduCopter : public Receiver {
private:
int receiverPin[6];
public:
Receiver_ArduCopter() : Receiver(){
receiverPin[ROLL] = 0;
receiverPin[PITCH] = 1;
receiverPin[YAW] = 3;
receiverPin[THROTTLE] = 2;
receiverPin[MODE] = 4;
receiverPin[AUX] = 5;
}
void initialize(void) {
this->_initialize(); // load in calibration and xmitFactor from EEPROM
/*Note that timer4 is configured to used the Input capture for PPM decoding and to pulse two servos
OCR4A is used as the top counter*/
pinMode(49, INPUT);
pinMode(7,OUTPUT);
pinMode(8,OUTPUT);
//Remember the registers not declared here remains zero by default...
TCCR4A =((1<<WGM40)|(1<<WGM41)|(1<<COM4C1)|(1<<COM4B1)|(1<<COM4A1));
TCCR4B = ((1<<WGM43)|(1<<WGM42)|(1<<CS41)|(1<<ICES4)); //Prescaler set to 8, that give us a resolution of 2us, read page 134 of data sheet
OCR4A = 40000; ///50hz freq...Datasheet says (system_freq/prescaler)/target frequency. So (16000000hz/8)/50hz=40000,
//must be 50hz because is the servo standard (every 20 ms, and 1hz = 1sec) 1000ms/20ms=50hz, elementary school stuff...
OCR4B = 3000; //PH4, OUT5
OCR4C = 3000; //PH5, OUT4
TIMSK4 |= (1<<ICIE4); //Timer interrupt mask
sei();
}
void read(void) {
for(channel = ROLL; channel < LASTCHANNEL; channel++) {
// Apply transmitter calibration adjustment
receiverData[channel] = (mTransmitter[channel] * ((PWM_RAW[receiverPin[channel]]+600)/2)) + bTransmitter[channel];
// Smooth the flight control transmitter inputs
transmitterCommandSmooth[channel] = smooth(receiverData[channel], transmitterCommandSmooth[channel], transmitterSmooth[channel]);
}
// Reduce transmitter commands using xmitFactor and center around 1500
for (channel = ROLL; channel < THROTTLE; channel++)
transmitterCommand[channel] = ((transmitterCommandSmooth[channel] - transmitterZero[channel]) * xmitFactor) + transmitterZero[channel];
// No xmitFactor reduction applied for throttle, mode and
for (channel = THROTTLE; channel < LASTCHANNEL; channel++)
transmitterCommand[channel] = transmitterCommandSmooth[channel];
}
};
#endif
/*************************************************/
/*************** Multipilot PCINT ****************/
/*************************************************/
#if defined(Multipilot) || defined(MultipilotI2C)
#define ROLLCH 4
#define PITCHCH 3
#define YAWCH 1
#define THROTTLECH 2
#define MODECH 8
#define AUXCH 7
#define CAMERAROLLCH 5
#define CAMERAPITCHCH 6
class Receiver_Multipilot : public Receiver {
private:
int receiverChannel[6];
public:
Receiver_Multipilot() : Receiver(){
receiverChannel[ROLL] = ROLLCH;
receiverChannel[PITCH] = PITCHCH;
receiverChannel[YAW] = YAWCH;
receiverChannel[THROTTLE] = THROTTLECH;
receiverChannel[MODE] = MODECH;
receiverChannel[AUX] = AUXCH;
}
// Configure each receiver pin for PCINT
void initialize() {
this->_initialize(); // load in calibration xmitFactor from EEPROM
ServoDecode.begin();
ServoDecode.setFailsafe(3,1234); // set channel 3 failsafe pulse width
}
// Calculate PWM pulse width of receiver data
// If invalid PWM measured, use last known good time
void read(void) {
uint16_t data[6];
if(ServoDecode.getState()!= READY_state)
{
for (channel = ROLL; channel < LASTCHANNEL; channel++)
{
safetyCheck=0;
data[channel]=5000;
}
}
else
{
data[ROLL] = ServoDecode.GetChannelPulseWidth((int)receiverChannel[ROLL]);
data[PITCH] = ServoDecode.GetChannelPulseWidth((int)receiverChannel[PITCH]);
data[THROTTLE] = ServoDecode.GetChannelPulseWidth((int)receiverChannel[THROTTLE]);
data[YAW] = ServoDecode.GetChannelPulseWidth((int)receiverChannel[YAW]);
data[MODE] = ServoDecode.GetChannelPulseWidth((int)receiverChannel[MODE]);
data[AUX] = ServoDecode.GetChannelPulseWidth((int)receiverChannel[AUX]);
safetyCheck=1;
}
for(channel = ROLL; channel < LASTCHANNEL; channel++) {
// Apply transmitter calibration adjustment
receiverData[channel] = (mTransmitter[channel] * data[channel]) + bTransmitter[channel];
// Smooth the flight control transmitter inputs
transmitterCommandSmooth[channel] = smooth(receiverData[channel], transmitterCommandSmooth[channel], transmitterSmooth[channel]);
}
// Reduce transmitter commands using xmitFactor and center around 1500
for (channel = ROLL; channel < THROTTLE; channel++)
transmitterCommand[channel] = ((transmitterCommandSmooth[channel] - transmitterZero[channel]) * xmitFactor) + transmitterZero[channel];
//transmitterCommand[channel] = ((transmitterCommandSmooth[channel] - transmitterZero[channel])) + transmitterZero[channel];
// No xmitFactor reduction applied for throttle, mode and
for (channel = THROTTLE; channel < LASTCHANNEL; channel++)
transmitterCommand[channel] = transmitterCommandSmooth[channel];
}
};
#endif