1 // file for FRSKY telemetry (SPORT and HUB)
3 #include "oXs_out_frsky.h"
4 #if defined(PROTOCOL) && ( (PROTOCOL == FRSKY_SPORT) || ( PROTOCOL == FRSKY_HUB ) || (PROTOCOL == FRSKY_SPORT_HUB ) ) //if Frsky protocol is used
7 // ************************* Several parameters to help debugging
8 //#define DEBUG_LOAD_SPORT
10 //#define DEBUG_SPORT_RECEIVED
11 //#define DEBUGSENDDATA
12 //#define DEBUGSENDSENSITIVITY
13 //#define DEBUGNEXTVALUETYPE
14 //#define DEBUGSENDDATADELAY
15 //#define DEBUGTRANSMITDELAY
16 //#define DEBUGLOADVALUETOSEND
17 //#define DEBUGLOADVALUETOSENDALTIMETER
18 //#define DEBUGLOADVALUETOSENDVERTICALSPEED
19 //#define DEBUGLOADVALUETOSENDALTIMETER_2
20 //#define DEBUGLOADVALUETOSENDVERTICALSPEED_2
22 //#define DEBUGLOADVALUETOSENDVOLT1
23 //#define DEBUGLOADVALUETOSENDVOLT2
24 //#define DEBUGLOADVALUETOSENDSENSITIVITY
25 //#define DEBUGLOADVALUETOSENDALT_OVER_10_SEC
26 //#define DEBUGLOADVALUETOSENDSENSITIVITY_2
27 //#define DEBUGLOADVALUETOSENDALT_OVER_10_SEC_2
29 //#define DEBUGLOADVALUETOSENDCELL_1_2
30 //#define DEBUGLOADVALUETOSENDCELL_3_4
31 //#define DEBUGLOADVALUETOSENDCELL_5_6
32 //#define DEBUGLOADVALUETOSENDCURRENTMA
33 //#define DEBUGLOADVALUETOSENDMILLIAH
34 //#define DEBUGHUBPROTOCOL
35 //#define DEBUGWITHFIXVALUE // for SPORT protocol only; send a value varying continuously (cycling) between min and max value (see code below)
38 extern OXS_MS5611 oXs_MS5611
;
39 extern OXS_VOLTAGE oXs_Voltage
;
40 extern OXS_CURRENT oXs_Current
;
41 extern OXS_4525 oXs_4525
;
42 extern OXS_SDP3X oXs_sdp3x
;
43 #if defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(ADS_CURRENT_BASED_ON)
44 extern CURRENTDATA adsCurrentData
;
47 extern unsigned long micros( void ) ;
48 extern unsigned long millis( void ) ;
49 extern void delay(unsigned long ms
) ;
51 //used only by Sport protocol
52 extern uint8_t volatile sportData
[7] ;
53 uint8_t volatile TxData
[8] ;
54 uint8_t volatile TxDataIdx
;
56 extern uint8_t LastRx
;
57 static volatile uint8_t prevLastRx
; // just for testing
59 uint8_t volatile sportDataLock
;
60 extern uint8_t volatile sendStatus
;
61 #if defined(VFAS_SOURCE)
62 struct ONE_MEASUREMENT vfas
;
65 #if ( defined(ARDUINO_MEASURES_A_CURRENT) && (ARDUINO_MEASURES_A_CURRENT == YES) ) || ( defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(ADS_CURRENT_BASED_ON))
66 struct ONE_MEASUREMENT sport_currentData
;
69 #if defined(GPS_INSTALLED)
70 struct ONE_MEASUREMENT sport_gps_lon
;
71 struct ONE_MEASUREMENT sport_gps_lat
;
72 struct ONE_MEASUREMENT sport_gps_alt
;
73 struct ONE_MEASUREMENT sport_gps_speed
;
74 struct ONE_MEASUREMENT sport_gps_course
;
75 #if defined GPS_TRANSMIT_TIME
76 struct ONE_MEASUREMENT sport_gps_date
;
77 struct ONE_MEASUREMENT sport_gps_time
;
82 extern struct ONE_MEASUREMENT sport_rpm
;
84 //used only by Hub protocol
85 //static int fieldToSend ;
86 //static bool fieldOk ;
87 extern uint8_t volatile hubData
[MAXSIZEBUFFER
] ;
88 //extern uint8_t volatile hubCurrentData ; //index of current data
89 extern uint8_t volatile hubMaxData
; // max number of data prepared to be send
92 //Used by both protocols
93 volatile bool sportAvailable
= false ;
94 //int fieldContainsData[][5] = { SETUP_FRSKY_DATA_TO_SEND } ; // contains the set up of field to be transmitted
95 //int numberOfFields = sizeof(fieldContainsData) / sizeof(fieldContainsData[0]) ;
96 //static uint16_t convertToSportId[15] = { FRSKY_SPORT_ID } ; // this array is used to convert an index inside fieldContainsData[][0] into the SPORT field Id (or defaultfield)
97 //static uint8_t convertToHubId[15] = { FRSKY_HUB_ID } ; //// this array is used to convert an index inside fieldContainsData[][0] into the Hub field Id (or defaultfield)
98 //static uint8_t currentFieldToSend = 0 ;
99 extern volatile uint8_t state
; //!< Holds the state of the UART.
102 #ifdef DEBUG_SPORT_RECEIVED
103 volatile uint16_t sportRcvCount
;
108 OXS_OUT::OXS_OUT(uint8_t pinTx
,HardwareSerial
&print
)
110 OXS_OUT::OXS_OUT(uint8_t pinTx
)
115 printer
= &print
; //operate on the address of print
120 // **************** Setup the FRSky OutputLib *********************
121 void OXS_OUT::setup() {
122 // here we look if sport is available or not; when available, sport protocol must be activated otherwise hub protocol
124 TRXDDR
&= ~( 1 << PIN_SERIALTX
) ; // PIN is input, tri-stated.
125 TRXPORT
&= ~( 1 << PIN_SERIALTX
) ; // PIN is input, tri-stated.
126 #if PIN_SERIALTX == 7
127 ADCSRB
&= ~(1<<ACME
) ;
128 ACSR
= (1<<ACBG
) | (1 << ACIS1
) ;
129 DIDR1
|= (1<<AIN1D
) ;
132 #if defined( PROTOCOL ) && ( PROTOCOL == FRSKY_SPORT )
135 sportAvailable
= true ; // force the SPORT protocol
136 #elif defined(PROTOCOL) && ( PROTOCOL == FRSKY_HUB )
138 sportAvailable
= false ; // force the HUB protocol
139 #else // we will detect automatically if SPORT is available
140 // Activate pin change interupt 2 on Tx pin
141 #if PIN_SERIALTX == 4
142 PCMSK2
|= 0x10 ; // IO4 (PD4) on Arduini mini
143 #elif PIN_SERIALTX == 2
144 PCMSK2
|= 0x04 ; // IO2 (PD2) on Arduini mini
146 #if PIN_SERIALTX != 7
147 #error "This PIN is not supported"
149 #endif // test on PIN_SERIALTX
150 delay(1500) ; // this delay has been added because some users reported that SPORT is not recognised with a X6R ; perhaps is it related to the EU firmware (2015)
151 #ifdef DEBUG_SPORT_PIN
152 digitalWrite(DEBUG_SPORT_PIN
, HIGH
); // Set the pulse used during SPORT detection to HIGH because detecttion is starting
155 #if PIN_SERIALTX == 7
156 ACSR
|= ( 1<<ACI
) ; // clear pending interrupt
158 PCIFR
= (1<<PCIF2
) ; // clear pending interrupt
160 delay(20) ; // to see if SPORT is active, we have to wait at least 12 msec and check bit PCIF2 from PCIFR; if bit is set, it is SPORT
161 #ifdef DEBUG_SPORT_PIN
162 digitalWrite(DEBUG_SPORT_PIN
, LOW
); // Set the pulse used during SPORT detection to LOW because detection is done
164 #if PIN_SERIALTX == 7
165 if ( ( ACSR
& (1<<ACI
)) == 0 ) {
167 if ( ( PCIFR
& (1<<PCIF2
)) == 0 ) {
169 sportAvailable
= false ;
173 sportAvailable
= true ;
177 #endif // end test on FRSKY
179 printer
->print(F("FRSky Output Module: TX Pin="));
180 printer
->println(_pinTx
);
181 printer
->print(F("Sport protocol= "));
182 printer
->println(sportAvailable
);
187 void OXS_OUT::sendData() {
188 #if defined( PROTOCOL ) && ( PROTOCOL == FRSKY_SPORT )
190 #elif defined(PROTOCOL) && ( PROTOCOL == FRSKY_HUB )
192 #else // we will detect automatically if SPORT is available
193 if (sportAvailable
) {
202 //****************************************************** Look which value can be transmitted and load it in a set of fields used by interrupt routine
203 // oXs reacts on 6 sensorId being send by the Rx
204 // In the main loop, we look periodically (calling function sendData ) if a new data has to be preloaded for each of the 6 sensors
205 // It is the ISR that send the data and set a flag (to 1) in a bit of "frskyStatus" to say that a new data has to be loaded (bit 0...5 are used).
206 // The main loop set the bit to 0 when a data has been loaded.
208 #if defined( PROTOCOL ) && ( ( PROTOCOL == FRSKY_SPORT ) || ( PROTOCOL == FRSKY_SPORT_HUB ) )
210 volatile uint8_t idToReply
; // each bit (0..5) reports (set to 1) if oXs has to reply to a pooling on a specific Id (this has been added because oXs has to reply with all 0x00 when he has not yet data available
211 volatile uint8_t frskyStatus
= 0x3F ; //Status of SPORT protocol saying if data is to load in work field (bit 0...5 are used for the 6 sensorId), initially all data are to be loaded
212 uint8_t currFieldIdx
[6] = { 0 , 2, 5 , 10 , 17 , 21 } ; // per sensor, say which field has been loaded the last time (so next time, we have to search from the next one)
213 const uint8_t fieldMinIdx
[7] = { 0 , 2, 5 , 10 , 17 , 21 , 24 } ; // per sensor, say the first field index ; there is one entry more in the array to know the last index
214 const uint8_t fieldId
[24] = { 0x10 , 0x11 , 0x30 , 0x30 , 0x30 , 0x21 , 0x20 , 0x60 ,0x90, 0x91 , 0x80, 0x80 , 0x82 , 0x83 , 0x84 , 0x85, 0x85, 0x50 , 0x40 , 0x41 , 0xA0 , 0x70 , 0x71 , 0x72 } ; //fieldID to send to Tx (to shift 4 bits to left
215 struct ONE_MEASUREMENT
* p_measurements
[24] ; // array of 22 pointers (each pointer point to a structure containing a byte saying if a value is available and to the value.
216 // There are 20 possible fields to transmit in SPORT
217 // They are grouped per sensor ID
218 // Sensor 0 start from index = 0 and contains Alt + Vspeed
219 // Sensor 1 start from index = 2 and contains Cell_1_2 , Cell_3_4 and Cell_5_6
220 // Sensor 2 start from index = 5 and contains vfas , current and fuel
221 // Sensor 3 start from index = 10 and contains gps_lon , gps_lat, gps_alt , gps_speed and gps_course
222 // Sensor 4 start from index = 15 and contains rpm, T1, T2, airspeed
223 // Sensor 5 start from index = 19 and contains accX , accY, accZ
225 int32_t dataValue
[6] ; // keep for each sensor id the next value to be sent
226 uint8_t dataId
[6] ; // keep for each sensor id the Id of next field to be sent
230 struct ONE_MEASUREMENT no_data
= { 0, 0 } ;
232 void initMeasurement() {
233 // pointer to Altitude
235 p_measurements
[0] = &oXs_MS5611
.varioData
.relativeAlt
; // we use always relative altitude in Frsky protocol
238 p_measurements
[0] = &no_data
;
243 p_measurements
[1] = &mainVspeed
;
245 p_measurements
[1] = &no_data
;
248 // pointer to Cell_1_2
249 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(NUMBEROFCELLS) && (NUMBEROFCELLS > 0)
250 p_measurements
[2] = &oXs_Voltage
.voltageData
.mVoltCell_1_2
;
253 p_measurements
[2] = &no_data
;
256 // pointer to Cell_3_4
257 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(NUMBEROFCELLS) && (NUMBEROFCELLS > 2)
258 p_measurements
[3] = &oXs_Voltage
.voltageData
.mVoltCell_3_4
;
260 p_measurements
[3] = &no_data
;
263 // pointer to Cell_5_6
264 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(NUMBEROFCELLS) && (NUMBEROFCELLS > 4)
265 p_measurements
[4] = &oXs_Voltage
.voltageData
.mVoltCell_5_6
;
267 p_measurements
[4] = &no_data
;
270 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VFAS_SOURCE) && ( VFAS_SOURCE == VOLT_1 || VFAS_SOURCE == VOLT_2 || VFAS_SOURCE == VOLT_3 || VFAS_SOURCE == VOLT_4 || VFAS_SOURCE == VOLT_5 || VFAS_SOURCE == VOLT_6 )
271 p_measurements
[5] = &vfas
;
273 #elif defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(VFAS_SOURCE) && ( VFAS_SOURCE == ADS_VOLT_1 || VFAS_SOURCE == ADS_VOLT_2 || VFAS_SOURCE == ADS_VOLT_3 || VFAS_SOURCE == ADS_VOLT_4 )
274 p_measurements
[5] = &vfas
;
277 p_measurements
[5] = &no_data
;
280 // pointer to current
281 #if ( defined(ARDUINO_MEASURES_A_CURRENT) && (ARDUINO_MEASURES_A_CURRENT == YES) ) || ( defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(ADS_CURRENT_BASED_ON))
282 p_measurements
[6] = &sport_currentData
;
285 p_measurements
[6] = &no_data
;
289 #if defined(FUEL_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES)&& ( FUEL_SOURCE == VOLT_1 || FUEL_SOURCE == VOLT_2 || FUEL_SOURCE == VOLT_3 || FUEL_SOURCE == VOLT_4 || FUEL_SOURCE == VOLT_5 || FUEL_SOURCE == VOLT_6 )
290 p_measurements
[7] = &oXs_Voltage
.voltageData
.mVolt
[FUEL_SOURCE
- VOLT_1
];
292 #elif defined(FUEL_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( FUEL_SOURCE == ADS_VOLT_1 || FUEL_SOURCE == ADS_VOLT_2 || FUEL_SOURCE == ADS_VOLT_3 || FUEL_SOURCE == ADS_VOLT_4 )
293 p_measurements
[7] = &ads_Conv
[FUEL_SOURCE
- ADS_VOLT_1
];
296 p_measurements
[7] = &no_data
;
300 #if defined(A3_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( A3_SOURCE == VOLT_1 || A3_SOURCE == VOLT_2 || A3_SOURCE == VOLT_3 || A3_SOURCE == VOLT_4 || A3_SOURCE == VOLT_5 || A3_SOURCE == VOLT_6 )
301 p_measurements
[8] = &oXs_Voltage
.voltageData
.mVolt
[A3_SOURCE
- VOLT_1
];
303 #elif defined(A3_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( A3_SOURCE == ADS_VOLT_1 || A3_SOURCE == ADS_VOLT_2 || A3_SOURCE == ADS_VOLT_3 || A3_SOURCE == ADS_VOLT_4 )
304 p_measurements
[8] = &ads_Conv
[A3_SOURCE
- ADS_VOLT_1
];
307 p_measurements
[8] = &no_data
;
311 #if defined(A4_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( A4_SOURCE == VOLT_1 || A4_SOURCE == VOLT_2 || A4_SOURCE == VOLT_3 || A4_SOURCE == VOLT_4 || A4_SOURCE == VOLT_5 || A4_SOURCE == VOLT_6 )
312 p_measurements
[9] = &oXs_Voltage
.voltageData
.mVolt
[A4_SOURCE
- VOLT_1
];
314 #elif defined(A4_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( A4_SOURCE == ADS_VOLT_1 || A4_SOURCE == ADS_VOLT_2 || A4_SOURCE == ADS_VOLT_3 || A4_SOURCE == ADS_VOLT_4 )
315 p_measurements
[9] = &ads_Conv
[A4_SOURCE
- ADS_VOLT_1
];
318 p_measurements
[9] = &no_data
;
322 // pointer to GPS lon
323 #if defined(GPS_INSTALLED)
324 p_measurements
[10] = &sport_gps_lon
;
327 p_measurements
[10] = &no_data
;
330 // pointer to GPS lat
331 #if defined(GPS_INSTALLED)
332 p_measurements
[11] = &sport_gps_lat
;
334 p_measurements
[11] = &no_data
;
337 // pointer to GPS alt
338 #if defined(GPS_INSTALLED)
339 p_measurements
[12] = &sport_gps_alt
;
341 p_measurements
[12] = &no_data
;
344 // pointer to GPS speed
345 #if defined(GPS_INSTALLED)
346 p_measurements
[13] = &sport_gps_speed
;
348 p_measurements
[13] = &no_data
;
351 // pointer to GPS course
352 #if defined(GPS_INSTALLED)
353 p_measurements
[14] = &sport_gps_course
;
355 p_measurements
[14] = &no_data
;
358 #if defined(GPS_TRANSMIT_TIME)
359 // pointer to GPS date
360 #if defined(GPS_INSTALLED)
361 p_measurements
[15] = &sport_gps_date
;
362 p_measurements
[16] = &sport_gps_time
;
364 p_measurements
[15] = &no_data
;
365 p_measurements
[16] = &no_data
;
368 p_measurements
[15] = &no_data
;
369 p_measurements
[16] = &no_data
;
373 #if defined(MEASURE_RPM)
374 p_measurements
[17] = &sport_rpm
;
377 p_measurements
[17] = &no_data
;
381 #if defined(T1_SOURCE) && ( T1_SOURCE == TEST_1)
382 p_measurements
[18] = &test1
;
384 #elif defined(T1_SOURCE) && ( T1_SOURCE == TEST_2)
385 p_measurements
[18] = &test2
;
387 #elif defined(T1_SOURCE) && ( T1_SOURCE == TEST_3)
388 p_measurements
[18] = &test3
;
390 #elif defined(T1_SOURCE) && ( T1_SOURCE == GLIDER_RATIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
391 p_measurements
[18] = &gliderRatio
;
393 #elif defined(T1_SOURCE) && ( T1_SOURCE == SECONDS_SINCE_T0 ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
394 p_measurements
[18] = &secFromT0
;
396 #elif defined(T1_SOURCE) && ( T1_SOURCE == AVERAGE_VSPEED_SINCE_TO ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
397 p_measurements
[18] = &averageVspeedSinceT0
;
399 #elif defined(T1_SOURCE) && ( T1_SOURCE == SENSITIVITY) && defined(VARIO)
400 p_measurements
[18] = &oXs_MS5611
.varioData
.sensitivity
;
402 #elif defined(T1_SOURCE) && ( T1_SOURCE == PPM) && ( defined(PIN_PPM) || ( defined(PPM_VIA_SPORT) && ( (PROTOCOL == FRSKY_SPORT) || (PROTOCOL == FRSKY_SPORT_HUB) ) ) )
403 p_measurements
[18] = &ppm
;
405 #elif defined(T1_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( T1_SOURCE == VOLT_1 || T1_SOURCE == VOLT_2 || T1_SOURCE == VOLT_3 || T1_SOURCE == VOLT_4 || T1_SOURCE == VOLT_5 || T1_SOURCE == VOLT_6 )
406 p_measurements
[18] = &oXs_Voltage
.voltageData
.mVolt
[T1_SOURCE
- VOLT_1
] ;
408 #elif defined(T1_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( T1_SOURCE == ADS_VOLT_1 || T1_SOURCE == ADS_VOLT_2 || T1_SOURCE == ADS_VOLT_3 || T1_SOURCE == ADS_VOLT_4 )
409 p_measurements
[18] = &ads_Conv
[T1_SOURCE
- ADS_VOLT_1
];
412 p_measurements
[18] = &no_data
; // T1
416 #if defined(T2_SOURCE) && ( T2_SOURCE == TEST_1)
417 p_measurements
[19] = &test1
;
419 #elif defined(T2_SOURCE) && ( T2_SOURCE == TEST_2)
420 p_measurements
[19] = &test2
;
422 #elif defined(T2_SOURCE) && ( T2_SOURCE == TEST_3)
423 p_measurements
[19] = &test3
;
425 #elif defined(T2_SOURCE) && ( T2_SOURCE == GLIDER_RATIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
426 p_measurements
[19] = &gliderRatio
;
428 #elif defined(T2_SOURCE) && ( T2_SOURCE == SECONDS_SINCE_T0 ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
429 p_measurements
[19] = &secFromT0
;
431 #elif defined(T2_SOURCE) && ( T2_SOURCE == AVERAGE_VSPEED_SINCE_TO ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
432 p_measurements
[19] = &averageVspeedSinceT0
;
434 #elif defined(T2_SOURCE) && ( T2_SOURCE == SENSITIVITY) && defined(VARIO)
435 p_measurements
[19] = &oXs_MS5611
.varioData
.sensitivity
;
437 #elif defined(T2_SOURCE) && ( T2_SOURCE == PPM) && ( defined(PIN_PPM) || ( defined(PPM_VIA_SPORT) && ( (PROTOCOL == FRSKY_SPORT) || (PROTOCOL == FRSKY_SPORT_HUB) ) ) )
438 p_measurements
[19] = &ppm
;
440 #elif defined(T2_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( T2_SOURCE == VOLT_1 || T2_SOURCE == VOLT_2 || T2_SOURCE == VOLT_3 || T2_SOURCE == VOLT_4 || T2_SOURCE == VOLT_5 || T2_SOURCE == VOLT_6 )
441 p_measurements
[19] = &oXs_Voltage
.voltageData
.mVolt
[T2_SOURCE
- VOLT_1
] ;
443 #elif defined(T2_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( T2_SOURCE == ADS_VOLT_1 || T2_SOURCE == ADS_VOLT_2 || T2_SOURCE == ADS_VOLT_3 || T2_SOURCE == ADS_VOLT_4 )
444 p_measurements
[19] = &ads_Conv
[T2_SOURCE
- ADS_VOLT_1
];
447 p_measurements
[19] = &no_data
; // T2
452 // pointer to airspeed
453 #if defined(AIRSPEED)
454 p_measurements
[20] = &oXs_4525
.airSpeedData
.airSpeed
;
456 #elif defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(ADS_AIRSPEED_BASED_ON)
457 p_measurements
[20] = &oXs_ads1115
.adsAirSpeedData
.airSpeed
;
459 #elif defined(AIRSPEED_SDP3X)
460 p_measurements
[20] = &oXs_sdp3x
.airSpeedData
.airSpeed
;
463 p_measurements
[20] = &no_data
;
467 #if defined(ACCX_SOURCE) && ( ACCX_SOURCE == TEST_1)
468 p_measurements
[21] = &test1
; // accX
470 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == TEST_2)
471 p_measurements
[21] = &test2
; // accX
473 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == TEST_3)
474 p_measurements
[21] = &test3
; // accX
476 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == GLIDER_RATIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
477 p_measurements
[21] = &gliderRatio
;
479 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == SECONDS_SINCE_T0 ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
480 p_measurements
[21] = &secFromT0
;
482 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == AVERAGE_VSPEED_SINCE_TO ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
483 p_measurements
[21] = &averageVspeedSinceT0
;
485 #elif defined(ACCX_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( ACCX_SOURCE == VOLT_1 || ACCX_SOURCE == VOLT_2 || ACCX_SOURCE == VOLT_3 || ACCX_SOURCE == VOLT_4 || ACCX_SOURCE == VOLT_5 || ACCX_SOURCE == VOLT_6 )
486 p_measurements
[21] = &oXs_Voltage
.voltageData
.mVolt
[ACCX_SOURCE
- VOLT_1
] ;
488 #elif defined(ACCX_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( ACCX_SOURCE == ADS_VOLT_1 || ACCX_SOURCE == ADS_VOLT_2 || ACCX_SOURCE == ADS_VOLT_3 || ACCX_SOURCE == ADS_VOLT_4 )
489 p_measurements
[21] = &ads_Conv
[ACCX_SOURCE
- ADS_VOLT_1
];
491 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == PITCH) && defined(USE_6050)
492 p_measurements
[21] = &pitch
; // accX
494 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == ROLL) && defined(USE_6050)
495 p_measurements
[21] = &roll
; // accX
497 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == YAW) && defined(USE_6050)
498 p_measurements
[21] = &yaw
; // accX
501 p_measurements
[21] = &no_data
; // accX
505 #if defined(ACCY_SOURCE) && ( ACCY_SOURCE == TEST_1)
506 p_measurements
[22] = &test1
; // accY
508 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == TEST_2)
509 p_measurements
[22] = &test2
; // accY
511 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == TEST_3)
512 p_measurements
[22] = &test3
; // accY
514 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == GLIDER_RATIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
515 p_measurements
[22] = &gliderRatio
;
517 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == SECONDS_SINCE_T0 ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
518 p_measurements
[22] = &secFromT0
;
520 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == AVERAGE_VSPEED_SINCE_TO ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
521 p_measurements
[22] = &averageVspeedSinceT0
;
523 #elif defined(ACCY_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( ACCY_SOURCE == VOLT_1 || ACCY_SOURCE == VOLT_2 || ACCY_SOURCE == VOLT_3 || ACCY_SOURCE == VOLT_4 || ACCY_SOURCE == VOLT_5 || ACCY_SOURCE == VOLT_6 )
524 p_measurements
[22] = &oXs_Voltage
.voltageData
.mVolt
[ACCY_SOURCE
- VOLT_1
] ;
526 #elif defined(ACCY_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( ACCY_SOURCE == ADS_VOLT_1 || ACCY_SOURCE == ADS_VOLT_2 || ACCY_SOURCE == ADS_VOLT_3 || ACCY_SOURCE == ADS_VOLT_4 )
527 p_measurements
[22] = &ads_Conv
[ACCY_SOURCE
- ADS_VOLT_1
];
529 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == PITCH) && defined(USE_6050)
530 p_measurements
[22] = &pitch
;
532 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == ROLL) && defined(USE_6050)
533 p_measurements
[22] = &roll
;
535 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == YAW) && defined(USE_6050)
536 p_measurements
[22] = &yaw
;
539 p_measurements
[22] = &no_data
; // accY
543 #if defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == TEST_1)
544 p_measurements
[23] = &test1
; // accZ
546 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == TEST_2)
547 p_measurements
[23] = &test2
; // accZ
549 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == TEST_3)
550 p_measurements
[23] = &test3
; // accZ
552 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == GLIDER_RATIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
553 p_measurements
[23] = &gliderRatio
;
555 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == SECONDS_SINCE_T0 ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
556 p_measurements
[23] = &secFromT0
;
558 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == AVERAGE_VSPEED_SINCE_TO ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
559 p_measurements
[23] = &averageVspeedSinceT0
;
561 #elif defined(ACCZ_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( ACCZ_SOURCE == VOLT_1 || ACCZ_SOURCE == VOLT_2 || ACCZ_SOURCE == VOLT_3 || ACCZ_SOURCE == VOLT_4 || ACCZ_SOURCE == VOLT_5 || ACCZ_SOURCE == VOLT_6 )
562 p_measurements
[23] = &oXs_Voltage
.voltageData
.mVolt
[ACCZ_SOURCE
- VOLT_1
] ;
564 #elif defined(ACCZ_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( ACCZ_SOURCE == ADS_VOLT_1 || ACCZ_SOURCE == ADS_VOLT_2 || ACCZ_SOURCE == ADS_VOLT_3 || ACCZ_SOURCE == ADS_VOLT_4 )
565 p_measurements
[23] = &ads_Conv
[ACCZ_SOURCE
- ADS_VOLT_1
];
567 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == PITCH) && defined(USE_6050)
568 p_measurements
[23] = &pitch
; // accX
570 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == ROLL) && defined(USE_6050)
571 p_measurements
[23] = &roll
; // accX
573 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == YAW) && defined(USE_6050)
574 p_measurements
[23] = &yaw
; // accX
577 p_measurements
[23] = &no_data
; // accZ
583 void OXS_OUT::sendSportData()
585 #if defined(GPS_TRANSMIT_TIME)
586 static uint32_t ptxtime
=0;
590 Serial
.print("State "); Serial
.print(state
,HEX
) ; Serial
.print(" LastRx "); Serial
.print(LastRx
,HEX
) ; Serial
.print(" prevLastRx "); Serial
.print(prevLastRx
,HEX
) ;
591 Serial
.print(" sensorIsr "); Serial
.println(sensorIsr
,HEX
) ;
594 // first we calculate fields that are used only by SPORT
595 #if defined(VFAS_SOURCE)
596 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( (VFAS_SOURCE == VOLT_1) || (VFAS_SOURCE == VOLT_2) || (VFAS_SOURCE == VOLT_3) || (VFAS_SOURCE == VOLT_4) || (VFAS_SOURCE == VOLT_5) || (VFAS_SOURCE == VOLT_6) )
597 if ( (!vfas
.available
) && ( oXs_Voltage
.voltageData
.mVolt
[VFAS_SOURCE
- VOLT_1
].available
) ){
598 vfas
.value
= oXs_Voltage
.voltageData
.mVolt
[VFAS_SOURCE
- VOLT_1
].value
/ 10 ; // voltage in mv is divided by 10 because SPORT expect it (volt * 100)
599 vfas
.available
= true ;
600 oXs_Voltage
.voltageData
.mVolt
[VFAS_SOURCE
- VOLT_1
].available
= false ;
602 #elif defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( (VFAS_SOURCE == ADS_VOLT_1) || (VFAS_SOURCE == ADS_VOLT_2) || (VFAS_SOURCE == ADS_VOLT_3) || (VFAS_SOURCE == ADS_VOLT_4) )
603 if ( (!vfas
.available
) && ( ads_Conv
[VFAS_SOURCE
- ADS_VOLT_1
].available
) ){
604 vfas
.value
= ads_Conv
[VFAS_SOURCE
- ADS_VOLT_1
].value
/ 10 ; // voltage in mv is divided by 10 because SPORT expect it (volt * 100)
605 vfas
.available
= true ;
606 ads_Conv
[VFAS_SOURCE
- ADS_VOLT_1
].available
= false;
609 #if ( (VFAS_SOURCE == ADS_VOLT_1) || (VFAS_SOURCE == ADS_VOLT_2) || (VFAS_SOURCE == ADS_VOLT_3) || (VFAS_SOURCE == ADS_VOLT_4) )
610 #error When VFAS_SOURCE is ADS_VOLT_1, ADS_VOLT_2,... ADS_VOLT_4 then ADS_MEASURE must be defined too.
611 #elif ( (VFAS_SOURCE == VOLT_1) || (VFAS_SOURCE == VOLT_2) || (VFAS_SOURCE == VOLT_3) || (VFAS_SOURCE == VOLT_4) || (VFAS_SOURCE == VOLT_5) || (VFAS_SOURCE == VOLT_6) )
612 #error When VFAS_SOURCE is VOLT_1, VOLT_2,... VOLT_6 then PIN_VOLTAGE must be defined too.
614 #error When defined, VFAS_SOURCE must be VOLT_1, VOLT_2,... VOLT_6 or ADS_VOLT_1, ADS_VOLT_2,... ADS_VOLT_4
619 #if defined(ARDUINO_MEASURES_A_CURRENT) && (ARDUINO_MEASURES_A_CURRENT == YES)
620 if ( oXs_Current
.currentData
.milliAmps
.available
) {
621 oXs_Current
.currentData
.milliAmps
.available
= false ;
622 sport_currentData
.value
= oXs_Current
.currentData
.milliAmps
.value
/ 100 ;
623 if (sport_currentData
.value
<0) {
624 sport_currentData
.value
=0;
626 sport_currentData
.available
= true ;
628 #elif defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(ADS_CURRENT_BASED_ON)
629 if ( oXs_ads1115
.adsCurrentData
.milliAmps
.available
) {
630 oXs_ads1115
.adsCurrentData
.milliAmps
.available
= false ;
631 sport_currentData
.value
= oXs_ads1115
.adsCurrentData
.milliAmps
.value
/ 100 ;
632 if (sport_currentData
.value
<0) {
633 sport_currentData
.value
=0;
635 sport_currentData
.available
= true ;
639 #if defined(GPS_INSTALLED)
640 if (GPS_lonAvailable
) {
641 sport_gps_lon
.available
= GPS_lonAvailable
;
642 GPS_lonAvailable
= false ;
643 sport_gps_lon
.value
= (( ((((uint32_t)( GPS_lon
< 0 ? -GPS_lon
: GPS_lon
)) /10 ) * 6 ) / 10 ) & 0x3FFFFFFF) | 0x80000000;
644 if(GPS_lon
< 0) sport_gps_lon
.value
|= 0x40000000;
646 if (GPS_latAvailable
) {
647 sport_gps_lat
.available
= GPS_latAvailable
;
648 GPS_latAvailable
= false ;
649 sport_gps_lat
.value
= (( ((((uint32_t)( GPS_lat
< 0 ? -GPS_lat
: GPS_lat
)) / 10 ) * 6 )/ 10 ) & 0x3FFFFFFF ) ;
650 if(GPS_lat
< 0) sport_gps_lat
.value
|= 0x40000000;
652 if (GPS_altitudeAvailable
) {
653 sport_gps_alt
.available
= GPS_altitudeAvailable
;
654 GPS_altitudeAvailable
= false ;
655 sport_gps_alt
.value
= GPS_altitude
/ 10; // convert mm in cm
658 if (GPS_speed_3dAvailable
) {
659 sport_gps_speed
.available
= GPS_speed_3dAvailable
;
660 GPS_speed_3dAvailable
= false ;
661 #ifdef GPS_SPEED_IN_KMH
662 sport_gps_speed
.value
= ( ((uint32_t) GPS_speed_3d
) * 36 ) ; // convert cm/s in 1/100 of km/h (factor = 3.6)
664 sport_gps_speed
.value
= ( ((uint32_t) GPS_speed_3d
) * 700 ) / 36 ; // convert cm/s in 1/100 of knots (factor = 19.44)
665 #endif // end of GPS_SPEED_IN_KMH
667 #else // use gps_Speed_2d
668 if (GPS_speed_2dAvailable
) {
669 sport_gps_speed
.available
= GPS_speed_2dAvailable
;
670 GPS_speed_2dAvailable
= false ;
671 #ifdef GPS_SPEED_IN_KMH
672 sport_gps_speed
.value
= ( ((uint32_t) GPS_speed_2d
) * 36 ) ; // convert cm/s in 1/100 of km/h (factor = 3.6)
674 sport_gps_speed
.value
= ( ((uint32_t) GPS_speed_2d
) * 700 ) / 36 ; // convert cm/s in 1/1000 of knots (factor = 19.44)
675 #endif // end of GPS_SPEED_IN_KMH
677 #endif // enf of GPS_SPEED_3D or 2D
678 if (GPS_ground_courseAvailable
) {
679 sport_gps_course
.available
= GPS_ground_courseAvailable
;
680 GPS_ground_courseAvailable
= false ;
681 sport_gps_course
.value
= GPS_ground_course
/ 1000; // convert from degree * 100000 to degree * 100
684 #if defined(GPS_TRANSMIT_TIME)
685 if (GPS_timeAvailable
) {
686 sport_gps_date
.value
=(GPS_year
% 100);
687 sport_gps_date
.value
<<=8;
688 sport_gps_date
.value
+=GPS_month
;
689 sport_gps_date
.value
<<=8;
690 sport_gps_date
.value
+=GPS_day
;
691 sport_gps_date
.value
<<=8;
692 sport_gps_date
.value
+=0xFF;
693 sport_gps_time
.value
=GPS_hour
;
694 sport_gps_time
.value
<<=8;
695 sport_gps_time
.value
+=GPS_min
;
696 sport_gps_time
.value
<<=8;
697 sport_gps_time
.value
+=GPS_sec
;
698 sport_gps_time
.value
<<=8;
699 if (ptxtime
!=sport_gps_time
.value
) {
700 ptxtime
=sport_gps_time
.value
;
701 sport_gps_date
.available
=GPS_timeAvailable
;
702 sport_gps_time
.available
=GPS_timeAvailable
;
706 #endif // end of GPS_INSTALLED
708 // Serial.print("frskyStatus "); Serial.println(frskyStatus,HEX) ;
709 if ( frskyStatus
) { // if at least one data has to be loaded
710 for (uint8_t sensorSeq
= 0 ; sensorSeq
< 6 ; sensorSeq
++ ) { // for each sensor (currently 6)
711 if ( frskyStatus
& (1 << sensorSeq
) ) { //if frskyStatus says that a data must be loaded for this sensor
712 uint8_t currFieldIdx_
= currFieldIdx
[sensorSeq
] ; // retrieve the last field being loaded for this sensor
713 for (uint8_t iCount
= fieldMinIdx
[sensorSeq
] ; iCount
< fieldMinIdx
[sensorSeq
+1] ; iCount
++ ) { // we will not seach more than the number of fields for the selected sensor
714 currFieldIdx_
++ ; // search with next field
715 if ( currFieldIdx_
>= fieldMinIdx
[sensorSeq
+1] ) currFieldIdx_
= fieldMinIdx
[sensorSeq
] ; // if overlap within sensor range, set idx to first idx for this sensorSeq
716 // Serial.print("currFieldIdx_ "); Serial.print(currFieldIdx_) ;
717 // Serial.print(" p_m.av "); Serial.print( p_measurements[currFieldIdx_]->available) ;
718 // Serial.print(" p_m.va "); Serial.println( p_measurements[currFieldIdx_]->value) ;
719 if ( p_measurements
[currFieldIdx_
]->available
){ // if data of current index of sensor is available
720 p_measurements
[currFieldIdx_
]->available
= 0 ; // mark the data as not available
721 dataValue
[sensorSeq
] = p_measurements
[currFieldIdx_
]->value
; // store the value in a buffer
722 dataId
[sensorSeq
] = fieldId
[currFieldIdx_
] ; // mark the data from this sensor as available
723 uint8_t oReg
= SREG
; // save status register
725 frskyStatus
&= ~(1<< sensorSeq
) ; // says that data is loaded by resetting one bit
726 SREG
= oReg
; // restore the status register
727 #ifdef DEBUG_LOAD_SPORT
728 Serial
.print("Load "); Serial
.print(dataId
[sensorSeq
],HEX
) ; Serial
.print(" ") ; Serial
.println(dataValue
[sensorSeq
]);
730 break ; // exit inner for
733 currFieldIdx
[sensorSeq
] = currFieldIdx_
; // save currentFieldIdx for this
735 } // End for one sensorSeq
736 } // End of if (frskystatus)
737 #ifdef DEBUG_SPORT_RECEIVED
738 Serial
.print("RcvCnt "); Serial
.println( sportRcvCount
) ;
745 // -------------------------End of SPORT protocol--------------------------------------------------------------------------------------
747 //========================= Hub protocol ==========================================
748 #if defined( PROTOCOL ) && ( ( PROTOCOL == FRSKY_HUB ) || ( PROTOCOL == FRSKY_SPORT_HUB ) )
749 void OXS_OUT::sendHubData() // for Hub protocol
751 #define FRAME2_EVERY_N_FRAME1 1 // n means that there is n frame1 after one frame2(gps)
752 #define MSEC_PER_BYTE 7 // number of msec per byte to transmit; I expect that a value of 7 ms should work; probably it can even be reduced up to 6.
753 static uint32_t lastMsFrame1
=0;
754 static uint16_t lastFrameLength
;
755 static uint32_t temp
;
756 static uint8_t countFrame1
= FRAME2_EVERY_N_FRAME1
;
758 //static uint32_t lastMsFrame2=0;
763 if ( (state
== IDLE
) && (temp
> (lastMsFrame1
+ ( lastFrameLength
* MSEC_PER_BYTE
) ) ) ) {
765 if ( (countFrame1
== 0 ) && GPS_fix
) {
767 lastFrameLength
= hubMaxData
;
768 countFrame1
= FRAME2_EVERY_N_FRAME1
;
774 lastFrameLength
= hubMaxData
;
775 if ( countFrame1
) countFrame1
-- ;
780 // second frame used for GPS
782 if ( (state == IDLE ) && (temp > lastMsFrame2 + INTERVAL_FRAME2 ) && (temp >= lastMsFrame1 + INTERVAL_FRAME1 ) && GPS_fix ) {
783 #ifdef DEBUGHUBPROTOCOL
784 printer->print("F2 at ");
785 printer->println( millis() );
791 if ( (state == IDLE) && (temp >= lastMsFrame1 + INTERVAL_FRAME1 ) && (temp >= lastMsFrame2 + INTERVAL_FRAME1 ) ) {
792 #ifdef DEBUGHUBPROTOCOL
793 printer->print("F1 at ");
794 printer->println( millis() );
800 } // end sendData Hub protocol
802 //======================================================================================================Send Frame 1A via serial
803 void OXS_OUT::SendFrame1(){
804 hubMaxData
= 0 ; // reset of number of data to send
806 // pointer to Altitude
808 uint16_t Centimeter
= uint16_t(abs(oXs_MS5611
.varioData
.absoluteAlt
.value
)%100);
810 if (oXs_MS5611
.varioData
.absoluteAlt
.value
>0){
811 Meter
= (oXs_MS5611
.varioData
.absoluteAlt
.value
- Centimeter
);
813 Meter
= -1*(abs(oXs_MS5611
.varioData
.absoluteAlt
.value
) + Centimeter
);
816 SendValue(FRSKY_USERDATA_BARO_ALT_B
, (int16_t)Meter
);
817 SendValue(FRSKY_USERDATA_BARO_ALT_A
, Centimeter
);
822 SendValue( FRSKY_USERDATA_VERT_SPEED
, (int16_t) mainVspeed
.value
);
826 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(NUMBEROFCELLS) && (NUMBEROFCELLS > 0)
827 SendCellVoltage( oXs_Voltage
.voltageData
.mVoltCell_1_2
.value
);
831 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(NUMBEROFCELLS) && (NUMBEROFCELLS > 2)
832 SendCellVoltage( oXs_Voltage
.voltageData
.mVoltCell_3_4
.value
) ;
836 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(NUMBEROFCELLS) && (NUMBEROFCELLS > 4)
837 SendCellVoltage( oXs_Voltage
.voltageData
.mVoltCell_5_6
.value
) ;
841 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VFAS_SOURCE) && ( (VFAS_SOURCE == VOLT_1) || (VFAS_SOURCE == VOLT_2) || (VFAS_SOURCE == VOLT_3) || (VFAS_SOURCE == VOLT_4) || (VFAS_SOURCE == VOLT_5) || (VFAS_SOURCE == VOLT_6) )
842 SendValue( FRSKY_USERDATA_VFAS_NEW
, (int16_t) (voltageData
->mVolt
[VFAS_SOURCE
- VOLT_1
].value
/ 100) ) ; // convert mvolt in 1/10 of volt; in openTx 2.1.x, it is possible to get 1 more decimal using [VFAS_SOURCE - VOLT_1 ].value/10.)+2000);
843 #elif defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(VFAS_SOURCE) && ( (VFAS_SOURCE == ADS_VOLT_1) || (VFAS_SOURCE == ADS_VOLT_2) || (VFAS_SOURCE == ADS_VOLT_3) || (VFAS_SOURCE == ADS_VOLT_4) )
844 SendValue( FRSKY_USERDATA_VFAS_NEW
, (int16_t) (ads_Conv
[VFAS_SOURCE
- ADS_VOLT_1
].value
/ 100) ) ; // convert mvolt in 1/10 of volt; in openTx 2.1.x, it is possible to get 1 more decimal using [VFAS_SOURCE - VOLT_1 ].value/10.)+2000);
848 #if defined(ARDUINO_MEASURES_A_CURRENT) && (ARDUINO_MEASURES_A_CURRENT == YES)
849 SendValue( FRSKY_USERDATA_CURRENT
, (int16_t) ( oXs_Current
.currentData
.milliAmps
.value
/ 100 ) ) ;
850 #elif defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(ADS_CURRENT_BASED_ON)
851 SendValue( FRSKY_USERDATA_CURRENT
, (int16_t) ( oXs_ads1115
.adsCurrentData
.milliAmps
.value
/ 100 ) ) ;
855 #if defined(FUEL_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( FUEL_SOURCE == VOLT_1 || FUEL_SOURCE == VOLT_2 || FUEL_SOURCE == VOLT_3 || FUEL_SOURCE == VOLT_4 || FUEL_SOURCE == VOLT_5 || FUEL_SOURCE == VOLT_6 )
856 SendValue(FRSKY_USERDATA_FUEL
, (int16_t) voltageData
->mVolt
[FUEL_SOURCE
- VOLT_1
].value
) ;
857 #elif defined(VFAS_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( (FUEL_SOURCE == ADS_VOLT_1) || (FUEL_SOURCE == ADS_VOLT_2) || (FUEL_SOURCE == ADS_VOLT_3) || (FUEL_SOURCE == ADS_VOLT_4) )
858 SendValue( FRSKY_USERDATA_FUEL
, (int16_t) (ads_Conv
[FUEL_SOURCE
- ADS_VOLT_1
].value
) ) ;
862 #if defined(MEASURE_RPM)
863 SendValue( FRSKY_USERDATA_RPM
, (int16_t) sport_rpm
.value
) ;
867 #if defined(T1_SOURCE) && ( T1_SOURCE == TEST_1)
868 SendValue( FRSKY_USERDATA_TEMP1
, (int16_t) test1
.value
) ;
869 #elif defined(T1_SOURCE) && ( T1_SOURCE == TEST_2)
870 SendValue( FRSKY_USERDATA_TEMP1
, (int16_t) test2
.value
) ;
871 #elif defined(T1_SOURCE) && ( T1_SOURCE == TEST_3)
872 SendValue( FRSKY_USERDATA_TEMP1
, (int16_t) test3
.value
) ;
873 #elif defined(T1_SOURCE) && ( T1_SOURCE == GLIDER_RATIO) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
874 SendValue( FRSKY_USERDATA_TEMP1
, (int16_t) gliderRatio
.value
) ;
875 #elif defined(T1_SOURCE) && ( T1_SOURCE == SECONDS_SINCE_T0 ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
876 SendValue( FRSKY_USERDATA_TEMP1
, (int16_t) secFromT0
.value
) ;
877 #elif defined(T1_SOURCE) && ( T1_SOURCE == AVERAGE_VSPEED_SINCE_TO ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
878 SendValue( FRSKY_USERDATA_TEMP1
, (int16_t) averageVspeedSinceT0
.value
) ;
879 #elif defined(T1_SOURCE) && ( T1_SOURCE == SENSITIVITY) && defined(VARIO)
880 SendValue( FRSKY_USERDATA_TEMP1
, (int16_t) oXs_MS5611
.varioData
.sensitivity
.value
) ;
881 #elif defined(T1_SOURCE) && ( T1_SOURCE == PPM) && ( defined(PIN_PPM) || ( defined(PPM_VIA_SPORT) && ( (PROTOCOL == FRSKY_SPORT) || (PROTOCOL == FRSKY_SPORT_HUB) ) ) )
882 SendValue( FRSKY_USERDATA_TEMP1
, (int16_t) ppm
.value
) ;
883 #elif defined(T1_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( (T1_SOURCE == VOLT_1) || (T1_SOURCE == VOLT_2) || (T1_SOURCE == VOLT_3) || (T1_SOURCE == VOLT_4) || (T1_SOURCE == VOLT_5) || (T1_SOURCE == VOLT_6) )
884 SendValue( FRSKY_USERDATA_TEMP1
, (int16_t) (voltageData
->mVolt
[T1_SOURCE
- VOLT_1
].value
) ) ;
885 #elif defined(T1_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( (T1_SOURCE == ADS_VOLT_1) || (T1_SOURCE == ADS_VOLT_2) || (T1_SOURCE == ADS_VOLT_3) || (T1_SOURCE == ADS_VOLT_4) )
886 SendValue( FRSKY_USERDATA_TEMP1
, (int16_t) (ads_Conv
[T1_SOURCE
- ADS_VOLT_1
].value
) ) ;
891 #if defined(T2_SOURCE) && ( T2_SOURCE == TEST_1)
892 SendValue( FRSKY_USERDATA_TEMP2
, (int16_t) test1
.value
) ;
893 #elif defined(T2_SOURCE) && ( T2_SOURCE == TEST_2)
894 SendValue( FRSKY_USERDATA_TEMP2
, (int16_t) test2
.value
) ;
895 #elif defined(T2_SOURCE) && ( T2_SOURCE == TEST_3)
896 SendValue( FRSKY_USERDATA_TEMP2
, (int16_t) test3
.value
) ;
897 #elif defined(T2_SOURCE) && ( T2_SOURCE == GLIDER_RATIO) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
898 SendValue( FRSKY_USERDATA_TEMP2
, (int16_t) gliderRatio
.value
) ;
899 #elif defined(T2_SOURCE) && ( T2_SOURCE == SECONDS_SINCE_T0 ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
900 SendValue( FRSKY_USERDATA_TEMP2
, (int16_t) secFromT0
.value
) ;
901 #elif defined(T2_SOURCE) && ( T2_SOURCE == AVERAGE_VSPEED_SINCE_TO ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
902 SendValue( FRSKY_USERDATA_TEMP2
, (int16_t) averageVspeedSinceT0
.value
) ;
903 #elif defined(T2_SOURCE) && ( T2_SOURCE == SENSITIVITY) && defined(VARIO)
904 SendValue( FRSKY_USERDATA_TEMP2
, (int16_t) oXs_MS5611
.varioData
.sensitivity
.value
) ;
905 #elif defined(T2_SOURCE) && ( T2_SOURCE == PPM) && ( defined(PIN_PPM) || ( defined(PPM_VIA_SPORT) && ( (PROTOCOL == FRSKY_SPORT) || (PROTOCOL == FRSKY_SPORT_HUB) ) ) )
906 SendValue( FRSKY_USERDATA_TEMP2
, (int16_t) ppm
.value
) ;
907 #elif defined(T2_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( (T2_SOURCE == VOLT_1) || (T2_SOURCE == VOLT_2) || (T2_SOURCE == VOLT_3) || (T2_SOURCE == VOLT_4) || (T2_SOURCE == VOLT_5) || (T2_SOURCE == VOLT_6) )
908 SendValue( FRSKY_USERDATA_TEMP2
, (int16_t) (voltageData
->mVolt
[T2_SOURCE
- VOLT_1
].value
) ) ;
909 #elif defined(T2_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( (T2_SOURCE == ADS_VOLT_1) || (T2_SOURCE == ADS_VOLT_2) || (T2_SOURCE == ADS_VOLT_3) || (T2_SOURCE == ADS_VOLT_4) )
910 SendValue( FRSKY_USERDATA_TEMP2
, (int16_t) (ads_Conv
[T2_SOURCE
- ADS_VOLT_1
].value
) ) ;
913 // airspeed // not implemented in Hub protocol; to add in T1 or T2
914 #if defined(AIRSPEED)
915 //oXs_4525.airSpeedData.airSpeed ;
919 #if defined(ACCX_SOURCE) && ( ACCX_SOURCE == TEST_1)
920 SendValue( FRSKY_USERDATA_ACC_X
, (int16_t) test1
.value
) ;
921 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == TEST_2)
922 SendValue( FRSKY_USERDATA_ACC_X
, (int16_t) test2
.value
) ;
923 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == TEST_3)
924 SendValue( FRSKY_USERDATA_ACC_X
, (int16_t) test3
.value
) ;
925 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == GLIDER_RATIO) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
926 SendValue( FRSKY_USERDATA_ACC_X
, (int16_t) gliderRatio
.value
) ;
927 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == SECONDS_SINCE_T0 ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
928 SendValue( FRSKY_USERDATA_ACC_X
, (int16_t) secFromT0
.value
) ;
929 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == AVERAGE_VSPEED_SINCE_TO ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
930 SendValue( FRSKY_USERDATA_ACC_X
, (int16_t) averageVspeedSinceT0
.value
) ;
931 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == PITCH) && defined(USE_6050)
932 SendValue( FRSKY_USERDATA_ACC_X
, (int16_t) pitch
.value
) ;
933 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == ROLL) && defined(USE_6050)
934 SendValue( FRSKY_USERDATA_ACC_X
, (int16_t) roll
.value
) ;
935 #elif defined(ACCX_SOURCE) && ( ACCX_SOURCE == YAW) && defined(USE_6050)
936 SendValue( FRSKY_USERDATA_ACC_X
, (int16_t) yaw
.value
) ;
937 #elif defined(ACCX_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( (ACCX_SOURCE == VOLT_1) || (ACCX_SOURCE == VOLT_2) || (ACCX_SOURCE == VOLT_3) || (ACCX_SOURCE == VOLT_4) || (ACCX_SOURCE == VOLT_5) || (ACCX_SOURCE == VOLT_6) )
938 SendValue( FRSKY_USERDATA_ACC_X
, (int16_t) (voltageData
->mVolt
[ACCX_SOURCE
- VOLT_1
].value
) ) ;
939 #elif defined(ACCX_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( (ACCX_SOURCE == ADS_VOLT_1) || (ACCX_SOURCE == ADS_VOLT_2) || (ACCX_SOURCE == ADS_VOLT_3) || (ACCX_SOURCE == ADS_VOLT_4) )
940 SendValue( FRSKY_USERDATA_ACC_X
, (int16_t) (ads_Conv
[ACCX_SOURCE
- ADS_VOLT_1
].value
) ) ;
944 #if defined(ACCY_SOURCE) && ( ACCY_SOURCE == TEST_1)
945 SendValue( FRSKY_USERDATA_ACC_Y
, (int16_t) test1
.value
) ;
946 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == TEST_2)
947 SendValue( FRSKY_USERDATA_ACC_Y
, (int16_t) test2
.value
) ;
948 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == TEST_3)
949 SendValue( FRSKY_USERDATA_ACC_Y
, (int16_t) test3
.value
) ;
950 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == GLIDER_RATIO) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
951 SendValue( FRSKY_USERDATA_ACC_Y
, (int16_t) gliderRatio
.value
) ;
952 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == SECONDS_SINCE_T0 ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
953 SendValue( FRSKY_USERDATA_ACC_Y
, (int16_t) secFromT0
.value
) ;
954 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == AVERAGE_VSPEED_SINCE_TO ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
955 SendValue( FRSKY_USERDATA_ACC_Y
, (int16_t) averageVspeedSinceT0
.value
) ;
956 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == PITCH) && defined(USE_6050)
957 SendValue( FRSKY_USERDATA_ACC_Y
, (int16_t) pitch
.value
) ;
958 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == ROLL) && defined(USE_6050)
959 SendValue( FRSKY_USERDATA_ACC_Y
, (int16_t) roll
.value
) ;
960 #elif defined(ACCY_SOURCE) && ( ACCY_SOURCE == YAW) && defined(USE_6050)
961 SendValue( FRSKY_USERDATA_ACC_Y
, (int16_t) yaw
.value
) ;
962 #elif defined(ACCY_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( (ACCY_SOURCE == VOLT_1) || (ACCY_SOURCE == VOLT_2) || (ACCY_SOURCE == VOLT_3) || (ACCY_SOURCE == VOLT_4) || (ACCY_SOURCE == VOLT_5) || (ACCY_SOURCE == VOLT_6) )
963 SendValue( FRSKY_USERDATA_ACC_Y
, (int16_t) (voltageData
->mVolt
[ACCY_SOURCE
- VOLT_1
].value
) ) ;
964 #elif defined(ACCY_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( (ACCY_SOURCE == ADS_VOLT_1) || (ACCY_SOURCE == ADS_VOLT_2) || (ACCY_SOURCE == ADS_VOLT_3) || (ACCY_SOURCE == ADS_VOLT_4) )
965 SendValue( FRSKY_USERDATA_ACC_Y
, (int16_t) (ads_Conv
[ACCY_SOURCE
- ADS_VOLT_1
].value
) ) ;
969 #if defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == TEST_1)
970 SendValue( FRSKY_USERDATA_ACC_Z
, (int16_t) test1
.value
) ;
971 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == TEST_2)
972 SendValue( FRSKY_USERDATA_ACC_Z
, (int16_t) test2
.value
) ;
973 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == TEST_3)
974 SendValue( FRSKY_USERDATA_ACC_Z
, (int16_t) test3
.value
) ;
975 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == GLIDER_RATIO) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
976 SendValue( FRSKY_USERDATA_ACC_Z
, (int16_t) gliderRatio
.value
) ;
977 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == SECONDS_SINCE_T0 ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
978 SendValue( FRSKY_USERDATA_ACC_Z
, (int16_t) secFromT0
.value
) ;
979 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == AVERAGE_VSPEED_SINCE_TO ) && defined(VARIO) && defined(GLIDER_RATIO_CALCULATED_AFTER_X_SEC)
980 SendValue( FRSKY_USERDATA_ACC_Z
, (int16_t) averageVspeedSinceT0
.value
) ;
981 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == PITCH) && defined(USE_6050)
982 SendValue( FRSKY_USERDATA_ACC_Z
, (int16_t) pitch
.value
) ;
983 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == ROLL) && defined(USE_6050)
984 SendValue( FRSKY_USERDATA_ACC_Z
, (int16_t) roll
.value
) ;
985 #elif defined(ACCZ_SOURCE) && ( ACCZ_SOURCE == YAW) && defined(USE_6050)
986 SendValue( FRSKY_USERDATA_ACC_Z
, (int16_t) yaw
.value
) ;
987 #elif defined(ACCZ_SOURCE) && defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && ( (ACCZ_SOURCE == VOLT_1) || (ACCZ_SOURCE == VOLT_2) || (ACCZ_SOURCE == VOLT_3) || (ACCZ_SOURCE == VOLT_4) || (ACCZ_SOURCE == VOLT_5) || (ACCZ_SOURCE == VOLT_6) )
988 SendValue( FRSKY_USERDATA_ACC_Z
, (int16_t) (voltageData
->mVolt
[ACCZ_SOURCE
- VOLT_1
].value
) ) ;
989 #elif defined(ACCZ_SOURCE) && defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && ( (ACCZ_SOURCE == ADS_VOLT_1) || (ACCZ_SOURCE == ADS_VOLT_2) || (ACCZ_SOURCE == ADS_VOLT_3) || (ACCZ_SOURCE == ADS_VOLT_4) )
990 SendValue( FRSKY_USERDATA_ACC_Z
, (int16_t) (ads_Conv
[ACCZ_SOURCE
- ADS_VOLT_1
].value
) ) ;
993 if( hubMaxData
> 0 ) {
994 sendHubByte(0x5E) ; // End of Frame 1!
997 #ifdef DEBUGHUBPROTOCOL
998 printer
->print(F("Frame 1 to send: "));
999 for (int cntPrint
= 0 ; cntPrint
< hubData
.maxData
; cntPrint
++) {
1000 printer
->print(" ");
1001 printer
->print(hubData
.data
[cntPrint
] , HEX
);
1003 printer
->println(" ");
1005 } // end send frame 1
1008 #define FRSKY_USERDATA_GPS_ALT_B 0x01 // Altitude m
1009 #define FRSKY_USERDATA_GPS_ALT_A 0x09 // Altitude in centimeter
1010 #define FRSKY_USERDATA_GPS_SPEED_B 0x11 // Speed knots
1011 #define FRSKY_USERDATA_GPS_LONG_B 0x12 // Longitude (DDMM)
1012 #define FRSKY_USERDATA_GPS_LAT_B 0x13 // Latitude (DDMM)
1013 #define FRSKY_USERDATA_GPS_CURSE_B 0x14 // Course degrees
1014 #define FRSKY_USERDATA_GPS_SPEED_A 0x19 // Speed 2 decimals of knots
1015 #define FRSKY_USERDATA_GPS_LONG_A 0x1A // Longitude (.MMMM)
1016 #define FRSKY_USERDATA_GPS_LAT_A 0x1B // Latitude (.MMMM)
1017 #define FRSKY_USERDATA_GPS_CURSE_A 0x1C // // Course 2 decimals of degrees
1018 #define FRSKY_USERDATA_GPS_LONG_EW 0x22 //(uint16_t)(flon < 0 ? 'W' : 'E')
1019 #define FRSKY_USERDATA_GPS_LAT_EW 0x23 //(uint16_t)(lat < 0 ? 'S' : 'N')
1020 #define FRSKY_USERDATA_GPS_DIST 0x3C
1023 #ifdef GPS_INSTALLED
1024 //======================================================================================================Send Frame 2 via serial used for GPS
1025 void OXS_OUT::SendFrame2(){
1026 static uint8_t hubGpsCount
;
1027 uint32_t absLongLat
;
1028 uint32_t decimalPartOfDegree
;
1029 uint32_t minWith7Decimals
;
1030 hubMaxData
= 0 ; // reset of number of data to send
1031 // here we fill the buffer with all GPS data
1032 // GPS_lon // longitude in degree with 7 decimals, (neg for S)
1033 // GPS_lat // latitude in degree with 7 decimals, (neg for ?)
1034 // GPS_altitude; // altitude in mm
1035 // GPS_speed_3d; // speed in cm/s
1036 // GPS_speed; // speed in cm/s
1037 // GPS_ground_course ; // degrees with 5 decimals
1038 if ( hubGpsCount
== 0 ) {
1039 absLongLat
= abs(GPS_lat
) ;
1040 decimalPartOfDegree
= (absLongLat
% 10000000 );
1041 minWith7Decimals
= decimalPartOfDegree
* 60 ;
1042 SendValue(FRSKY_USERDATA_GPS_LAT_B
, (uint16_t) (((absLongLat
/ 10000000L) * 100 ) + (minWith7Decimals
/ 10000000L )) ) ; // Latitude (DDMM)
1043 SendValue(FRSKY_USERDATA_GPS_LAT_A
, (uint16_t) (( minWith7Decimals
% 10000000L) / 1000 ) ) ; // Latitude (.MMMM)
1044 SendValue(FRSKY_USERDATA_GPS_LAT_EW
, (uint16_t)(GPS_lat
< 0 ? 'S' : 'N')) ;
1045 } else if ( hubGpsCount
== 1 ) {
1046 absLongLat
= abs(GPS_lon
) ;
1047 decimalPartOfDegree
= (absLongLat
% 10000000 );
1048 minWith7Decimals
= decimalPartOfDegree
* 60 ;
1049 SendValue(FRSKY_USERDATA_GPS_LONG_B
, (uint16_t) (((absLongLat
/ 10000000L) * 100 ) + (minWith7Decimals
/ 10000000L )) ) ; // Longitude (DDMM)
1050 SendValue(FRSKY_USERDATA_GPS_LONG_A
, (uint16_t) (( minWith7Decimals
% 10000000L) / 1000 ) ) ; // Longitude (.MMMM)
1051 SendValue(FRSKY_USERDATA_GPS_LONG_EW
, (uint16_t)(GPS_lon
< 0 ? 'W' : 'E')) ;
1052 } else if ( hubGpsCount
== 2 ) {
1053 SendValue(FRSKY_USERDATA_GPS_ALT_B
, (int16_t) (GPS_altitude
/ 1000) ); // Altitude m
1054 SendValue(FRSKY_USERDATA_GPS_ALT_A
, (uint16_t) ( ( (abs(GPS_altitude
) % 1000 ) / 10 ) ) ) ; // Altitude centimeter
1055 } else if ( hubGpsCount
== 3 ) {
1057 uint32_t GPSSpeedKnot
= GPS_speed_3d
* 1944L ; // speed in knots with 5 décimals (1 cm/sec = 0,0194384 knot)
1059 uint32_t GPSSpeedKnot
= GPS_speed_2d
* 1944L ;
1061 SendValue(FRSKY_USERDATA_GPS_SPEED_B
, (uint16_t) ( GPSSpeedKnot
/ 100000) ) ; // Speed knots
1062 SendValue(FRSKY_USERDATA_GPS_SPEED_A
, (uint16_t) ( (GPSSpeedKnot
% 100000 ) /1000) ) ; // Speed 2 decimals of knots
1063 } else if ( hubGpsCount
== 4 ) {
1064 SendValue(FRSKY_USERDATA_GPS_CURSE_B
, (uint16_t) ( GPS_ground_course
/ 100000 ) ) ; // Course degrees
1065 SendValue(FRSKY_USERDATA_GPS_CURSE_A
, (uint16_t) ( (GPS_ground_course
% 100000) / 1000 ) ) ; // Course 2 decimals of degrees
1068 if ( hubGpsCount
>= 5 ) hubGpsCount
= 0 ;
1069 if( hubMaxData
> 0 ) {
1070 sendHubByte(0x5E) ; // End of Frame 2!
1073 #ifdef DEBUGHUBPROTOCOL
1074 printer
->print("Frame2 to send = ");
1075 for (int cntPrint
= 0 ; cntPrint
< hubData
.maxData
; cntPrint
++) {
1076 printer
->print(" ");
1077 printer
->print(hubData
.data
[cntPrint
] , HEX
);
1079 printer
->println(" ");
1083 #endif // end of GPS_INSTALLED
1086 // ******************************************************** //
1087 // SendValue => send a value as frsky sensor hub data //
1088 // ******************************************************** //
1089 void OXS_OUT::SendValue(uint8_t ID
, uint16_t Value
) {
1090 uint8_t tmp1
= Value
& 0x00ff;
1091 uint8_t tmp2
= (Value
& 0xff00)>>8;
1095 if ( (tmp1
== 0x5E) || (tmp1
== 0x5D) ){
1100 if ( (tmp2
== 0x5E) || (tmp2
== 0x5D) ){
1107 //***************************************************
1108 // Put a byte in the buffer
1109 //***************************************************
1110 void OXS_OUT::sendHubByte( uint8_t byte
)
1112 hubData
[hubMaxData
] = byte
;
1117 // ***************************************************
1118 // Search the value, format it and put it in a buffer
1119 // ***************************************************
1120 void OXS_OUT::loadHubValueToSend( uint8_t currentFieldToSend ) {
1121 fieldToSend = (int) convertToHubId[ fieldContainsData[currentFieldToSend][0] ] ;
1122 if ( (fieldToSend >= FRSKY_USERDATA_GPS_ALT_B ) && (fieldToSend <= FRSKY_USERDATA_FUELPERCENT ) ) fieldOk = true ;
1123 else fieldOk = false ;
1124 switch ( fieldContainsData[currentFieldToSend][1] ) {
1128 // if ( (SwitchFrameVariant == 0) && (varioData->absoluteAltAvailable) ) { //========================================================================== Vario Data
1129 if (fieldToSend == DEFAULTFIELD) {
1130 SendAlt( ( (varioData->relativeAlt.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4] );
1131 // varioData->absoluteAlt.available = false ;
1133 else if( fieldOk == true ) {
1134 SendValue((int8_t) fieldToSend ,(int16_t) ( (varioData->relativeAlt.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4] );
1135 // varioData->absoluteAlt.available = false ;
1139 case VERTICAL_SPEED :
1140 // if ( (SwitchFrameVariant == 0) && (varioData->climbRateAvailable) ){
1141 if (fieldToSend == DEFAULTFIELD) {
1142 // Attempt to work around the annoying 10cm double beep
1143 //SendValue(FRSKY_USERDATA_VERT_SPEED,(int16_t)varioData->climbRate); // ClimbRate in open9x Vario mode
1144 if (varioData->climbRate.value==10) SendValue(FRSKY_USERDATA_VERT_SPEED,(int16_t)9); // ClimbRate in open9x Vario mode
1145 else if (varioData->climbRate.value==-10) SendValue(FRSKY_USERDATA_VERT_SPEED,(int16_t)-9);
1146 else SendValue(FRSKY_USERDATA_VERT_SPEED,( ( (int16_t) varioData->climbRate.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3]))+ fieldContainsData[currentFieldToSend][4] ); // ClimbRate in open9x Vario mode
1147 // varioData->climbRateAvailable = false ;
1149 else if( fieldOk == true ) {
1150 SendValue((int8_t) fieldToSend , ( ((int16_t)varioData->climbRate.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3]))+ fieldContainsData[currentFieldToSend][4] );
1151 varioData->climbRate.available = false ;
1156 // if ( (SwitchFrameVariant == 0) && (varioData->sensitivity.available ) ){
1157 if ( fieldOk == true ) {
1158 SendValue((int8_t) fieldToSend , ( ((int16_t) varioData->sensitivity.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3]))+ fieldContainsData[currentFieldToSend][4] );
1159 // varioData->sensitivityAvailable = false ;
1163 case ALT_OVER_10_SEC :
1164 // if ( (SwitchFrameVariant == 0) && (varioData->vSpeed10SecAvailable ) ){
1165 if ( fieldOk == true ) {
1166 SendValue((int8_t) fieldToSend , ( ( (int16_t) varioData->vSpeed10SecAvailable * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3]) ) + fieldContainsData[currentFieldToSend][4] );
1167 // varioData->vSpeed10SecAvailable = false ;
1178 // if ( (SwitchFrameVariant == 0) && (varioData_2->absoluteAltAvailable) ) { //========================================================================== Vario Data
1179 if (fieldToSend == DEFAULTFIELD) {
1180 SendAlt( ( (varioData_2->absoluteAlt.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4]);
1181 // varioData_2->absoluteAltAvailable = false ;
1183 else if( fieldOk == true ) {
1184 SendValue((int8_t) fieldToSend ,(int16_t) ( (varioData_2->absoluteAlt.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4] );
1185 // varioData_2->absoluteAltAvailable = false ;
1189 case VERTICAL_SPEED_2 :
1190 // if ( (SwitchFrameVariant == 0) && (varioData_2->climbRateAvailable) ){
1191 if (fieldToSend == DEFAULTFIELD) {
1192 // Attempt to work around the annoying 10cm double beep
1193 //SendValue(FRSKY_USERDATA_VERT_SPEED,(int16_t)varioData->climbRate); // ClimbRate in open9x Vario mode
1194 if (varioData_2->climbRate.value == 10) SendValue(FRSKY_USERDATA_VERT_SPEED,(int16_t)9); // ClimbRate in open9x Vario mode
1195 else if (varioData_2->climbRate.value == -10) SendValue(FRSKY_USERDATA_VERT_SPEED,(int16_t)-9);
1196 else SendValue(FRSKY_USERDATA_VERT_SPEED, ( ( (int16_t) varioData_2->climbRate.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3]))+ fieldContainsData[currentFieldToSend][4] ); // ClimbRate in open9x Vario mode
1197 // varioData_2->climbRateAvailable = false ;
1199 else if( fieldOk == true ) {
1200 SendValue((int8_t) fieldToSend , ( ( (int16_t) varioData_2->climbRate.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3]))+ fieldContainsData[currentFieldToSend][4] );
1201 // varioData_2->climbRateAvailable = false ;
1205 case SENSITIVITY_2 :
1206 // if ( (SwitchFrameVariant == 0) && (varioData_2->sensitivityAvailable ) ){
1207 if ( fieldOk == true ) {
1208 SendValue((int8_t) fieldToSend , ( ( (int16_t) varioData_2->sensitivity.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3]))+ fieldContainsData[currentFieldToSend][4] );
1209 // varioData_2->sensitivityAvailable = false ;
1213 case ALT_OVER_10_SEC_2 :
1214 // if ( (SwitchFrameVariant == 0) && (varioData_2->vSpeed10SecAvailable ) ){
1215 if ( fieldOk == true ) {
1216 SendValue((int8_t) fieldToSend ,(int16_t) ( (varioData_2->vSpeed10SecAvailable * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3]) ) + fieldContainsData[currentFieldToSend][4] );
1217 // varioData_2->vSpeed10SecAvailable = false ;
1223 #endif // end vario2
1225 #if defined (VARIO ) && defined (VARIO2)
1226 case VERTICAL_SPEED_A :
1227 if( fieldOk == true ) {
1228 SendValue((int8_t) fieldToSend , ( ( (int16_t) averageVSpeed.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4] );
1233 #if defined (VARIO ) && ( defined (VARIO2) || defined( AIRSPEED) || defined(USE_6050) ) && defined (VARIO_PRIMARY ) && defined (VARIO_SECONDARY ) && defined (PIN_PPM)
1235 if( fieldOk == true ) {
1236 SendValue((int8_t) fieldToSend , ( ( (int16_t) switchVSpeed.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4] );
1243 if (fieldToSend == DEFAULTFIELD) {
1244 SendGPSSpeed( (( (int16_t) airSpeedData->airSpeed.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4]) ;
1246 else if( fieldOk == true ) {
1247 SendValue((int8_t) fieldToSend , ( ( (int16_t) airSpeedData->airSpeed.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4] );
1250 case PRANDTL_COMPENSATION :
1251 // if ( (SwitchFrameVariant == 0) && (airSpeedData->airSpeedAvailable) ) { //========================================================================== Vario Data
1252 if( fieldOk == true ) {
1253 SendValue((int8_t) fieldToSend , ( ( (int16_t) airSpeedData->compensation * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4] );
1254 // airSpeedData->airSpeedAvailable = false ;
1259 #endif // end airspeed
1261 #if defined (VARIO) && defined ( AIRSPEED)
1263 if( fieldOk == true ) {
1264 SendValue((int8_t) fieldToSend , ( ((int16_t) compensatedClimbRate.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4] );
1267 #endif // End defined (VARIO) && defined ( AIRSPEED)
1272 SendVoltX( 0 , currentFieldToSend) ;
1275 SendVoltX( 1 , currentFieldToSend) ;
1278 SendVoltX( 2 , currentFieldToSend) ;
1281 SendVoltX( 3 , currentFieldToSend) ;
1284 SendVoltX( 4 , currentFieldToSend) ;
1287 SendVoltX( 5 , currentFieldToSend) ;
1291 #if defined (PIN_CURRENTSENSOR)
1293 // if ( (SwitchFrameVariant == 0) && (currentData->milliAmpsAvailable ) ) {
1294 if ( fieldToSend == DEFAULTFIELD ) {
1295 SendCurrentMilliAmps(( ( (int16_t) currentData->milliAmps.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3]) ) + fieldContainsData[currentFieldToSend][4]);
1296 // currentData->milliAmpsAvailable = false ;
1298 else if( fieldOk == true ) {
1299 SendValue((int8_t) fieldToSend , ( ( (int16_t) currentData->milliAmps.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3]) ) + fieldContainsData[currentFieldToSend][4] );
1300 // currentData->milliAmpsAvailable = false ;
1305 // if ( (SwitchFrameVariant == 0) && (currentData->consumedMilliAmpsAvailable) ){
1306 if( fieldOk == true ) {
1307 SendValue((int8_t) fieldToSend ,(int16_t) ( (currentData->consumedMilliAmps * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4] );
1308 // currentData->consumedMilliAmpsAvailable = false ;
1312 // case FRSKY_USERDATA_CURRENT_MAX :
1313 //// if ( (SwitchFrameVariant == 0) ) {
1314 // if ( fieldToSend == DEFAULTFIELD ) {
1315 // SendValue(0x38,int16_t(currentData->maxMilliAmps)); //Cur+ OK!
1317 // else if( fieldOk == true ) {
1318 // SendValue((int8_t) fieldToSend ,(int16_t) ( (currentData->maxMilliAmps * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3]) ) + fieldContainsData[currentFieldToSend][4] );
1322 #endif // End PIN_CURRENTSENSOR
1324 #if defined (NUMBEROFCELLS) && (NUMBEROFCELLS > 0) && defined (PIN_VOLTAGE)
1326 // if ( (SwitchFrameVariant == 0) && ( voltageData->mVoltCell_1_2_Available ) ) {
1327 if ( fieldToSend == DEFAULTFIELD ) {
1328 SendCellVoltage( voltageData->mVoltCell_1_2.value ) ;
1329 // voltageData->mVoltCell_1_2_Available = false ;
1335 // if ( (SwitchFrameVariant == 0) && ( voltageData->mVoltCell_3_4_Available ) ) {
1336 if ( fieldToSend == DEFAULTFIELD ) {
1337 SendCellVoltage( voltageData->mVoltCell_3_4.value ) ;
1338 // voltageData->mVoltCell_3_4_Available = false ;
1344 // if ( (SwitchFrameVariant == 0) && ( voltageData->mVoltCell_5_6_Available ) ) {
1345 if ( fieldToSend == DEFAULTFIELD ) {
1346 SendCellVoltage( voltageData->mVoltCell_5_6.value ) ;
1347 // voltageData->mVoltCell_5_6_Available = false ;
1352 #endif // NUMBEROFCELLS > 0
1356 if( fieldOk == true ) {
1357 SendValue((int8_t) fieldToSend , ( ( (int16_t) ppm * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4] );
1365 // if ( (SwitchFrameVariant == 0) && ( RpmAvailable ) ) {
1366 if ( fieldToSend == DEFAULTFIELD || fieldToSend == FRSKY_USERDATA_RPM ) {
1367 SendValue(FRSKY_USERDATA_RPM, (( RpmValue * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4]);
1371 #endif // MEASURE_RPM
1373 if( fieldOk == true ) {
1374 SendValue((int8_t) fieldToSend ,(int16_t) ( (test1.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4] );
1378 if( fieldOk == true ) {
1379 SendValue((int8_t) fieldToSend ,(int16_t) ( (test2.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4] );
1383 if( fieldOk == true ) {
1384 SendValue((int8_t) fieldToSend ,(int16_t) ( (test3.value * fieldContainsData[currentFieldToSend][2] / fieldContainsData[currentFieldToSend][3])) + fieldContainsData[currentFieldToSend][4] );
1390 } // End function loadValueToSend (Frame 1)
1394 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined (NUMBEROFCELLS) && (NUMBEROFCELLS > 0)
1395 // ********************************************************** //
1396 // SendCellVoltage => send a cell voltage //
1397 // ********************************************************** //
1398 void OXS_OUT::SendCellVoltage( uint32_t voltage
) {
1399 // For SPORT, cell voltage is formatted as (hex) 12 34 56 78 where 123 = volt of cell n+1 (divided by 2), 456 idem for cell n, 7 = max number of cell and 8 = n (number of cell)
1400 // target format for Hub (hex) is having 2 data sent in format : 84 56 and 91 23 (where 9 = content of 8 incresed by 1)
1401 byte cellID
= (voltage
& 0x0000000f);
1402 uint16_t cellVolt
= ((voltage
>> 8) & 0x0fff) ;
1403 uint8_t v1
= ( (cellID
)<<4 & 0xf0) | ((cellVolt
& 0x0f00)>>8) ;
1404 uint8_t v2
= (cellVolt
& 0x00ff);
1405 uint16_t Value
= (v2
<<8) | (v1
& 0x00ff) ;
1406 SendValue(FRSKY_USERDATA_CELL_VOLT
, Value
);
1408 if (cellID
< NUMBEROFCELLS
) {
1409 cellVolt
= (voltage
& 0xfff00000) >> 20 ;
1410 uint8_t v1
= ( (cellID
)<<4 & 0xf0) | ((cellVolt
& 0x0f00)>>8) ;
1411 uint8_t v2
= (cellVolt
& 0x00ff);
1412 uint16_t Value
= (v2
<<8) | (v1
& 0x00ff) ;
1413 SendValue(FRSKY_USERDATA_CELL_VOLT
, Value
);
1416 #endif // enf of 6 voltage
1418 // ********************************** //
1419 // SendGPSDist => send 0..32768 //
1420 // ********************************** //
1421 //void OXS_OUT::SendGPSDist(uint16_t dist) {// ==> Field "Dist" in open9x
1422 // SendValue(0x3C,uint16_t(dist)); //>> DIST
1425 // ************************************************************ //
1426 // SendTemperature1/2 => tempc in 1/100th of degree celsius //
1427 // Display Range in openTX: -3276,8..32768=-3276,8C..+3276,C //
1428 // ************************************************************ //
1429 void OXS_OUT::SendTemperature1(int16_t tempc) {
1430 SendValue(FRSKY_USERDATA_TEMP1, tempc);
1432 void OXS_OUT::SendTemperature2(int16_t tempc) {
1433 SendValue(FRSKY_USERDATA_TEMP2, tempc);
1436 // ************************************* //
1437 // SendRPM => Send Rounds Per Minute //
1438 // ************************************* //
1439 //void OXS_OUT::SendRPM(uint16_t rpm) {
1441 // rpm = uint16_t((float)rpm/(60/blades));
1442 // SendValue(FRSKY_USERDATA_RPM, rpmValue);
1446 // ************************************* //
1447 // SendFuel => SendFuel Level //
1448 // ************************************* //
1449 void OXS_OUT::SendFuel(uint16_t fuel) {
1450 SendValue(FRSKY_USERDATA_FUEL, fuel);
1453 // ********************************** //
1454 // SendAlt => Send ALtitude in cm //
1455 // ********************************* //
1456 void OXS_OUT::SendAlt(long altcm)
1458 uint16_t Centimeter = uint16_t(abs(altcm)%100);
1462 Meter = (altcm-(long)Centimeter);
1465 Meter = -1*(abs(altcm)+(long)Centimeter);
1468 SendValue(FRSKY_USERDATA_BARO_ALT_B, (int16_t)Meter);
1469 SendValue(FRSKY_USERDATA_BARO_ALT_A, Centimeter);
1472 // **************************************************************** //
1473 // SendGPSAlt - send the a value to the GPS altitude field //
1474 // parameter: altitude in cm between -3276800 and 3276799 //
1475 // cm will not be displayed //
1476 // **************************************************************** //
1477 void OXS_OUT::SendGPSAlt(long altcm)
1479 uint16_t Centimeter = uint16_t(abs(altcm)%100);
1482 Meter = (altcm-(long)Centimeter);
1485 Meter = -1*(abs(altcm)+(long)Centimeter);
1489 // need to send a gps fix before openTX displays this field....
1490 SendValue(FRSKY_USERDATA_GPS_LONG_A, 1);
1491 SendValue(FRSKY_USERDATA_GPS_LONG_B, 1);
1492 SendValue(FRSKY_USERDATA_GPS_LAT_A, 1);
1493 SendValue(FRSKY_USERDATA_GPS_LAT_B, 1);
1494 // now send the data
1495 SendValue(FRSKY_USERDATA_GPS_ALT_B, Meter);
1496 SendValue(FRSKY_USERDATA_GPS_ALT_A, Centimeter);
1500 // **************************************************************** //
1501 // SendGPSSpeed - send the a value to the GPS speed //
1502 // value is split in 2 fields //
1503 // knots and 1/10 of knots //
1504 // **************************************************************** //
1505 void OXS_OUT::SendGPSSpeed(long speedknots)
1507 uint16_t knotDecimal = uint16_t(abs(speedknots)%10);
1510 knots = (speedknots-(long) knotDecimal);
1513 knots = -1*(abs(speedknots)+(long)knotDecimal);
1517 // need to send a gps fix before openTX displays this field....
1518 SendValue(FRSKY_USERDATA_GPS_LONG_A, 1);
1519 SendValue(FRSKY_USERDATA_GPS_LONG_B, 1);
1520 SendValue(FRSKY_USERDATA_GPS_LAT_A, 1);
1521 SendValue(FRSKY_USERDATA_GPS_LAT_B, 1);
1522 // now send the data
1523 SendValue(FRSKY_USERDATA_GPS_SPEED_B, knots);
1524 SendValue(FRSKY_USERDATA_GPS_SPEED_A, knotDecimal);
1527 // *********************************************** //
1528 // SendCurrentMilliAmps => Send Current //
1529 // current will be transmitted as 1/10th of A //
1530 // Range: -32768..32767 => disp -3276..3276 //
1531 // *********************************************** //
1532 void OXS_OUT::SendCurrentMilliAmps(int32_t milliamps)
1534 #ifdef ForceAbsolutCurrent
1535 milliamps=abs(milliamps);
1537 SendValue(FRSKY_USERDATA_CURRENT, (uint16_t)(milliamps/100));
1540 //#endif // End of FRSKY_SPORT
1542 #endif // end HUB protocol --------------------------------------------------------------------------
1544 // ********************************** Here the code to handle the UART communication with the receiver
1546 //#define DEBUGSETNEWDATA
1549 //#define DEBUGASERIAL // Generate signal on A0 A1 in order to debug UART timing
1551 #define FORCE_INDIRECT(ptr) __asm__ __volatile__ ("" : "=e" (ptr) : "0" (ptr))
1553 volatile uint8_t state
; //!< Holds the state of the UART.
1554 static volatile unsigned char SwUartTXData
; //!< Data to be transmitted.
1555 static volatile unsigned char SwUartTXBitCount
; //!< TX bit counter.
1556 static volatile uint8_t SwUartRXData
; //!< Storage for received bits.
1557 static volatile uint8_t SwUartRXBitCount
; //!< RX bit counter.
1558 static volatile uint8_t TxCount
;
1560 volatile uint8_t debugUartRx
;
1562 volatile uint8_t ppmInterrupted
; // This flag is activated at the end of handling interrupt on Timer 1 Compare A if during this interrupt handling an interrupt on pin change (INT0 or INT1) occurs
1563 // in this case, ppm will be wrong and has to be discarded
1567 // Here the code for both Frsky protocols +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
1568 //! \brief Timer1 interrupt service routine. *************** interrupt between 2 bits (handled by timer1)
1570 // Timer1 will ensure that bits are written and read at the correct instants in time.
1571 // The state variable will ensure context switching between transmit and receive.
1572 // If state should be something else, the variable is set to IDLE. IDLE is regarded as a safe state/mode.
1575 uint8_t ByteStuffByte
= 0 ;
1578 uint8_t volatile hubData
[MAXSIZEBUFFER
] ;
1579 uint8_t volatile hubMaxData
; // max number of data prepared to be send
1583 uint8_t TxSportData
[7] ;
1585 uint8_t volatile sportData
[7] ;
1586 uint8_t volatile sendStatus
;
1587 //uint8_t volatile gpsSendStatus ;
1588 //uint8_t volatile gpsSportDataLock ;
1589 //uint8_t volatile gpsSportData[7] ;
1590 uint8_t currentSensorId
; // save the sensor id being received and on which oXs will reply (can be the main sensor id or GPS sensor id)
1593 ISR(TIMER1_COMPA_vect
)
1595 #if defined( PROTOCOL ) && ( ( PROTOCOL == FRSKY_SPORT ) || ( PROTOCOL == FRSKY_SPORT_HUB ) )
1596 if ( sportAvailable
) { // ++++++++ here only for SPORT protocol ++++++++++++++++++++++++++++++++++
1600 case TRANSMIT
: // Output the TX buffer in SPORT ************ we are sending each bit of data
1604 if( SwUartTXBitCount
< 8 )
1606 if( SwUartTXData
& 0x01 ) // If the LSB of the TX buffer is 1:
1608 CLEAR_TX_PIN() ; // Send a logic 1 on the TX_PIN.
1612 SET_TX_PIN() ; // Send a logic 0 on the TX_PIN.
1614 SwUartTXData
= SwUartTXData
>> 1 ; // Bitshift the TX buffer and
1615 SwUartTXBitCount
+= 1 ; // increment TX bit counter.
1617 else //Send stop bit.
1619 CLEAR_TX_PIN(); // Output a logic 1.
1620 state
= TRANSMIT_STOP_BIT
;
1621 //ENABLE_TIMER0_INT() ; // Allow this in now.
1623 OCR1A
+= TICKS2WAITONESPORT
; // Count one period into the future.
1629 // Go to idle after stop bit was sent.
1630 case TRANSMIT_STOP_BIT
: // SPORT ************************************* We have sent a stop bit, we look now if there is other byte to send
1631 if ( ByteStuffByte
|| (++TxCount
< 8 ) ) // Have we sent 8 bytes?
1633 if ( ByteStuffByte
)
1635 SwUartTXData
= ByteStuffByte
;
1640 if ( TxCount
< 7 ) // Data (or crc)?
1642 SwUartTXData
= TxSportData
[TxCount
] ;
1643 Crc
+= SwUartTXData
; //0-1FF
1644 Crc
+= Crc
>> 8 ; //0-100
1649 SwUartTXData
= 0xFF-Crc
; // prepare sending check digit
1651 if ( ( SwUartTXData
== 0x7E ) || ( SwUartTXData
== 0x7D ) )
1653 ByteStuffByte
= SwUartTXData
^ 0x20 ;
1654 SwUartTXData
= 0x7D ;
1657 SET_TX_PIN() ; // Send a logic 0 on the TX_PIN. (= start bit)
1658 OCR1A
= TCNT1
+ TICKS2WAITONESPORT
- INTERRUPT_BETWEEN_TRANSMIT
; // Count one period into the future. Compensate the time for ISR
1659 SwUartTXBitCount
= 0 ;
1661 //DISABLE_TIMER0_INT() ; // For the byte duration
1663 else // 8 bytes have been send
1665 frskyStatus
|= 1 << sensorIsr
; // set the bit relative to sensorIsr to say that a new data has to be loaded for sensorIsr.
1667 OCR1A
+= DELAY_3500
; // 3.5mS gap before listening
1668 TRXDDR
&= ~( 1 << PIN_SERIALTX
) ; // PIN is input
1669 TRXPORT
&= ~( 1 << PIN_SERIALTX
) ; // PIN is tri-stated.
1673 case RECEIVE
: // SPORT **** Start bit has been received and we will read bits of data receiving, LSB first.
1674 OCR1A
+= TICKS2WAITONESPORT
; // Count one period after the falling edge is trigged.
1676 uint8_t data
; // Use a temporary local storage
1677 data
= SwUartRXBitCount
;
1678 if( data
< 8 ) { // If 8 bits are not yet read
1679 SwUartRXBitCount
= data
+ 1 ;
1680 data
= SwUartRXData
;
1681 data
>>= 1 ; // Shift due to receiving LSB first.
1685 #if PIN_SERIALTX == 7
1686 if( GET_RX_PIN( )) {
1688 if( GET_RX_PIN( ) == 0 ) {
1690 data
|= 0x80 ; // If a logical 1 is read, let the data mirror this.
1695 SwUartRXData
= data
;
1697 else { //Done receiving = 8 bits are in SwUartRXData
1701 #ifdef DEBUG_SPORT_RECEIVED
1705 if ( LastRx
== 0x7E ) {
1706 switch (SwUartRXData
) {
1708 #define VARIO_ID DATA_ID_VARIO // replace those values by the right on
1709 #define CELL_ID DATA_ID_FLVSS
1710 #define CURRENT_ID DATA_ID_FAS
1711 #define GPS_ID DATA_ID_GPS
1712 #define RPM_ID DATA_ID_RPM
1713 #define ACC_ID DATA_ID_ACC
1714 #define TX_ID DATA_ID_TX // this ID is used when TX sent data to RX with a LUA script ; it requires that LUA script uses the same parameters
1715 #define SENSOR_ISR_FOR_TX_ID 0XF0 // this value says that we already received a byte == TX_ID
1718 sensorIsr
= 0 ; break ;
1720 sensorIsr
= 1 ; break ;
1722 sensorIsr
= 2 ; break ;
1724 sensorIsr
= 3 ; break ;
1726 sensorIsr
= 4 ; break ;
1728 sensorIsr
= 5 ; break ;
1730 TxDataIdx
= 0 ; // reset the counter used to register all bytes received from Tx
1731 sensorIsr
= SENSOR_ISR_FOR_TX_ID
; break ; // this value says that an ID related to a frame sent by Tx has been received; take care that it is perhaps just a pulling from RX without Tx frame.
1735 if ( ( sensorIsr
< 6 ) && ( idToReply
& (1 << sensorIsr
) ) ) { // If this sensor ID is supported by oXs and it has been configured in order to send some data
1736 if ( ( frskyStatus
& ( 1 << sensorIsr
) ) == 0 ) { // If this sensor ID is supported by oXs and oXs has prepared data to reply data in dataValue[] for this sensorSeq
1737 // if ( sportDataLock == 0 ) {
1738 TxSportData
[0] = 0x10 ;
1739 TxSportData
[1] = dataId
[sensorIsr
] << 4 ;
1740 TxSportData
[2] = dataId
[sensorIsr
] >> 4 ;
1741 TxSportData
[3] = dataValue
[sensorIsr
] ;
1742 TxSportData
[4] = dataValue
[sensorIsr
] >> 8 ;
1743 TxSportData
[5] = dataValue
[sensorIsr
] >> 16 ;
1744 TxSportData
[6] = dataValue
[sensorIsr
] >> 24 ;
1746 TxSportData
[0] = 0x10 ;
1747 TxSportData
[1] = 0 ;
1748 TxSportData
[2] = 0 ;
1749 TxSportData
[3] = 0 ;
1750 TxSportData
[4] = 0 ;
1751 TxSportData
[5] = 0 ;
1752 TxSportData
[6] = 0 ;
1755 OCR1A
+= ( DELAY_400
- TICKS2WAITONESPORT
) ; // 400 uS gap before sending (remove 1 tick time because it was already added before
1757 } else if ( sensorIsr
== SENSOR_ISR_FOR_TX_ID
) { // we received an ID that could be used by TX to send data to the sensor; so we have to continue reading bytes
1758 state
= IDLE
; // Go back to idle
1759 } else { // No data are loaded (so there is no data yet available or oXs does not have to reply to this ID)
1760 state
= WAITING
; // Wait for idle time
1761 OCR1A
+= DELAY_3500
; // 3.5mS gap before listening
1763 } // end receive 1 byte and previous was equal to 0x7E
1764 else if ( SwUartRXData
== 0x7E) { // reset sensorIsr when 0X7E is received (stop receiving data from Tx) and listen to next byte
1765 sensorIsr
= 128 ; // reset sensorIsr when 0X7E is received (stop receiving data from Tx)
1766 rxStuff
= 0; // and reset the stuff flag
1767 state
= IDLE
; // Go back to idle.
1768 } else if ((sensorIsr
== SENSOR_ISR_FOR_TX_ID
) && (TxDataIdx
< 8) ){ // we receive one byte that is not 0x7E. We check if it follow a sequence 0X7E and the Tx_ID which means it is sent by Tx to oXs
1769 // Note: if all bytes have been received, then TxDataIdx = 8 and we do not store the data anymore; test on TxDataIdx = 8 is done in .ino file
1770 if (SwUartRXData
== 0x7D) // byte stuffing indicator
1771 rxStuff
= 1; // set the flag and discard byte
1772 else if (rxStuff
== 0)
1773 TxData
[TxDataIdx
++] = SwUartRXData
; // we save the received byte in a buffer
1775 TxData
[TxDataIdx
++] = SwUartRXData
| 0x20 ; // we save the received byte in a buffer taking into account the stuff bit
1776 rxStuff
= 0; // and reset the flag
1778 state
= IDLE
; // Go back to idle.
1780 state
= IDLE
; // Go back to idle.
1781 } // end of test on receiving one byte
1782 LastRx
= SwUartRXData
; // save the current byte
1783 if (state
== IDLE
) { // when Go back to idle.
1784 DISABLE_TIMER_INTERRUPT() ; // Stop the timer interrupts.
1785 #if PIN_SERIALTX == 7
1786 ACSR
|= ( 1<<ACI
) ; // clear pending interrupt
1787 ACSR
|= ( 1<<ACIE
) ; // interrupt enabled (so we can receive another byte)
1789 PCIFR
= ( 1<<PCIF2
) ; // clear pending interrupt
1790 PCICR
|= ( 1<<PCIE2
) ; // pin change interrupt enabled
1794 } // End receiving 1 bit or 1 byte (8 bits)
1798 case TxPENDING
: // SPORT ****** we will here send a start bit before sending a byte
1802 TRXDDR
|= ( 1 << PIN_SERIALTX
) ; // PIN is output
1803 SET_TX_PIN() ; // Send a logic 0 on the TX_PIN. = start bit
1804 OCR1A
= TCNT1
+ ( TICKS2WAITONESPORT
- INTERRUPT_ENTRY_TRANSMIT
); // Count one period into the future (less the time to execute ISR) .
1805 SwUartTXBitCount
= 0 ;
1806 Crc
= SwUartTXData
= TxSportData
[0] ;
1813 //#endif // end of Frsky_Port
1815 case WAITING
: // SPORT ******** we where waiting for some time before listening for an start bit; we can now expect a start bit again
1816 DISABLE_TIMER_INTERRUPT() ; // Stop the timer interrupts.
1817 state
= IDLE
; // Go back to idle.
1818 #if PIN_SERIALTX == 7
1819 ACSR
|= ( 1<<ACI
) ; // clear pending interrupt
1820 ACSR
|= ( 1<<ACIE
) ; // interrupt enabled (so we can receive another byte)
1822 PCIFR
= ( 1<<PCIF2
) ; // clear pending interrupt
1823 PCICR
|= ( 1<<PCIE2
) ; // pin change interrupt enabled
1829 state
= IDLE
; // Error, should not occur. Going to a safe state.
1831 } // end sportAvailable == true
1833 #endif // end of #if defined( PROTOCOL ) && ( ( PROTOCOL == FRSKY_SPORT ) || ( PROTOCOL == FRSKY_SPORT_HUB ) )
1834 #if defined( PROTOCOL ) && ( ( PROTOCOL == FRSKY_HUB ) || ( PROTOCOL == FRSKY_SPORT_HUB ) ) // ++++++++ here for Hub protocol ++++++++++++++++++++++++++++++++++
1836 if (!sportAvailable
) { // we are handling the Hub protocol
1839 case TRANSMIT
: // Hub **** Output the TX buffer. Start bit has already been sent ************
1843 if( SwUartTXBitCount
< 8 ) { // if all bits have not been sent
1844 if( SwUartTXData
& 0x01 ) { // If the LSB of the TX buffer is 1:
1845 CLEAR_TX_PIN() ; // Send a logic 1 on the TX_PIN.
1846 } else { // Otherwise:
1847 SET_TX_PIN() ; // Send a logic 0 on the TX_PIN.
1849 SwUartTXData
= SwUartTXData
>> 1 ; // Bitshift the TX buffer and
1850 SwUartTXBitCount
+= 1 ; // increment TX bit counter.
1851 } else { //all 8 bits have been sent so now Send stop bit.
1852 CLEAR_TX_PIN(); // Output a logic 1.
1853 state
= TRANSMIT_STOP_BIT
;
1855 OCR1A
+= TICKS2WAITONEHUB
; // Count one period into the future.
1861 // Go to idle after stop bit was sent.
1862 case TRANSMIT_STOP_BIT
: // HUB ********************* We have sent a stop bit, now sent eventually next byte from buffer
1863 if ( ++TxCount
< hubMaxData
) { // Have we sent all bytes? if not,
1864 SwUartTXData
= hubData
[TxCount
] ; // load next byte
1865 SET_TX_PIN() ; // Send a logic 0 on the TX_PIN. (= start bit)
1866 OCR1A
= TCNT1
+ TICKS2WAITONEHUB
- INTERRUPT_BETWEEN_TRANSMIT
; // Count one period into the future.
1867 SwUartTXBitCount
= 0 ;
1869 } else { // if all bytes have been send, wait 100usec
1872 OCR1A
+= DELAY_3500
; // 3500 usec gap (instead of 100uS gap)
1877 DISABLE_TIMER_INTERRUPT() ; // Stop the timer interrupts.
1878 state
= IDLE
; // Go back to idle.
1883 state
= IDLE
; // Error, should not occur. Going to a safe state.
1886 } // end Hub protocol
1887 #endif // end of code for HUB protocol
1890 // End of the code for both Frsky protocols +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
1893 //____________________Here the code for SPORT interface only ++++++++++++++++++++++++++++++++++++++++++
1894 #if defined( PROTOCOL ) && ( ( PROTOCOL == FRSKY_SPORT ) || ( PROTOCOL == FRSKY_SPORT_HUB ) )
1895 //brief Function to initialize the UART for Sport protocol
1896 // This function will set up pins to transmit and receive on. Control of Timer0 and External interrupt 0.
1897 void initSportUart( ) //*************** initialise UART pour SPORT
1900 #if defined ( SPORT_SENSOR_ID ) && SPORT_SENSOR_ID >= 1 && SPORT_SENSOR_ID <= 28
1901 #define ID_MIN_1 (SPORT_SENSOR_ID - 1)
1902 #define BIT0 ( ID_MIN_1 & 0x01 )
1903 #define BIT1 (( ID_MIN_1 >> 1) & 0x01 )
1904 #define BIT2 (( ID_MIN_1 >> 2) & 0x01 )
1905 #define BIT3 (( ID_MIN_1 >> 3) & 0x01 )
1906 #define BIT4 (( ID_MIN_1 >> 4) & 0x01 )
1907 #define BIT5 (BIT0 xor BIT1 xor BIT2)
1908 #define BIT6 (BIT2 xor BIT3 xor BIT4)
1909 #define BIT7 (BIT0 xor BIT2 xor BIT4)
1910 sensorId = ID_MIN_1 | (BIT5 << 5) | (BIT6 << 6) | (BIT7 << 7) ;
1912 #error "SPORT_SENSOR_ID must be between 1 and 28 (included)"
1916 TRXDDR
&= ~( 1 << PIN_SERIALTX
) ; // PIN is input.
1917 TRXPORT
&= ~( 1 << PIN_SERIALTX
) ; // PIN is tri-stated.
1919 // External interrupt
1921 #if PIN_SERIALTX == 4
1922 PCMSK2
|= 0x10 ; // IO4 (PD4) on Arduini mini
1923 #elif PIN_SERIALTX == 2
1924 PCMSK2
|= 0x04 ; // IO2 (PD2) on Arduini mini
1926 #if PIN_SERIALTX != 7
1927 #error "This PIN is not supported"
1931 #if PIN_SERIALTX == 7
1932 ACSR
|= ( 1<<ACI
) ; // clear pending interrupt
1933 ACSR
|= ( 1<<ACIE
) ; // interrupt enabled (so we can receive another byte)
1935 PCIFR
= ( 1<<PCIF2
) ; // clear pending interrupt
1936 PCICR
|= ( 1<<PCIE2
) ; // pin change interrupt enabled
1939 // Internal State Variable
1943 DDRC
= 0x03 ; // PC0,1 as o/p debug
1948 // ! \brief External interrupt service routine. ********************
1949 // Interrupt on Pin Change to detect change on level on SPORT signal (= could be a start bit)
1951 // The falling edge in the beginning of the start
1952 // bit will trig this interrupt. The state will
1953 // be changed to RECEIVE, and the timer interrupt
1954 // will be set to trig one and a half bit period
1955 // from the falling edge. At that instant the
1956 // code should sample the first data bit.
1958 // note initSoftwareUart( void ) must be called in advance.
1960 // This is the pin change interrupt for port D
1961 // This assumes it is the only pin change interrupt on port D
1962 //#ifdef FRSKY_SPORT
1963 #if PIN_SERIALTX == 7
1964 ISR(ANALOG_COMP_vect
)
1966 ACSR
&= ~(1 << ACIE
) ; // interrupt disabled
1968 state
= RECEIVE
; // Change state
1969 DISABLE_TIMER_INTERRUPT() ; // Disable timer to change its registers.
1970 OCR1A
= TCNT1
+ TICKS2WAITONE_HALFSPORT
- INTERRUPT_EXEC_CYCL
- INTERRUPT_EARLY_BIAS
; // Count one and a half period into the future.
1972 DDRC
= 0x03 ; // PC0,1 as o/p debug
1975 SwUartRXBitCount
= 0 ; // Clear received bit counter.
1976 CLEAR_TIMER_INTERRUPT() ; // Clear interrupt bits
1977 ENABLE_TIMER_INTERRUPT() ; // Enable timer1 interrupt on again
1982 if ( TRXPIN
& ( 1 << PIN_SERIALTX
) ) { // if Pin is high = start bit (inverted)
1983 DISABLE_PIN_CHANGE_INTERRUPT() ; // pin change interrupt disabled
1985 state
= RECEIVE
; // Change state
1986 DISABLE_TIMER_INTERRUPT() ; // Disable timer to change its registers.
1987 OCR1A
= TCNT1
+ TICKS2WAITONE_HALFSPORT
- INTERRUPT_EXEC_CYCL
- INTERRUPT_EARLY_BIAS
; // Count one and a half period into the future.
1991 SwUartRXBitCount
= 0 ; // Clear received bit counter.
1992 CLEAR_TIMER_INTERRUPT() ; // Clear interrupt bits
1993 ENABLE_TIMER_INTERRUPT() ; // Enable timer1 interrupt on again
1995 //#ifdef PPM_INTERRUPT
1996 // if ( EIFR & PPM_INT_BIT) ppmInterrupted = 1 ;
2001 #endif // #end of code for SPORT protocol
2006 //____________________Here the code for HUB interface only ++++++++++++++++++++++++++++++++++++++++++
2007 #if defined( PROTOCOL ) && ( ( PROTOCOL == FRSKY_HUB ) || ( PROTOCOL == FRSKY_SPORT_HUB ) )
2008 //brief Function to initialize the UART for Sport protocol
2009 // This function will set up pins to transmit and receive on. Control of Timer0 and External interrupt 0.
2012 // ThisHubData = pdata ;
2013 TRXPORT
&= ~( 1 << PIN_SERIALTX
) ; // PIN is low
2014 TRXDDR
|= ( 1 << PIN_SERIALTX
) ; // PIN is output.
2016 //Internal State Variable
2022 DDRC
= 0x03 ; // PC0,1 as o/p debug
2027 void setHubNewData( )
2029 if ( (TxCount
== 0) && (hubMaxData
> 0) ) {
2030 // for (int cntNewData = 0 ; cntNewData < hubMaxData ; cntNewData++) {
2031 // TxHubData[cntNewData] = hubData[cntNewData] ;
2033 // TxMax = hubMaxData ;
2034 #ifdef DEBUGSETNEWDATA
2035 Serial
.print("set new data at ");
2036 Serial
.print( millis() );
2038 for (int cntNewData
= 0 ; hubMaxData
; cntNewData
++) {
2039 Serial
.print( hubData
[cntNewData
] , HEX
);
2042 Serial
.println(" ");
2044 startHubTransmit() ;
2048 void startHubTransmit()
2050 if ( state
!= IDLE
)
2054 SET_TX_PIN() ; // Send a logic 0 on the TX_PIN (=start bit).
2055 uint8_t oReg
= SREG
; // save status register
2057 OCR1A
= TCNT1
+ TICKS2WAITONEHUB
- INTERRUPT_ENTRY_TRANSMIT
; // Count one period into the future.
2058 CLEAR_TIMER_INTERRUPT() ; // Clear interrupt bits
2059 SREG
= oReg
; // restore the status register
2060 SwUartTXBitCount
= 0 ;
2061 SwUartTXData
= hubData
[0] ;
2064 ENABLE_TIMER_INTERRUPT() ; // Enable timer1 interrupt on again
2070 // end of function that are hub specific
2071 #endif // end of code for Hub protocol
2074 //********************************** End of code to handle the UART communication with the receiver
2075 #endif //End of FRSKY protocols