2 #include "oXs_out_jeti.h"
3 #include <avr/pgmspace.h>
4 #if defined(PROTOCOL) && (PROTOCOL == JETI)
7 // ************************* Several parameters to help debugging
8 //#define DEBUGSETNEWDATA
9 //#define DEBUGFORMATONEVALUE
10 //#define DEBUGJETIFRAME
11 //#define DEBUGADSCURRENT
12 //#define DEBUGSETNEWDATA
13 //#define DEBUGASERIAL
16 //#define DEBUG_FORCE_VARIODATA // this is used to force oXs to send a fixed dummy value for Vspeed and Alt in order to test if an issue result of bmp180 or from Multiplex / Jeti protocol.
17 //#define DEBUG_SERIAL_RX // this is used to generate pulses when oXs decodes a byte sent by the receiver
18 //#define DEBUGASERIAL // this is used to generate pulses when oXs send a byte
20 extern unsigned long micros( void ) ;
21 extern unsigned long millis( void ) ;
22 extern void delay(unsigned long ms
) ;
24 //struct t_mbAllData jetiData ;
25 volatile uint8_t sendStatus
;
26 uint8_t listOfFields
[16] ; // list of oXs Field Id to transmit
27 //struct ONE_MEASUREMENT * p_measurements[16] ; // array of 16 pointers (each pointer point to a structure containing a byte saying if a value is available and to the value.
28 uint8_t listOfFieldsIdx
; // current fields being handled
29 uint8_t numberOfFields
; // number of fields to transmit (from 1 ... 15)
30 uint8_t volatile jetiData
[63] = { 0x7E, 0x9F, 0x40 , 0x11 , 0xA4 , 0xAD , 0x04, 0x00 }; // 64 = 29 bytes for data + 34 bytes for text ; buffer where Jeti frame is prepared , 7E = header, 0x?F = X frame(? = any 4 bits) , 40 = means data (TXT would be 00) + length in 6 bits - to be filled-, A400 0001 = device id ; 00 = fixed value
31 uint8_t volatile jetiMaxData
; // max number of bytes prepared in the buffer to be sent
32 volatile uint8_t state
; //!< Holds the state of the software UART.
33 volatile uint8_t oneByteReceived
; // Keep a flag that is true when a byte has been received
34 volatile uint8_t lastByteReceived
; // Keep the last byte received
35 uint8_t prevByteReceived
;
36 uint8_t countOfFieldsChecked
; //
41 static volatile unsigned char SwUartTXData
; //!< Data to be transmitted.
42 static volatile uint8_t SwUartTXBit8
; // the bit 8 has to be 0 for the fist byte in the tx buffer in the jeti protocol
43 static volatile uint8_t SwUartTXBitParity
; // keep the number of 1 in the data beeing sent because jeti protocol uses ODD parity
44 static volatile unsigned char SwUartTXBitCount
; //!< TX bit counter.
45 static volatile uint8_t SwUartRXData
; //!< Storage for received bits.
46 static volatile uint8_t SwUartRXBit9
; //!< Storage for received bit 9.
47 static volatile uint8_t SwUartRXBitParity
; //!< Storage for received parity bit.
48 static volatile uint8_t SwUartRXBitCount
; //!< RX bit counter.
49 static volatile uint8_t TxCount
;
51 volatile uint8_t debugUartRx
;
53 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
54 // in this case, ppm will be wrong and has to be discarded
55 uint8_t nbWaitingDelay
;
61 //#if defined ( A_FLOW_SENSOR_IS_CONNECTED ) && ( A_FLOW_SENSOR_IS_CONNECTED == YES) // we will use interrupt PCINT0
62 extern volatile uint16_t flowMeterCnt
; // counter of pin change connected to the flow sensor (increased in the interrupt. reset every X sec when flow is processed)
63 extern float currentFlow
; // count the consumed ml/min during the last x sec
64 extern float consumedML
; // total of consumed ml since the last reset (or restart if reset is not activated); can be saved in EEPROM
65 extern struct ONE_MEASUREMENT actualFlow
; // in ml/min
66 extern struct ONE_MEASUREMENT remainingFuelML
; // in ml
67 extern struct ONE_MEASUREMENT fuelPercent
; // in % of tank capacity
68 extern int16_t flowParam
[8] ; // table that contains the parameters to correct the ml/pulse depending on the flow ; can be loaded by SPORT in EEPROM; can also be defined in a parameter
69 extern uint8_t residuelFuel
; // percentage of residual fuel
70 extern uint16_t tankCapacity
; // capacity of fuel tank
71 extern uint16_t consumedMLPrev
; //Last value saved in eeprom
72 extern uint16_t tankCapacityPrev
; //Last value saved in eeprom
73 extern int16_t flowParamPrev
[8] ; //Last value saved in eeprom
74 void processReceivedCmd( uint8_t cmd
) ;
75 void upDown ( int8_t upOrDown
) ;
76 void fillTxBuffer( void ) ;
77 void itoc ( int16_t n
, uint8_t posLastDigit
) ;
79 extern void checkFlowParam() ;
81 #if defined (MEASURE_RPM)
82 extern struct ONE_MEASUREMENT sport_rpm
;
90 #define LEFT_RIGHT 0x60
91 #define JETI_MENU_MAX 10 // number of items in jeti menu starting with 0
94 #define JETI_TANK_RESET 1
95 #define JETI_TANK_CAPACITY 2
96 #define JETI_CAL_FLOW_1 3
97 #define JETI_CAL_FLOW_2 4
98 #define JETI_CAL_FLOW_3 5
99 #define JETI_CAL_FLOW_4 6
100 #define JETI_CORR_FLOW_1 7
101 #define JETI_CORR_FLOW_2 8
102 #define JETI_CORR_FLOW_3 9
103 #define JETI_CORR_FLOW_4 10
105 // "0123456789ABCDE-0123456789ABCDE-0123456789ABCDE-0123456789ABCDE-0123456789ABCDE-0123456789ABCDE-0123456789ABCDE-0123456789ABCDE-0123456789ABCDE-0123456789ABCDE-
106 uint8_t const jetiText
[161] PROGMEM
= { "Flow ml/minRemain mlReset fuel <=+=> %Tank capacity <= => mlCalib. Flow 1 <= => ml/minCalib. Corr 1 <= => %"};
110 OXS_OUT::OXS_OUT(uint8_t pinTx
,HardwareSerial
&print
)
112 OXS_OUT::OXS_OUT(uint8_t pinTx
)
117 printer
= &print
; //operate on the address of print
122 // **************** Setup the OutputLib *********************
123 void OXS_OUT::setup() {
126 TRXDDR
&= ~( 1 << PIN_SERIALTX
) ; // PIN is input, tri-stated.
127 TRXPORT
|= ( 1 << PIN_SERIALTX
) ; // Pull up activated.
129 // Activate pin change interrupt on Tx pin
130 #if PIN_SERIALTX == 4
131 PCMSK2
|= 0x10 ; // IO4 (PD4) on Arduini mini
132 #elif PIN_SERIALTX == 2
133 PCMSK2
|= 0x04 ; // IO2 (PD2) on Arduini mini
135 #error "This PIN is not supported"
138 // PCIFR = (1<<PCIF2) ; // clear pending interrupt
140 state
= IDLE
; // Internal State Variable
143 DDRC
= 0x01 ; // PC0 as o/p debug = pin A0 !!!! is here put as output
147 #ifdef DEBUG_SERIAL_RX
148 DDRC
= 0x01 ; // PC0 as o/p debug = pin A0 !!!! is here put as output
152 degreeChar
[0] = 0xB0 ; // for the symbol °, fill with 0xB0 followed by 0x00 as showed in jetiprotocol example and in datasheet (code A02 for european set of char))
153 degreeChar
[1] = 0x00 ;
154 initJetiListOfFields() ;
157 printer
->print(F("Jeti Output Module: TX Pin="));
158 printer
->println(_pinTx
);
159 printer
->print(F(" milli="));
160 printer
->println(millis());
161 printer
->println(F("Jeti Output Module: Setup!"));
162 printer
->print(F("Number of fields to send = "));
163 printer
->println(numberOfFields
);
168 void OXS_OUT::initJetiListOfFields() { // fill an array with the list of fields (field ID) that are defined - Note : this list is not yet complete (e.g; GPS, ...)
169 listOfFieldsIdx
= 1 ; // 0 is not used for a value, because - for text- it contains the name of the sensor (e.g. openXsensor)
171 listOfFields
[listOfFieldsIdx
++] = REL_ALTIMETER
;
172 listOfFields
[listOfFieldsIdx
++] = VERTICAL_SPEED
;
173 listOfFields
[listOfFieldsIdx
++] = ALTIMETER_MAX
;
175 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(NUMBEROFCELLS) && (NUMBEROFCELLS > 0)
176 listOfFields
[listOfFieldsIdx
++] = CELL_1
;
177 listOfFields
[listOfFieldsIdx
++] = CELL_MIN
;
178 listOfFields
[listOfFieldsIdx
++] = CELL_TOT
;
180 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(NUMBEROFCELLS) && (NUMBEROFCELLS > 1)
181 listOfFields
[listOfFieldsIdx
++] = CELL_2
;
183 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(NUMBEROFCELLS) && (NUMBEROFCELLS > 2)
184 listOfFields
[listOfFieldsIdx
++] = CELL_3
;
186 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(NUMBEROFCELLS) && (NUMBEROFCELLS > 3)
187 listOfFields
[listOfFieldsIdx
++] = CELL_4
;
189 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(NUMBEROFCELLS) && (NUMBEROFCELLS > 4)
190 listOfFields
[listOfFieldsIdx
++] = CELL_5
;
192 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(NUMBEROFCELLS) && (NUMBEROFCELLS > 5)
193 listOfFields
[listOfFieldsIdx
++] = CELL_6
;
195 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_1 || VOLTAGE_SOURCE == VOLT_2 || VOLTAGE_SOURCE == VOLT_3 || VOLTAGE_SOURCE == VOLT_4 || VOLTAGE_SOURCE == VOLT_5 || VOLTAGE_SOURCE == VOLT_6 )
196 listOfFields
[listOfFieldsIdx
++] = VOLTAGE_SOURCE
;
198 #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))
199 listOfFields
[listOfFieldsIdx
++] = CURRENTMA
;
200 listOfFields
[listOfFieldsIdx
++] = MILLIAH
;
203 listOfFields
[listOfFieldsIdx
++] = AIR_SPEED
;
204 #elif defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(ADS_AIRSPEED_BASED_ON)
205 listOfFields
[listOfFieldsIdx
++] = AIR_SPEED
;
206 #elif defined(AIRSPEED_SDP3X)
207 listOfFields
[listOfFieldsIdx
++] = AIR_SPEED
;
208 #endif // End airpseed
210 listOfFields
[listOfFieldsIdx
++] = GPS_COURSE
;
211 listOfFields
[listOfFieldsIdx
++] = GPS_SPEED
;
212 listOfFields
[listOfFieldsIdx
++] = GPS_ALTITUDE
;
213 listOfFields
[listOfFieldsIdx
++] = GPS_DISTANCE
;
214 listOfFields
[listOfFieldsIdx
++] = GPS_BEARING
;
215 listOfFields
[listOfFieldsIdx
++] = GPS_LONG
;
216 listOfFields
[listOfFieldsIdx
++] = GPS_LAT
;
217 #endif // end GPS_INSTALLED
218 #if defined ( A_FLOW_SENSOR_IS_CONNECTED ) && ( A_FLOW_SENSOR_IS_CONNECTED == YES)
219 listOfFields
[listOfFieldsIdx
++] = FLOW_ACTUAL
;
220 listOfFields
[listOfFieldsIdx
++] = FLOW_REMAIN
;
221 listOfFields
[listOfFieldsIdx
++] = FLOW_PERCENT
;
222 #endif // end FLOW_SENSOR_IS_CONNECTED
223 #if defined (TEMPERATURE_SOURCE) && ( defined (VARIO) && ( TEMPERATURE_SOURCE == MS5611 ) )
224 listOfFields
[listOfFieldsIdx
++] = TEMPERATURE
;
226 #if defined (MEASURE_RPM)
227 listOfFields
[listOfFieldsIdx
++] = RPM
;
229 numberOfFields
= listOfFieldsIdx
- 1 ;
230 listOfFieldsIdx
= 1 ;
233 boolean
OXS_OUT::retrieveFieldIfAvailable(uint8_t fieldId
, int32_t * fieldValue
, uint8_t * dataType
) { // fill fieldValue and dataType for the fieldId when data is available, return true if data is available
235 uint8_t GPS_no_fix
= ( (GPS_fix_type
!= 3 ) && (GPS_fix_type
!= 4 ) ) ; // this flag is true when there is no fix
241 if ( ! varioData
->relativeAlt
.available
) return 0 ;
242 * fieldValue
= varioData
->relativeAlt
.value
/ 10 ; // Altitude converted from cm to dm
243 #ifdef DEBUG_FORCE_VARIODATA
244 static int32_t relativeAltTest
= 0 ;
245 * fieldValue
= relativeAltTest
++ ;
246 if ( relativeAltTest
>= 300 ) relativeAltTest
= 0 ;
248 * dataType
= JETI22_1D
;
249 varioData
->relativeAlt
.available
= false ;
251 case VERTICAL_SPEED
:
252 if ( ! mainVspeed
.available
) return 0;
253 * fieldValue
= mainVspeed
.value
;
254 #ifdef DEBUG_FORCE_VARIODATA
255 static int32_t VspeedTest
= 0 ;
256 * fieldValue
= VspeedTest
++ ;
257 if ( VspeedTest
>= 500 ) VspeedTest
= 0 ;
259 * dataType
= JETI14_2D
;
260 mainVspeed
.available
= false ;
263 if ( ! varioData
->relativeAltMaxAvailable
) return 0 ;
264 * fieldValue
= (varioData
->relativeAltMax
) / 10 ; // Altitude converted from cm to dm
265 #ifdef DEBUG_FORCE_VARIODATA
266 static int32_t relativeAltMaxTest
= 0 ;
267 * fieldValue
= relativeAltMaxTest
-- ;
268 if ( relativeAltMaxTest
<= -300 ) relativeAltMaxTest
= 0 ;
270 * dataType
= JETI22_1D
;
271 varioData
->relativeAltMaxAvailable
= false ;
275 #if (NUMBEROFCELLS > 0) // This part has still to be adapted for Multiplex !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
277 if ( ! voltageData
->mVoltCell_Available
[0] ) return 0;
278 * fieldValue
= voltageData
->mVoltCell
[0] /10 ; //Convert from mv to Volt with 2 decimal
279 * dataType
= JETI14_2D
;
280 voltageData
->mVoltCell_Available
[0] = false ;
283 if ( ! voltageData
->mVoltCell_Available
[1] ) return 0;
284 * fieldValue
= voltageData
->mVoltCell
[1] / 10 ;
285 * dataType
= JETI14_2D
;
286 voltageData
->mVoltCell_Available
[1] = false ;
289 if ( ! voltageData
->mVoltCell_Available
[2] ) return 0;
290 * fieldValue
= voltageData
->mVoltCell
[2] / 10 ;
291 * dataType
= JETI14_2D
;
292 voltageData
->mVoltCell_Available
[2] = false ;
295 if ( ! voltageData
->mVoltCell_Available
[3] ) return 0;
296 * fieldValue
= voltageData
->mVoltCell
[3] / 10 ;
297 * dataType
= JETI14_2D
;
298 voltageData
->mVoltCell_Available
[3] = false ;
301 if ( ! voltageData
->mVoltCell_Available
[4] ) return 0;
302 * fieldValue
= voltageData
->mVoltCell
[4] / 10 ;
303 * dataType
= JETI14_2D
;
304 voltageData
->mVoltCell_Available
[4] = false ;
307 if ( ! voltageData
->mVoltCell_Available
[5] ) return 0;
308 * fieldValue
= voltageData
->mVoltCell
[5] / 10 ;
309 * dataType
= JETI14_2D
;
310 voltageData
->mVoltCell_Available
[5] = false ;
313 if ( ! voltageData
->mVoltCellMin_Available
) return 0;
314 * fieldValue
= voltageData
->mVoltCellMin
/ 10 ;
315 * dataType
= JETI14_2D
;
316 voltageData
->mVoltCellMin_Available
= false ;
319 if ( ! voltageData
->mVoltCellTot_Available
) return 0;
320 * fieldValue
= voltageData
->mVoltCellTot
/ 10 ;
321 * dataType
= JETI14_2D
;
322 voltageData
->mVoltCellTot_Available
= false ;
325 #endif // NUMBEROFCELLS > 0
327 #if defined ( TEMPERATURE_SOURCE ) && ( TEMPERATURE_SOURCE == NTC ) // if a voltage field is (mis)used to transmit a NTC temperature, then format is different (no decimal).
328 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_1 )
330 if (! voltageData
->mVolt
[0].available
) return 0;
331 * fieldValue
= voltageData
->mVolt
[0].value
;
332 * dataType
= JETI14_0D
;
333 voltageData
->mVolt
[0].available
= false ;
336 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_2 )
338 if ( ! voltageData
->mVolt
[1].available
) return 0;
339 * fieldValue
= voltageData
->mVolt
[1].value
;
340 * dataType
= JETI14_0D
;
341 voltageData
->mVolt
[1].available
= false ;
344 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_3 )
346 if ( ! voltageData
->mVolt
[2].available
) return 0;
347 * fieldValue
= voltageData
->mVolt
[2].value
;
348 * dataType
= JETI14_0D
;
349 voltageData
->mVolt
[2].available
= false ;
352 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_4 )
354 if ( ! voltageData
->mVolt
[3].available
) return 0;
355 * fieldValue
= voltageData
->mVolt
[3].value
;
356 * dataType
= JETI14_0D
;
357 voltageData
->mVolt
[3].available
= false ;
360 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_5 )
362 if ( ! voltageData
->mVolt
[4].available
) return 0;
363 * fieldValue
= voltageData
->mVolt
[4].value
;
364 * dataType
= JETI14_0D
;
365 voltageData
->mVolt
[4].available
= false ;
368 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_6 )
370 if ( ! voltageData
->mVolt
[5].available
) return 0;
371 * fieldValue
= voltageData
->mVolt
[5].value
;
372 * dataType
= JETI14_0D
;
373 voltageData
->mVolt
[5].available
= false ;
376 #else // TEMPERATURE_SOURCE is not NTC and so VOLTAGE_SOURCE is a real voltage
378 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_1 )
380 if (! voltageData
->mVolt
[0].available
) return 0;
382 * fieldValue
= voltageData
->mVolt
[0].value
/ 10;
383 * dataType
= JETI14_2D
;
384 voltageData
->mVolt
[0].available
= false ;
387 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_2 )
389 if ( ! voltageData
->mVolt
[1].available
) return 0;
390 * fieldValue
= voltageData
->mVolt
[1].value
/ 10 ;
391 * dataType
= JETI14_2D
;
392 voltageData
->mVolt
[1].available
= false ;
395 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_3 )
397 if ( ! voltageData
->mVolt
[2].available
) return 0;
398 * fieldValue
= voltageData
->mVolt
[2].value
/ 10 ;
399 * dataType
= JETI14_2D
;
400 voltageData
->mVolt
[2].available
= false ;
403 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_4 )
405 if ( ! voltageData
->mVolt
[3].available
) return 0;
406 * fieldValue
= voltageData
->mVolt
[3].value
/ 10 ;
407 * dataType
= JETI14_2D
;
408 voltageData
->mVolt
[3].available
= false ;
411 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_5 )
413 if ( ! voltageData
->mVolt
[4].available
) return 0;
414 * fieldValue
= voltageData
->mVolt
[4].value
/ 10 ;
415 * dataType
= JETI14_2D
;
416 voltageData
->mVolt
[4].available
= false ;
419 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_6 )
421 if ( ! voltageData
->mVolt
[5].available
) return 0;
422 * fieldValue
= voltageData
->mVolt
[5].value
/ 10 ;
423 * dataType
= JETI14_2D
;
424 voltageData
->mVolt
[5].available
= false ;
427 #endif // end of defined ( TEMPERATURE_SOURCE ) && ( TEMPERATURE_SOURCE == NTC )
429 #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))
430 #if defined(ARDUINO_MEASURES_A_CURRENT) && (ARDUINO_MEASURES_A_CURRENT == YES) // when current is provide by arduino adc
432 if ( ! currentData
->milliAmps
.available
) return 0;
433 * fieldValue
= currentData
->milliAmps
.value
/10; // converted in A with 2 decimals
434 * dataType
= JETI14_2D
;
435 currentData
->milliAmps
.available
= false ;
438 if ( ! currentData
->consumedMilliAmps
.available
) return 0;
439 * fieldValue
= currentData
->consumedMilliAmps
.value
/ 10 ; // converted in Ah with 2 decimals
440 * dataType
= JETI14_2D
;
441 currentData
->consumedMilliAmps
.available
= false ;
443 #else // when current is provided using an ads1115
445 if ( ! oXs_ads1115
.adsCurrentData
.milliAmps
.available
) return 0;
446 * fieldValue
= oXs_ads1115
.adsCurrentData
.milliAmps
.value
/10; // converted in A with 2 decimals
447 * dataType
= JETI14_2D
;
448 oXs_ads1115
.adsCurrentData
.milliAmps
.available
= false ;
449 #ifdef DEBUGADSCURRENT
450 printer
->print(F("milliAmp="));
451 printer
->println(oXs_ads1115
.adsCurrentData
.milliAmps
.value
/10);
455 if ( ! oXs_ads1115
.adsCurrentData
.consumedMilliAmps
.available
) return 0;
456 * fieldValue
= oXs_ads1115
.adsCurrentData
.consumedMilliAmps
.value
; // in mAh without decimals
457 * dataType
= JETI22_0D
;
458 oXs_ads1115
.adsCurrentData
.consumedMilliAmps
.available
= false ;
459 #ifdef DEBUGADSCURRENT
460 printer
->print(F("consumed milliAmp="));
461 printer
->println(oXs_ads1115
.adsCurrentData
.consumedMilliAmps
.value
/ 10);
469 if ( ! airSpeedData
->airSpeed
.available
) return 0;
470 * fieldValue
= airSpeedData
->airSpeed
.value
* 1.852; // convert from 1/10 of knots to 1/10 of Km/h
471 * dataType
= JETI14_1D
;
472 airSpeedData
->airSpeed
.available
= false ;
474 #elif defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(ADS_AIRSPEED_BASED_ON)
476 if ( ! oXs_ads1115
.adsAirSpeedData
.airSpeed
.available
) return 0;
477 * fieldValue
= oXs_ads1115
.adsAirSpeedData
.airSpeed
.value
* 1.852; // convert from 1/10 of knots to 1/10 of Km/h
478 * dataType
= JETI14_1D
;
479 oXs_ads1115
.adsAirSpeedData
.airSpeed
.available
= false ;
481 #elif defined(AIRSPEED_SDP3X)
483 if ( ! oXs_sdp3x
.airSpeedData
.airSpeed
.available
) return 0;
484 * fieldValue
= oXs_sdp3x
.airSpeedData
.airSpeed
.value
* 1.852; // convert from 1/10 of knots to 1/10 of Km/h
485 * dataType
= JETI14_1D
;
486 oXs_sdp3x
.airSpeedData
.airSpeed
.available
= false ;
489 #endif // End airspseed
493 if (GPS_no_fix
) return 0 ;
494 * fieldValue
= GPS_ground_course
/ 100000 ; // convert from degree * 100000 to degree
495 * dataType
= JETI14_0D
;
498 if (GPS_no_fix
) return 0 ;
500 * fieldValue
= ((uint32_t) GPS_speed_3d
) * 36 /100 ; // convert from cm/sec to 1/10 of km/h
502 * fieldValue
= ((uint32_t) GPS_speed_2d
) * 36 /100 ; // convert from cm/sec to 1/10 of km/h
504 * dataType
= JETI14_1D
;
507 if (GPS_no_fix
) return 0 ;
508 * fieldValue
= GPS_altitude
/ 1000 ; // convert from mm to m
509 * dataType
= JETI14_0D
;
512 if (GPS_no_fix
) return 0 ;
513 * fieldValue
= GPS_distance
; // keep in m
514 * dataType
= JETI14_0D
;
517 if (GPS_no_fix
) return 0 ;
518 * fieldValue
= GPS_bearing
; // keep in degree
519 * dataType
= JETI14_0D
;
522 if (GPS_no_fix
) return 0 ;
523 jetiLong
= formatGpsLongLat (GPS_lon
, true ) ;
524 * fieldValue
= jetiLong
;
525 * dataType
= JETI_GPS
;
527 case GPS_LAT
: // Still to be added
528 if (GPS_no_fix
) return 0 ;
529 jetiLat
= formatGpsLongLat (GPS_lat
, false ) ;
530 * fieldValue
= jetiLat
;
531 * dataType
= JETI_GPS
;
533 #endif // end GPS_INSTALLED
534 #if defined ( A_FLOW_SENSOR_IS_CONNECTED ) && ( A_FLOW_SENSOR_IS_CONNECTED == YES)
536 if( ! actualFlow
.available
) return 0 ;
537 * fieldValue
= actualFlow
.value
;
538 * dataType
= JETI14_0D
;
539 actualFlow
.available
= false ; //reset the last bit to avoid sending twice the same value
542 if( ! remainingFuelML
.available
) return 0 ;
543 * fieldValue
= remainingFuelML
.value
;
544 * dataType
= JETI14_0D
;
545 remainingFuelML
.available
= false ;
548 if( ! fuelPercent
.available
) return 0 ;
549 * fieldValue
= fuelPercent
.value
;
550 * dataType
= JETI14_0D
;
551 fuelPercent
.available
= false ;
553 #endif // A_FLOW_SENSOR_IS_CONNECTED
554 #if defined (TEMPERATURE_SOURCE) && ( defined (VARIO) && ( TEMPERATURE_SOURCE == MS5611 ) )
556 * fieldValue
= varioData
->temperature
/ 100 ;
557 * dataType
= JETI14_0D
;
560 #if defined (MEASURE_RPM)
562 // if ( ! sport_rpm.available ) {
563 // * fieldValue = 0 ;
565 #if defined (PULSES_PER_ROTATION)
566 * fieldValue
= sport_rpm
.value
* 60.0 / PULSES_PER_ROTATION
;
567 #else // if PULSES_PER_ROTATION is not defined, we assume 1
568 * fieldValue
= sport_rpm
.value
* 60 ;
571 * dataType
= JETI22_0D
;
579 uint32_t OXS_OUT::formatGpsLongLat (int32_t longLat
, boolean isLong
) { // return the long or latitude in Jeti format
581 uint32_t valueInteger
;
586 uint32_t longLatE7P
;
587 longLatE7P
= (longLat
>= 0 ? longLat
: longLat
) ;
588 degree
= (uint16_t) (longLatE7P
/ 10000000) ; // remove 7 decimal from original value
589 minX1000
= (uint16_t ) ( (longLatE7P
- (degree
* 10000000)) * 6 / 1000 ) ; // keep 3 decimals to minutes
590 gps
.valueInteger
= 0;
591 gps
.valueBytes
[0] = minX1000
& 0xFF;
592 gps
.valueBytes
[1] = ( minX1000
>> 8 ) & 0xFF;
593 gps
.valueBytes
[2] = degree
& 0xFF;
594 gps
.valueBytes
[3] = ( degree
>> 8 ) & 0x01;
595 gps
.valueBytes
[3] |= isLong
? 0x20 : 0;
596 gps
.valueBytes
[3] |= (longLat
< 0) ? 0x40 : 0;
597 return gps
.valueInteger
;
600 boolean
OXS_OUT::tryToAddFieldToJetiBuffer (void) { // return true if a field has been added in the jetiBuffer
603 uint8_t fieldAvailable
= 0 ;
605 while ( countOfFieldsChecked
) {
606 // if ( listOfFieldsIdx == 0 ) { // this if has been added to generate an empty transmission like in MAVLINK to JETI but I am not sure it is needed; furthermore it should be put outside the loop.
607 // listOfFieldsIdx++ ;
610 if ( retrieveFieldIfAvailable(listOfFields
[listOfFieldsIdx
] , &fieldValue
, &dataType
) ) {
611 addFieldToJetiBuffer(fieldValue
, dataType
) ;
615 if (listOfFieldsIdx
> numberOfFields
) listOfFieldsIdx
= 1;
616 countOfFieldsChecked
-- ;
617 if ( fieldAvailable
) return true;
623 void OXS_OUT::addFieldToJetiBuffer(int32_t fieldValue
, uint8_t dataType
) { // dataType has 1 high bits = 0 ,
624 // then 2 bits to say precision (0= 0 digits, ... 2 = 2 digits) and 1 bit = 0
625 // then 4 bits to say the type in Jeti codification
627 codifJeti
= dataType
& 0x0F ;
630 jetiData
[jetiMaxData
++] = (listOfFieldsIdx
<< 4) | ( codifJeti
) ; // first 4 bits are the field identifiers ( 1...15) and the last 4 bits the type of data)
631 jetiData
[jetiMaxData
++] = fieldValue
& 0xFF ;
632 jetiData
[jetiMaxData
++] = ( fieldValue
>> 8 ) & 0xFF ;
633 jetiData
[jetiMaxData
++] = ( fieldValue
>> 16 ) & 0xFF ;
634 jetiData
[jetiMaxData
++] = ( ( fieldValue
>> 24 ) & 0x1F ) | ((fieldValue
< 0) ? 0x80 :0x00 ) ;
637 jetiData
[jetiMaxData
++] = (listOfFieldsIdx
<< 4) | (codifJeti
) ; // first 4 bits are the field identifiers ( 1...15) and the last 4 bits the type of data)
638 jetiData
[jetiMaxData
++] = fieldValue
& 0xFF ;
639 jetiData
[jetiMaxData
++] = ( fieldValue
>> 8 ) & 0xFF ;
640 jetiData
[jetiMaxData
++] = ( ( fieldValue
>> 16 ) & 0x1F ) | ((fieldValue
< 0) ? 0x80 :0x00 ) ;
643 jetiData
[jetiMaxData
++] = (listOfFieldsIdx
<< 4) | ( codifJeti
) ; // first 4 bits are the field identifiers ( 1...15) and the last 4 bits the type of data)
644 jetiData
[jetiMaxData
++] = fieldValue
& 0xFF ;
645 jetiData
[jetiMaxData
++] = ( ( fieldValue
>> 8 ) & 0x1F ) | ((fieldValue
< 0) ? 0x80 :0x00 ) ;
648 jetiData
[jetiMaxData
++] = (listOfFieldsIdx
<< 4) | ( codifJeti
) ; // first 4 bits are the field identifiers ( 1...15) and the last 4 bits the type of data)
649 jetiData
[jetiMaxData
++] = fieldValue
& 0xFF ;
650 jetiData
[jetiMaxData
++] = ( fieldValue
>> 8 ) & 0xFF ;
651 jetiData
[jetiMaxData
++] = ( fieldValue
>> 16 ) & 0xFF ;
652 jetiData
[jetiMaxData
++] = ( ( fieldValue
>> 24 ) & 0xFF ) ;
657 if ( ( codifJeti
== 8 ) || ( codifJeti
<= 4 ) ) { // when it is a number, then add precision
658 jetiData
[jetiMaxData
-1] |= dataType
& 0x60 ; // add the number of decimals in position 6 & 7 of the last byte
663 // Published in "JETI Telemetry Protocol EN V1.06"
664 //* Jeti EX Protocol: Calculate 8-bit CRC polynomial X^8 + X^2 + X + 1
665 uint8_t updateJetiCrc (uint8_t crc
, uint8_t crc_seed
)
672 crc_u
= ( crc_u
& 0x80 ) ? 7 ^ ( crc_u
<< 1 ) : ( crc_u
<< 1 );
677 void startJetiTransmit()
683 SET_TX_PIN_TO_OUTPUT() ;
684 CLEAR_TX_PIN() ; // Send a logic 0 on the TX_PIN (=start bit).
685 uint8_t oReg
= SREG
; // save status register
687 OCR1A
= TCNT1
+ TICKS2WAITONEJETI
- INTERRUPT_ENTRY_TRANSMIT
; // Count one period into the future.
688 CLEAR_TIMER_INTERRUPT() ; // Clear interrupt bits
689 SREG
= oReg
; // restore status register
690 SwUartTXBitCount
= 0 ;
691 SwUartTXData
= jetiData
[0] ;
693 SwUartTXBit8
= 0 ; // says that bit 8 must be 0 because the first byte is a separator of message
694 SwUartTXBitParity
= 0 ; // Jeti protocol uses ODD parity
696 ENABLE_TIMER_INTERRUPT() ; // Enable timer1 interrupt on again
702 void OXS_OUT::mergeLabelUnit( const uint8_t identifier
, const char * label
, const char * unit
)
707 jetiData
[8] = identifier
;
708 while( label
[i
] != '\0' )
709 jetiData
[ jetiMaxData
++ ] = label
[ i
++ ];
710 while( unit
[k
] != '\0' )
711 jetiData
[ jetiMaxData
++ ] = unit
[ k
++ ];
712 jetiData
[9] = (i
<< 3 ) | k
;
716 void OXS_OUT::fillJetiBufferWithText() {
717 static uint8_t textIdx
;
719 if (textIdx
> numberOfFields
) textIdx
= 0;
720 switch (listOfFields
[textIdx
]) {
722 mergeLabelUnit( textIdx
, "oXs", " " ) ;
726 mergeLabelUnit( textIdx
, "Rel. altit", "m" ) ;
728 case VERTICAL_SPEED
:
729 mergeLabelUnit( textIdx
, "Vario", "m/s" ) ;
732 mergeLabelUnit( textIdx
, "Alt.max", "m" ) ;
736 #if (NUMBEROFCELLS > 0)
738 mergeLabelUnit( textIdx
, "Cell 1", "V" ) ;
741 mergeLabelUnit( textIdx
, "Cell 2", "V" ) ;
744 mergeLabelUnit( textIdx
, "Cell 3", "V" ) ;
747 mergeLabelUnit( textIdx
, "Cell 4", "V" ) ;
750 mergeLabelUnit( textIdx
, "Cell 5", "V" ) ;
753 mergeLabelUnit( textIdx
, "Cell 6", "V" ) ;
756 mergeLabelUnit( textIdx
, "LowestCell", "V" ) ;
759 mergeLabelUnit( textIdx
, "Accu. volt", "V" ) ;
762 #endif // NUMBEROFCELLS > 0
764 #if defined ( TEMPERATURE_SOURCE ) && ( TEMPERATURE_SOURCE == NTC )
765 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_1 )
767 mergeLabelUnit( textIdx
, "Temp.", "\xB0\x43" ) ;
770 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_2 )
772 mergeLabelUnit( textIdx
, "Temp.", "\xB0\x43" ) ;
775 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_3 )
777 mergeLabelUnit( textIdx
, "Temp.", "\xB0\x43" ) ;
780 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_4 )
782 mergeLabelUnit( textIdx
, "Temp.", "\xB0\x43" ) ;
785 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_5 )
787 mergeLabelUnit( textIdx
, "Temp.", "\xB0\x43" ) ;
790 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_6 )
792 mergeLabelUnit( textIdx
, "Temp.", "\xB0\x43" ) ;
797 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_1 )
799 mergeLabelUnit( textIdx
, "Voltage 1", "V" ) ;
802 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_2 )
804 mergeLabelUnit( textIdx
, "Voltage 2", "V" ) ;
807 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_3 )
809 mergeLabelUnit( textIdx
, "Voltage 3", "V" ) ;
812 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_4 )
814 mergeLabelUnit( textIdx
, "Voltage 4", "V" ) ;
817 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_5 )
819 mergeLabelUnit( textIdx
, "Voltage 5", "V" ) ;
822 #if defined(ARDUINO_MEASURES_VOLTAGES) && (ARDUINO_MEASURES_VOLTAGES == YES) && defined(VOLTAGE_SOURCE) && ( VOLTAGE_SOURCE == VOLT_6 )
824 mergeLabelUnit( textIdx
, "Voltage 6", "V" ) ;
827 #endif // end defined ( TEMPERATURE_SOURCE ) && ( TEMPERATURE_SOURCE == NTC )
829 #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))
831 mergeLabelUnit( textIdx
, "Current", "A" ) ;
834 mergeLabelUnit( textIdx
, "Capacity", "mAh" ) ;
840 mergeLabelUnit( textIdx
, "Airspeed", "Km/h" ) ;
842 #elif defined(AN_ADS1115_IS_CONNECTED) && (AN_ADS1115_IS_CONNECTED == YES ) && defined(ADS_MEASURE) && defined(ADS_AIRSPEED_BASED_ON)
844 mergeLabelUnit( textIdx
, "Airspeed", "Km/h" ) ;
846 #elif defined(AIRSPEED_SDP3X)
848 mergeLabelUnit( textIdx
, "Airspeed", "Km/h" ) ;
850 #endif // End airpseed
854 mergeLabelUnit( textIdx
, "Course", degreeChar
) ;
857 mergeLabelUnit( textIdx
, "Speed", "Km/h" ) ;
860 mergeLabelUnit( textIdx
, "Gps Alt", "m" ) ;
863 mergeLabelUnit( textIdx
, "Distance", "m" ) ;
866 mergeLabelUnit( textIdx
, "Gps Bearing", degreeChar
) ;
868 case GPS_LONG
: // Still to be added
869 mergeLabelUnit( textIdx
, "Gps Long", degreeChar
) ;
871 case GPS_LAT
: // Still to be added
872 mergeLabelUnit( textIdx
, "Gps Lat", degreeChar
) ;
875 #endif // end GPS_INSTALLED
876 #if defined ( A_FLOW_SENSOR_IS_CONNECTED ) && ( A_FLOW_SENSOR_IS_CONNECTED == YES)
878 mergeLabelUnit( textIdx
, "Flow", "ml/min" ) ;
881 mergeLabelUnit( textIdx
, "Remain", "ml" ) ;
884 mergeLabelUnit( textIdx
, "Fuel", "%" ) ;
886 #endif // A_FLOW_SENSOR_IS_CONNECTED
887 #if defined (TEMPERATURE_SOURCE) && ( defined (VARIO) && ( TEMPERATURE_SOURCE == MS5611 ) )
889 mergeLabelUnit( textIdx
, "Temp.", "\xB0\x43" ) ;
892 #if defined (MEASURE_RPM)
894 mergeLabelUnit( textIdx
, "Revolution", "rpm" ) ;
899 jetiData
[2] = ( jetiMaxData
- 2 ) ; // update number of bytes that will be in buffer (including crc); keep flag in bit 6/7 to zero because it is text and not data
903 void OXS_OUT::sendData() // this part could be modified in order to put more than 1 data in a frame.
904 // the buffer must contain a header (already filled with fixed data), then DATA or TEXT part , then a CRC, a separator (0xFE), 2 * 16 char of text and a trailer (0xFF)
905 // the TEXT part contains or the name of the device or the name and unit of each field
908 // static uint32_t lastMsJetiDataFrame ;
909 // static uint32_t lastMsJetiTextFrame ;
910 // uint8_t jetiFrameReadyToSend;
911 // jetiFrameReadyToSend = 0 ;
912 static uint8_t jetiSendDataFrameCount
;
914 //printer->print("st: ") ; printer->println(state) ;
916 if (state
== IDLE
) {
917 if (jetiSendDataFrameCount
>= 5 ) { //Send a text frame instead of a data frame once every 5 data frames
918 jetiSendDataFrameCount
= 0 ;
919 //listOfFieldsIdx = 0 ; // set idx to 0 in order to force an empty frame after a TXT frame; this is not good because it could be that some fields with a high idx value are never sent if those with low value are always available
920 fillJetiBufferWithText() ; // fill the buffer (including number of bytes and type but not crc)
922 jetiSendDataFrameCount
++ ; // count the number of data frame sent (in order to send a text frame after 5 frames.
923 countOfFieldsChecked
= numberOfFields
; //countOfFieldsChecked is used in order to loop only once thru all data to be sent
924 jetiMaxData
= 8 ; // Jeti buffer contains 8 bytes in a header ; this header is already filled.
925 if ( tryToAddFieldToJetiBuffer() ) { // try to add first field and if OK, continue adding another one.
926 tryToAddFieldToJetiBuffer() ; // try to add second field
928 jetiData
[2] = 0x40 | ( jetiMaxData
- 2 ) ; // set bit to say that it concerns data (and not text) and update number of bytes that will be in buffer (including crc)
929 } // end test on jetiSendDataFrameCount
930 // if ( jetiFrameReadyToSend ) {
932 printer
->print("nf: ") ; printer
->print(numberOfFields
) ; printer
->print(" nb: ") ; printer
->print(jetiMaxData
) ; printer
->print(" > ") ;
933 for (uint8_t i
= 0 ; i
< jetiMaxData
; i
++){
934 printer
->print(jetiData
[i
], HEX
) ; printer
->print(" ");
936 printer
->println("");
940 for(c
=2; c
<jetiMaxData
; c
++) crc
= updateJetiCrc (jetiData
[c
], crc
); // calculate crc starting from position 2 from the buffer
941 jetiData
[jetiMaxData
++] = crc
; // store crc in buffer
942 //after filling data or text, we fill the buffer with the 2 lines for the display box (this seems to be mandatory by the protocol)
943 jetiData
[jetiMaxData
++] = 0xFE ; // fill the 2 lines for the display box (with 0xFE and 0xFF as delimiters) uint8_t carToSend = 0x41 ;
944 #if defined ( A_FLOW_SENSOR_IS_CONNECTED ) && ( A_FLOW_SENSOR_IS_CONNECTED == YES)
945 if (lastByteReceived
!= prevByteReceived
) {
946 prevByteReceived
= lastByteReceived
;
947 processReceivedCmd( lastByteReceived
) ;
950 #else // when a flow sensor is not connected, we send always a dummy text
951 for ( uint8_t i_jetiBoxText
= 0 ; i_jetiBoxText
< 16 ; i_jetiBoxText
++ ) {
952 jetiData
[jetiMaxData
++] = 0x2E ; // here it is a dummy text; it could be changed later on.
953 jetiData
[jetiMaxData
++] = 0x2D ;
956 jetiData
[jetiMaxData
++] = 0xFF ;
957 #ifdef DEBUGJETIFRAME // print the jeti buffer on 4 lines
958 //printer->print(F("01 02 03 04 05 06 07 08 09 0A 0B 0C 0D 0E 0F 10 11 12 13 14 15 16 17 18 19 1A 1B 1C 1E 1F 20 21 22 23 24 25 26 27 "));
959 //printer->print(F("28 29 2A 2B 2C 2D 2E 2F 30 31 32 33 34 35 36 37 38 39 3A 3B 3C 3D 3E 3F 40 "));
960 //printer->println(F("41 42 43 44 45 46 47 48 49 4A 4B 4C 4D 4E 4F 50 51 52 53 54 55 56 57 58 59 "));
961 //for (int i = 0 ; i<jetiMaxData ; i++ ) // to display the full buffer
963 for (int i = 8 ; i<= 13 ; i++ ) // to display only the first 2 bytes data
965 if ( jetiData[i]< 0x10 ) printer->print("0") ;
966 printer->print(jetiData[i],HEX); printer->print(" ");
968 printer->println("");
971 for (int i
= 0 ; i
<jetiMaxData
; i
++ )
973 if ( jetiData
[i
] >= 0x20 && jetiData
[i
] <= 0x7F) {
974 printer
->write(jetiData
[i
]);
977 if ( jetiData
[i
]< 0x10 ) printer
->print("0") ;
978 printer
->print(jetiData
[i
],HEX
);printer
->print(" ");
981 printer
->println(""); printer
->println("");
984 startJetiTransmit() ;
986 } // end state == IDLE
990 void processReceivedCmd( uint8_t cmd
) {
994 if (jetiMenu
> JETI_MENU_MAX
) jetiMenu
= 0 ;
998 if (jetiMenu
> JETI_MENU_MAX
) jetiMenu
= JETI_MENU_MAX
;
1001 if ( jetiMenu
== JETI_TANK_RESET
) consumedML
= 0 ;
1010 } // end processReceivedCmd
1012 void upDown ( int8_t upOrDown
) {
1013 if ( jetiMenu
== JETI_TANK_CAPACITY
) {
1014 tankCapacity
+= (50 * upOrDown
);
1016 else if ( ( jetiMenu
>= JETI_CAL_FLOW_1
) && (jetiMenu
<= JETI_CAL_FLOW_4
) ) {
1017 flowParam
[jetiMenu
- JETI_CAL_FLOW_1
]+= (5 * upOrDown
) ;
1019 else if ( ( jetiMenu
>= JETI_CORR_FLOW_1
) && (jetiMenu
<= JETI_CORR_FLOW_4
) ) {
1020 flowParam
[jetiMenu
- JETI_CAL_FLOW_1
] += upOrDown
;
1022 checkFlowParam() ; // check that new values are valid and consistent (is defined in openXsensor.ino)
1025 void memcpy_p (uint8_t posDes
, uint8_t posSrc
) {
1026 for (uint8_t i
= 0 ; i
<32 ; i
++) {
1027 jetiData
[posDes
++] = pgm_read_byte_near( jetiText
+ posSrc
++ ) ;
1030 void fillTxBuffer( void ){
1031 if (jetiMenu
< JETI_CAL_FLOW_1
) {
1032 memcpy_p ( jetiMaxData
, jetiMenu
* 32 ) ; // copy the text from a table (in flash memory) to the buffer
1033 switch ( jetiMenu
) {
1035 itoc( (int16_t) actualFlow
.value
, jetiMaxData
+ 8 ) ;
1036 itoc( (int16_t) remainingFuelML
.value
, jetiMaxData
+ 16 + 12 ) ;
1038 case JETI_TANK_RESET
:
1039 itoc( (int16_t) fuelPercent
.value
, jetiMaxData
+ 16 + 13 ) ;
1041 case JETI_TANK_CAPACITY
:
1042 itoc( tankCapacity
, jetiMaxData
+ 16 + 12 ) ;
1045 } else if ( jetiMenu
< JETI_CORR_FLOW_1
) {
1046 memcpy_p( jetiMaxData
, 32 * JETI_CAL_FLOW_1
) ; // copy the text from a table (in flash memory) to the buffer
1047 itoc( jetiMenu
- JETI_CAL_FLOW_1
+ 1 , jetiMaxData
+ 12 ) ;
1048 itoc( flowParam
[jetiMenu
- JETI_CAL_FLOW_1
] , jetiMaxData
+ 16 + 8 ) ;
1050 memcpy_p( jetiMaxData
, 32 * (JETI_CAL_FLOW_1
+ 1) ) ; // copy the text from a table (in flash memory) to the buffer
1051 itoc( jetiMenu
- JETI_CORR_FLOW_1
+ 1 , jetiMaxData
+ 12 ) ;
1052 itoc( flowParam
[jetiMenu
- JETI_CAL_FLOW_1
] , jetiMaxData
+ 16 + 13 ) ;
1055 } // end fillTxBuffer
1057 void itoc ( int16_t n
, uint8_t posLastDigit
) {
1060 if ( n
< 0 ) // record sign
1062 n
= -n
; // make n positive
1067 { // generate digits in reverse order
1068 jetiData
[posLastDigit
--] = n
% 10 + '0'; // get next digit
1069 } while ((n
/= 10) > 0) ; // delete it
1072 jetiData
[posLastDigit
] = '-';
1076 //---------------------------------- Here the code to handle the UART
1078 #define FORCE_INDIRECT(ptr) __asm__ __volatile__ ("" : "=e" (ptr) : "0" (ptr))
1082 ISR(TIMER1_COMPA_vect
)
1086 case TRANSMIT
: // startbit has been sent, it is time to output now 8 bits and 1 stop bit
1090 if( SwUartTXBitCount
< 8 ) { // If not 8 bits have been sent
1091 if( SwUartTXData
& 0x01 ) { // If the LSB of the TX buffer is 1:
1093 SwUartTXBitParity
++; // count the number of 1 for ODD parity
1094 } else { // Otherwise:
1095 CLEAR_TX_PIN() ; // Send a logic 0 on the TX_PIN
1097 SwUartTXData
= SwUartTXData
>> 1 ; // Bitshift the TX buffer and
1098 } else if ( SwUartTXBitCount
== 8) { // send bit 9 that says if the byte is the header or not.
1099 if( SwUartTXBit8
) { // If the bit 9 is set, then send a logic 1 on TX_PIN:
1101 SwUartTXBitParity
++; // count the number of 1 for ODD parity
1102 } else { // Otherwise:
1103 CLEAR_TX_PIN() ; // Send a logic 0 on the TX_PIN (this is the case for a separator of message)
1105 } else if ( SwUartTXBitCount
== 9) { // send parity bit (ODD parity in Jeti protocol)
1106 if( SwUartTXBitParity
& 0x01 ) { // If the number of bits set to 1 is odd, then send a logic 0on TX_PIN:
1108 } else { // Otherwise:
1109 SET_TX_PIN() ; // Send a logic 1 on the TX_PIN
1112 //Send stop bit after the parity bit.
1113 SET_TX_PIN() ; // Output a logic 1.
1114 OCR1A
+= TICKS2WAITONEJETI
+ TICKS2WAITONEJETI
; // Count already a first period into the future, the second is added just below (Jeti uses 2 stop bits); here we add a third stop bit because it does not seems to work with only 2
1115 state
= TRANSMIT_STOP_BIT
;
1117 SwUartTXBitCount
+= 1 ; // increment TX bit counter.
1118 OCR1A
+= TICKS2WAITONEJETI
; // Count 2 period into the future. (Jeti uses 2 stop bits)
1124 case TRANSMIT_STOP_BIT
: //************************************* handling after the stop bit has been sent
1125 if ( ++TxCount
< jetiMaxData
) {
1126 SwUartTXData
= jetiData
[TxCount
] ;
1127 CLEAR_TX_PIN(); // Send a logic 0 on the TX_PIN as start bit
1128 OCR1A
= TCNT1
+ TICKS2WAITONEJETI
- INTERRUPT_BETWEEN_TRANSMIT
; // Count one period into the future.
1129 SwUartTXBitCount
= 0 ;
1130 if ( (TxCount
== ( jetiMaxData
- 1 )) || (TxCount
== ( jetiMaxData
-34 )) )
1132 SwUartTXBit8
= 0 ; // force a bit 8 to 0 for the 2 text delimiters
1134 SwUartTXBit8
= 1 ; // force the bit 8 to 1 because only the first byte and the text delimiters in the buffer requests a bit 8 = 0
1136 SwUartTXBitParity
= 0 ; // reset the value for ODD parity to 0
1139 } else { // all bytes have already been sent
1141 nbWaitingDelay
= 15 ; // use a counter to extend the delay for the WAITING State (Jeti asks for 20 msec between 2 frames); here we put 30 msec for safety
1142 OCR1A
+= DELAY_2000
; // 2mS gap before listening (so before going to IDLE)
1143 TRXDDR
&= ~( 1 << PIN_SERIALTX
) ; // PIN become input during the WAIT time (it will become output when a new frame will be sent)
1144 TRXPORT
|= ( 1 << PIN_SERIALTX
) ; // PIN is pull up because it could be that the Rx send a byte (half duplex)
1145 CLEAR_PIN_CHANGE_INTERRUPT( ) ; // clear pin change interrupt 2 (on port D) used by Rx and Tx (arduino pin 2 or pin 4)
1146 ENABLE_PIN_CHANGE_INTERRUPT( ) ; // enable pin change interrupt 2 (because Jeti Rx could send a byte that we want to read)
1150 case WAITING
: // At the end of wait time, stop timer interrupt
1151 if (--nbWaitingDelay
) {
1152 OCR1A
+= DELAY_2000
; // wait one more time for 2 msec
1154 state
= IDLE
; // Go back to idle.
1155 DISABLE_TIMER_INTERRUPT() ; // Stop the timer interrupt. We will wait that the main loop ask for sending a frame and reactivate the interrupt
1156 DISABLE_TIMERB_INTERRUPT() ; // Stop the timer COMPB interrupts because the RX can't send a keyboard key anymore
1157 DISABLE_PIN_CHANGE_INTERRUPT() ; // disable pin change interrupt 2 (on port d) because we do not have to wait anymore for a byte sent by Tx
1164 state
= IDLE
; // Error, should not occur. Going to a safe state.
1166 //#ifdef PPM_INTERRUPT
1167 // if ( EIFR & PPM_INT_BIT) ppmInterrupted = 1 ;
1173 // ! \brief External interrupt service routine. ********************
1174 // Interrupt on Pin Change to detect change on level on Jeti signal (= could be a start bit)
1176 // The falling edge in the beginning of the start
1177 // bit will trig this interrupt. The stateReceive will
1178 // be changed to RECEIVE, and the timer interrupt B
1179 // will be set to trig one and a half bit period
1180 // from the falling edge. At that instant the
1181 // code should sample the first data bit.
1183 // note initSoftwareUart( void ) must be called in advance.
1185 // This is the pin change interrupt for port D
1186 // This assumes it is the only pin change interrupt on port D
1189 if ( ! (TRXPIN
& ( 1 << PIN_SERIALTX
) )) { // if Pin is low = start bit (inverted)
1190 DISABLE_PIN_CHANGE_INTERRUPT() ; // pin change interrupt disabled (it will be reactivated when a frame has been sent
1193 DISABLE_TIMERB_INTERRUPT() ; // Disable timer to change its registers. (normally not needed because TimerB interrupt is not active)
1194 OCR1B
= TCNT1
+ TICKS2WAITONE_HALFJETI
- INTERRUPT_EXEC_CYCL
- INTERRUPT_EARLY_BIAS
; // Count one and a half period into the future.
1195 #ifdef DEBUG_SERIAL_RX
1198 SwUartRXBitCount
= 0 ; // Clear received bit counter.
1199 SwUartRXData
= 0 ; // Reset the byte that will contains the byte being read
1200 CLEAR_TIMERB_INTERRUPT() ; // Clear interrupt bits
1201 ENABLE_TIMERB_INTERRUPT() ; // Enable timerB interrupt on again
1206 ISR(TIMER1_COMPB_vect
) // interrupt on COMPB is used to receive data (keyboard jetibox) from Rx while COMPA is still used to wait some delay between 2 frames
1209 OCR1B
+= TICKS2WAITONEJETI
; // Count one period after the falling edge is trigged.
1210 uint8_t data
; // Use a temporary local storage
1211 data
= SwUartRXBitCount
;
1212 if( data
< 8 ) { // If 8 bits are not yet read
1213 SwUartRXBitCount
= data
+ 1 ;
1214 data
= SwUartRXData
;
1215 data
>>= 1 ; // Shift due to receiving LSB first.
1216 if( GET_RX_PIN( ) ) {
1217 data
|= 0x80 ; // If a logical 1 is read, let the data mirror this.
1219 SwUartRXData
= data
;
1220 } else if ( data
== 8 ) { // we got 8 bits, so now we get the bit 9
1221 SwUartRXBitCount
= data
+ 1 ;
1222 SwUartRXBit9
= GET_RX_PIN( ) ;
1223 } else { //Done receiving = 8 bits are in SwUartRXData and 9th bit in SwUartRXBit9 is ready
1224 #ifdef DEBUG_SERIAL_RX
1228 SwUartRXBitParity
= GET_RX_PIN( ) ;
1229 // if ( ( ( SwUartRXData & 0X0F ) == 0 ) && ( SwUartRXBit9 == 0) ) { // check that last 4 bits are 0 and that bit 9 = 0; in fact we could also check the parity bit
1230 oneByteReceived
= true ; // Keep a flag that is true when a byte has been received
1231 lastByteReceived
= SwUartRXData
; // Keep the last byte received
1233 DISABLE_TIMERB_INTERRUPT() ; // Stop the timer COMPB interrupts.
1234 #ifdef DEBUG_SERIAL_RX
1241 } // end ISR TIMER1_COMPB_vect
1243 // in ISR TIMER1_COMP_vect, when a frame has been totaly sent, interrupt on pin change must be cleared and enabled. TODO (to uncomment)
1244 // when state become IDLE (end of 20 or 30 ms) after sending a frame, interrupt on COMPB must be disabled TODO (to uncomment)
1245 // in pin change interrupt, pin change interrupt must be disabled and SwUartRxBitCount must be reset to 0 and COMPB must be cleared and enabled ;
1246 // in SEND data, before filling the frame we should check if a byte has been received (oneByteReceived = true) and oneByteReceived should be set on false. TODO (to add)
1249 // -------------------------End of Jeti protocol--------------------------------------------------------------------------------------
1251 #endif // END of JETI