Handle the received gps configuration messages sent by ruwaicom.
[ruwai.git] / software / arduino / ruwai / ruwai.ino
blob7487595ee0cc4529cdd50b4dc341b91f70618417
1 // -*- coding: utf-8 -*-
2 // LICENSE
3 //
4 // This file is part of ruwai.
5 //
6 // If you use ruwai in any program or publication, please inform and
7 // acknowledge its author Stefan Mertl (stefan@mertl-research.at).
8 //
9 // pSysmon is free software: you can redistribute it and/or modify
10 // it under the terms of the GNU General Public License as published by
11 // the Free Software Foundation, either version 3 of the License, or
12 // (at your option) any later version.
14 // This program is distributed in the hope that it will be useful,
15 // but WITHOUT ANY WARRANTY; without even the implied warranty of
16 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17 // GNU General Public License for more details.
19 // You should have received a copy of the GNU General Public License
20 // along with this program.  If not, see <http://www.gnu.org/licenses/>.
22 #include <ruwai.h>
23 #include <rw_control.h>
24 #include <gps_ublox.h>
25 #include <ubx_protocol.h>
26 #include <rw_protocol.h>
27 #include <rw_pga281.h>
28 #include <timer16.h>
29 #include <rw_adc.h>
30 #include <SPI.h>
31 #include <Wire.h>
32 #include <OneWire.h>
33 #include <DallasTemperature.h>
34 #include <avr/wdt.h>
35 #include <avr/sleep.h>
36 #include <avr/power.h>
37 #include <rw_serial.h>
39 void data_ready_isr(void);
40 void gps_pps_isr(void);
41 void send_samples(void);
42 void send_samples_with_timestamp(void);
43 void record_loop(void);
44 void control_loop(void);
45 void set_control_mode(void);
46 void set_record_mode(void);
47 void arduino_reconnect(void);
48 void connect_gps(void);
49 void init_state(void);
50 void init_thermometer(void);
51 void sleep_now(void);
52 void sync_adc(void);
53 //void send_ruwai_message(uint8_t msg_class, uint8_t msg_id, void* msg, uint8_t length);
55 RuwaiSerial &usb_serial = RwSerial0;
56 RuwaiSerial &gps_serial = RwSerial2;
57 RuwaiSerial &ruwai_serial = RwSerial3;
59 // Setup a oneWire bus.
60 OneWire one_wire(ONEWIREBUS);
61 DallasTemperature ds_sensors(&one_wire);
62 DeviceAddress ds_gts;
65 uint8_t led = 13;
66 uint8_t count = 0;
67 uint8_t gps_byte_available = 0;
68 uint8_t ruwai_byte_available = 0;
69 volatile bool record_mode = false;
70 volatile bool control_mode = false;
71 volatile bool adc_data_ready = false;
72 volatile bool samples_ready = false;
73 volatile bool pps_set = false;
74 volatile bool timestamp_set = false;
75 volatile uint8_t ts_marker_id = 0;
76 volatile uint32_t sec_slts = 0;             // Seconds since last timestamp.
78 // Debug output pins.
79 bool pin_state_46 = false;
80 bool pin_state_47 = false;
81 bool pin_state_48 = false;
82 bool pin_state_49 = false;
84 RuwaiControl ruwai_control = RuwaiControl(ruwai_serial);
85 GpsLea6T gps = GpsLea6T(gps_serial);
86 //GpsLea6T gps = GpsLea6T(usb_serial);
87 RwAdc adc = RwAdc(S1_PCF_ADC, S1_PCF_PGA1, S1_PCF_PGA2, S1_PCF_PGA3, S1_PCF_PGA4);
88 //Timer16 &timer1 = Timer1;
90 uint8_t test_counter = 0;
91 uint16_t dbg_sample_counter = 0;
93 void setup(void) {
94     // Clear the watchdog reset flag and enable the watchdog.
95     MCUSR = 0;
96     wdt_enable(WDTO_8S);
98     // Clear the interrupt service routines.
99     detachInterrupt(ADC_DRDY_INTERRUPT);
100     detachInterrupt(GPS_TP_INTERRUPT);
102     String status_msg;
104     // Activate the debug serial output on Serial0.
105     usb_serial.begin(USB_SERIAL_BAUDRATE);
106     usb_serial.println("SETUP");
108     // Initialize the output pins.
109     pinMode(led, OUTPUT);
110     pinMode(46, OUTPUT);
111     digitalWrite(46, pin_state_46);
112     pinMode(47, OUTPUT);
113     digitalWrite(47, pin_state_47);
114     pinMode(48, OUTPUT);
115     digitalWrite(48, pin_state_48);
116     pinMode(49, OUTPUT);
117     digitalWrite(49, pin_state_48);
118     wdt_reset();
121     // Initialize serial port used for communication with the BBB.
122     ruwai_control.start_serial(RUWAI_SERIAL_BAUDRATE);
123     wdt_reset();
125     // Handshake with ruwaicom running on Beaglebone.
126     usb_serial.println("Waiting for handshake...");
127     bool handshake_success = ruwai_control.handshake();
128     if (handshake_success)
129     {
130         usb_serial.println("handshake success.");
131         ruwai_control.send_status(RW_STATUS_NOTICE, "Handshake with BBB established.");
132     }
135     status_msg = "Hello, Arduino Stack is speaking. Running on version ";
136     status_msg += VERSION;
137     ruwai_control.send_status(RW_STATUS_NOTICE, status_msg);
138     wdt_reset();
140     // Initialize the I2C communication.
141     Wire.begin();
143     // Initialize ADC. By default all channels are enabled.
144     usb_serial.println("Init ADC");
145     ruwai_control.send_status(RW_STATUS_NOTICE, "Init ADC.");
146     adc.begin(ADC_MODE_LOWSPEED_CLKDIV_1, ADC_FORMAT_SPI_TDM_FIXED);
147     wdt_reset();
150     usb_serial.println("Connect to GPS");
151     ruwai_control.send_status(RW_STATUS_NOTICE, "Connect to GPS.");
152     connect_gps();
153     wdt_reset();
155     usb_serial.println("Initializing the thermometer.");
156     init_thermometer();
157     wdt_reset();
159     /* 
160     gps.set_timepulse2_frequency(2048000, 2048000);
161     set_record_mode();
162     */
164     // Activate the control mode.
165     set_control_mode();
166     wdt_reset();
168     // Syncing the ADC might block because of a missing PPS interrupt. Call it
169     // after the watchdog has been enabled.
170     sync_adc();
171     wdt_reset();
173     // TODO: Get the ADC configuration from ruwaicom.
174     //adc.begin(ADC_MODE_LOWSPEED_CLKDIV_0, ADC_FORMAT_SPI_TDM_FIXED);
175     //adc.begin(ADC_MODE_HIGHRES, ADC_FORMAT_SPI_TDM_FIXED);
176     //adc.begin(ADC_MODE_LOWPOW_CLKDIV_1, ADC_FORMAT_SPI_TDM_FIXED);
177     //adc.disable_channel(1);
178     //adc.disable_channel(2);
179     //adc.disable_channel(3);
180     //adc.disable_channel(4);
182     //clk_freq = adc.get_clk_freq(800);
186 void init_state(void)
188     record_mode = false;
189     control_mode = false;
190     adc_data_ready = false;
191     samples_ready = false;
192     pps_set = false;
193     timestamp_set = false;
196 void connect_gps(void)
198     bool success = false;
199     String status_msg;
201     // Check for correct baud rate.
202     usb_serial.println("Start testing the baud rates:");
203     ruwai_control.send_status(RW_STATUS_NOTICE, "Start testing the baud rates.");
204     uint32_t detected_baudrate = 0;
205     uint32_t working_baudrate = 0;
207     while (detected_baudrate == 0)
208     {
209         detected_baudrate = gps.detect_baud_rate(GPS_DEFAULT_BAUDRATE, GPS_BAUDRATE);
210         usb_serial.println("Detected baudrate:");
211         usb_serial.println(detected_baudrate);
212         status_msg = "Detected baud rate: ";
213         status_msg += detected_baudrate;
214         ruwai_control.send_status(RW_STATUS_NOTICE, status_msg);
215     }
217     usb_serial.println("Starting GPS serial with detected baud rate.");
218     ruwai_control.send_status(RW_STATUS_NOTICE, "Starting GPS serial with detected baud rate.");
219     bool gps_serial_up = gps.start_serial(detected_baudrate);
220     if (gps_serial_up)
221     {
222         usb_serial.println("Established serial connection with GPS.");
223         ruwai_control.send_status(RW_STATUS_NOTICE, "Established serial connection with GPS.");
224     }
225     else
226     {
227         usb_serial.println("The serial connection to the GPS is not working.");
228         ruwai_control.send_status(RW_STATUS_NOTICE, "The serial connection to the GPS is not working.");
229     }
231     usb_serial.println("Disabling the default messages.");
232     ruwai_control.send_status(RW_STATUS_NOTICE, "Disabling the default messages.");
233     uint8_t ack_status = gps.disable_default_messages();
234     usb_serial.println("ack_status");
235     usb_serial.println(ack_status, BIN);
236     usb_serial.println("-------");
237     status_msg = "Message disable ack status: ";
238     status_msg += String(ack_status, BIN);
239     ruwai_control.send_status(RW_STATUS_NOTICE, status_msg);
241     usb_serial.println("Disabling the timepulse2 frequency.");
242     ruwai_control.send_status(RW_STATUS_NOTICE, "Disabling the timepulse2 frequency.");
243     success = gps.disable_timepulse2_frequency();
244     if (success)
245     {
246         usb_serial.println("success");
247         ruwai_control.send_status(RW_STATUS_NOTICE, "Succesfully disabled the timepulse 2 frequency.");
248     }
249     else
250     {
251         usb_serial.println("no confirmation");
252         ruwai_control.send_status(RW_STATUS_NOTICE, "No confirmation for disabling the timepulse 2 frequency.");
253     }
255     // Configure the baudrate of the GPS module.
256     if (detected_baudrate != GPS_BAUDRATE)
257     {
258         working_baudrate = GPS_BAUDRATE;
260         usb_serial.println("Setting the new GPS baudrate.");
261         status_msg = "Setting the GPS baud rate to the desired value of ";
262         status_msg += working_baudrate;
263         ruwai_control.send_status(RW_STATUS_NOTICE, status_msg);
264         gps.set_uart1_baudrate(GPS_BAUDRATE);
266         usb_serial.println("Stopping the gps serial.");
267         ruwai_control.send_status(RW_STATUS_NOTICE, "Stopping the GPS serial.");
268         gps.stop_serial();
270         usb_serial.println("Reconnect using the new baud rate.");
271         ruwai_control.send_status(RW_STATUS_NOTICE, "Reconnect using the new baud rate.");
273         while (!gps.start_serial(GPS_BAUDRATE))
274         {
275             gps.stop_serial();
276             usb_serial.println("Stopped the serial.");
277         }
279         usb_serial.println("GPS connection with new baud rate established.");
280         ruwai_control.send_status(RW_STATUS_NOTICE, "GPS connection with the new baud rate established.");
281     }
282     else
283     {
284         working_baudrate = detected_baudrate;
285         status_msg = "The detected baud rate is already the desired baud rate of ";
286         status_msg += GPS_BAUDRATE;
287         ruwai_control.send_status(RW_STATUS_NOTICE, status_msg);
288     }
290     status_msg = "Communicating with the GPS using baud rate ";
291     status_msg += working_baudrate;
292     ruwai_control.send_status(RW_STATUS_NOTICE, status_msg);
295     // Enable the needed UBX messages.
296     // TODO: Save the succes in the bitfield.
297     ruwai_control.send_status(RW_STATUS_NOTICE, "Enabling the GPS UBX messages.");
298     gps.enable_message(UBX_CLASS_NAV, UBX_NAV_ID_STATUS, 1);
299     gps.enable_message(UBX_CLASS_NAV, UBX_NAV_ID_TIMEUTC, 1);
300     gps.enable_message(UBX_CLASS_NAV, UBX_NAV_ID_POSLLH, 60);
301     gps.enable_message(UBX_CLASS_TIM, UBX_TIM_ID_TP, 1);
303     // Configure the timepulse 1.
304     ruwai_control.send_status(RW_STATUS_NOTICE, "Setting the timepulse 1.");
305     gps.set_timepulse1_pps();
307     // Initialize the PPS interrupt.
308     attachInterrupt(GPS_TP_INTERRUPT, gps_pps_isr, RISING);
311     // Configure the USB Port.
312     ruwai_control.send_status(RW_STATUS_NOTICE, "Disabling the GPS USB port.");
313     gps.disable_usb();
315     ruwai_control.send_status(RW_STATUS_NOTICE, "Finished configuration of the GPS.");
318 void
319 init_thermometer(void)
321     // Connect to the DS18B20 thermometer.
322     usb_serial.println("Locating oneWire devices...");
323     ds_sensors.begin();
324     usb_serial.print("Found ");
325     usb_serial.print(ds_sensors.getDeviceCount(), DEC);
326     usb_serial.println(" devices.");
327     if (!ds_sensors.getAddress(ds_gts, 0))
328     {
329         usb_serial.println("Unable to find address for OneWire sensor 0.");
330         ruwai_control.send_status(RW_STATUS_ERROR, "Unable to find address for OneWire sensor 0.");
331     }
332     // Set the sensor resolution to 10 bit (0.25 degree).
333     ds_sensors.setResolution(ds_gts, 10);
334     int resolution = ds_sensors.getResolution(ds_gts);
335     usb_serial.print("Device 0 Resolution: ");
336     usb_serial.println(resolution, DEC); 
337     usb_serial.print("Requesting temperature...");
338     ds_sensors.requestTemperaturesByAddress(ds_gts);
339     usb_serial.println("...done.");
340     float temp_c = ds_sensors.getTempC(ds_gts);
341     usb_serial.print("Temperature: ");
342     usb_serial.println(temp_c);
344     rw_soh_envdata_t msg;
345     msg.temp_gts = (int32_t) (temp_c * 100);
346     ruwai_control.send_message(RW_CLASS_SOH, RW_SOH_ID_ENVDATA, &msg, sizeof(msg));
351 void arduino_reconnect(void)
353     String status_msg;
355     wdt_reset();
356     ruwai_control.send_status(RW_STATUS_NOTICE, "Starting reconnection....");
358     // Clear the interrupt service routines.
359     detachInterrupt(ADC_DRDY_INTERRUPT);
360     detachInterrupt(GPS_TP_INTERRUPT);
362     /*
363     usb_serial.println("Disable the Watchdog Timer.");
364     ruwai_control.send_status(RW_STATUS_NOTICE, "Disabling the watchdog timer.");
365     wdt_disable();
366     */
367     usb_serial.println("Initialize the state.");
368     ruwai_control.send_status(RW_STATUS_NOTICE, "Initialize the ruwai state.");
369     init_state();
370     wdt_reset();
372     usb_serial.println("Initialize ADC.");
373     ruwai_control.send_status(RW_STATUS_NOTICE, "Initialize the ADC.");
374     //adc.end();
375     adc.begin(ADC_MODE_LOWSPEED_CLKDIV_1, ADC_FORMAT_SPI_TDM_FIXED);
376     wdt_reset();
378     usb_serial.println("RECONNECT");
379     ruwai_control.send_status(RW_STATUS_NOTICE, "Reconnect to GPS.");
380     gps.init_state();
381     gps.stop_serial();
382     connect_gps(); 
383     wdt_reset();
385     usb_serial.println("Reset the Ruwai Control.");
386     ruwai_control.send_status(RW_STATUS_NOTICE, "Reset the ruwai control.");
387     ruwai_control.reset();
388     wdt_reset();
390     usb_serial.println("Waiting for handshake.");
391     bool handshake_success = ruwai_control.handshake();
392     if (handshake_success)
393     {
394         usb_serial.println("Handshake success."); 
395         ruwai_control.send_status(RW_STATUS_NOTICE, "Handshake with BBB established.");
396     }
398     status_msg = "Hello, Arduino Stack is back. Running on version ";
399     status_msg += VERSION;
400     ruwai_control.send_status(RW_STATUS_NOTICE, status_msg);
401     wdt_reset();
403     init_thermometer();
404     wdt_reset();
406     set_control_mode();
407     wdt_reset();
409     // Syncing the ADC might block because of a missing PPS interrupt. Call it
410     // after the watchdog has been enabled.
411     sync_adc();
412     wdt_reset();
417 void set_control_mode(void)
419     usb_serial.println("ENTER CONTROL MODE");
420     control_mode = true;
421     record_mode = false;
423     detachInterrupt(ADC_DRDY_INTERRUPT);
424     ruwai_control.send_status(RW_STATUS_NOTICE, "Control mode activated.");
428 void set_record_mode(void)
430     usb_serial.println("ENTER RECORD MODE");
431     control_mode = false;
432     record_mode = true;
434     //digitalWrite(47, LOW);
436     attachInterrupt(ADC_DRDY_INTERRUPT, data_ready_isr, FALLING);
437     ruwai_control.send_status(RW_STATUS_NOTICE, "Record mode activated.");
441 void sleep_now(void)
443     //set_sleep_mode(SLEEP_MODE_STANDBY);
444     set_sleep_mode(SLEEP_MODE_IDLE);
446     // Disable peripherals that are not needed.
447     //power_spi_disable();
448     power_adc_disable();
449     power_timer0_disable();
450     power_timer1_disable();
451     power_twi_disable();
453     cli();
454     if (!adc_data_ready)
455     {
456         sleep_enable();
457         sei(); 
458         sleep_cpu();
459         sleep_disable();
460     }
461     sei();
463     // Upon waking up.
464     power_all_enable();
467 void sync_adc(void)
469     uint32_t clk_freq;
470     float t_syn;
471     uint32_t t_syn_u;
473     // Start the ADC. Sync to PPS.
474     clk_freq = adc.get_clk_freq(ruwai_control.rcv_cfg_sps.sps);
475     t_syn = 1 / clk_freq;
476     t_syn_u = (uint32_t) ceil(t_syn * 1e6);
477     if (t_syn_u == 0)
478     {
479         t_syn_u = 1;
480     }
482     // Wait for a PPS interrupt.
483     while(!pps_set)
484     {
485     }
486     digitalWrite(ADC_SYNC, LOW);
487     delayMicroseconds(2 * t_syn_u);
488     pps_set = false;
489     digitalWrite(47, LOW);
491     // Sync the ADC after the next received PPS.
492     while(!pps_set)
493     {
494     }    
495     digitalWrite(ADC_SYNC, HIGH);
496     pps_set = false;
501 void loop(void)
503     // Reset the watchdog.
504     wdt_reset();
506     if (control_mode)
507     {
508         control_loop();
509     }
510     else if (record_mode)
511     {
512         record_loop();
513     }
519 void control_loop(void)
521     uint32_t clk_freq;
522     bool ruwai_parsed = false;
523     String status_msg;
525     ruwai_byte_available = RwSerial3.available();
526     if (ruwai_byte_available > 0)
527     {
528         ruwai_parsed = ruwai_control.read();
529     }
531     if (ruwai_parsed)
532     {
533         if (ruwai_control.rcv_cfg_sps_changed)
534         {
535             // Set the new frequency and wait some time for the frequency to
536             // settle.
537             clk_freq = adc.get_clk_freq(ruwai_control.rcv_cfg_sps.sps);
538             gps.set_timepulse2_frequency(clk_freq, clk_freq);
539             delay(1000);
541             ruwai_control.rcv_cfg_sps_changed = false;
542             status_msg = "Set clock frequency to ";
543             status_msg += clk_freq;
544             status_msg += ".";
545             ruwai_control.send_status(RW_STATUS_NOTICE, status_msg);
546             ruwai_control.ack_msg(RW_CLASS_CFG, RW_CFG_ID_SPS);
547         }
549         if (ruwai_control.rcv_cfg_channels_changed)
550         {
551             if (ruwai_control.rcv_cfg_channels.active.channel1)
552                 adc.enable_channel(1);
553             else
554                 adc.disable_channel(1);
556             if (ruwai_control.rcv_cfg_channels.active.channel2)
557                 adc.enable_channel(2);
558             else
559                 adc.disable_channel(2);
561             if (ruwai_control.rcv_cfg_channels.active.channel3)
562                 adc.enable_channel(3);
563             else
564                 adc.disable_channel(3);
566             if (ruwai_control.rcv_cfg_channels.active.channel4)
567                 adc.enable_channel(4);
568             else
569                 adc.disable_channel(4);
571             adc.set_gain(1, (pga_gain_t)ruwai_control.rcv_cfg_channels.gain_channel1);
572             adc.set_gain(2, (pga_gain_t)ruwai_control.rcv_cfg_channels.gain_channel2);
573             adc.set_gain(3, (pga_gain_t)ruwai_control.rcv_cfg_channels.gain_channel3);
574             adc.set_gain(4, (pga_gain_t)ruwai_control.rcv_cfg_channels.gain_channel4);
575             ruwai_control.rcv_cfg_channels_changed = false;
576             ruwai_control.ack_msg(RW_CLASS_CFG, RW_CFG_ID_CHANNELS);
577         }
579         if (ruwai_control.rcv_cfg_mode_changed)
580         {
581             if (ruwai_control.rcv_cfg_mode.mode == 0)
582             {
583                 set_control_mode();
584             }
585             else if (ruwai_control.rcv_cfg_mode.mode == 1)
586             {
587                 set_record_mode();
588             }
590             ruwai_control.rcv_cfg_mode_changed = false;
591             ruwai_control.ack_msg(RW_CLASS_CFG, RW_CFG_ID_MODE);
592         }
594         if (ruwai_control.rcv_cfg_gps_changed)
595         {
596             if (ruwai_control.rcv_cfg_gps.ports.usb == 0)
597             {
598                 gps.disable_usb();
599             }
600             else if (ruwai_control.rcv_cfg_gps.ports.usb == 1)
601             {
602                 gps.enable_usb();
603             }
605             ruwai_control.rcv_cfg_gps_changed = false;
606             ruwai_control.ack_msg(RW_CLASS_CFG, RW_CFG_ID_GPS);
607         }
609         if (ruwai_control.rcv_ack_sync_changed)
610         {
611             usb_serial.println("sync in control mode");
612             ruwai_control.send_status(RW_STATUS_NOTICE, "Received sync request in control mode.");
613             arduino_reconnect();
614         }
616         if (ruwai_control.rcv_soh_request_changed)
617         {
618             usb_serial.print("Received a SOH request for msg_id ");
619             usb_serial.println(ruwai_control.rcv_soh_request.msg_id);
620             ruwai_control.rcv_soh_request_changed = false;
621         }
622     }
626 void record_loop(void)
628     bool gps_parsed = false;
629     bool ruwai_parsed = false;
630     bool bbb_serial_free = false;
631     bool wait_for_samples = false;
632     String status_msg;
634     // Enter sleep mode if no adc_data_ready interrupt has occured.
635     if (!adc_data_ready)
636     {
637         //usb_serial.println("sleep");
638         sleep_now();
639         /*
640         usb_serial.print(adc_data_ready);
641         usb_serial.print(";");
642         usb_serial.print(samples_ready);
643         usb_serial.print(";");
644         usb_serial.println(pps_set);
645         */
646     }
648     /***************************************************
649     // Get the data from the ADC.
650     ***************************************************/
651     if (adc_data_ready)
652     {
653         if (samples_ready)
654         {
655             usb_serial.println("race condition sr");
656         }
657         adc.request_data();
658         adc_data_ready = false;
659         wait_for_samples = true;
660         digitalWrite(48, LOW);
661     }
663     /***************************************************
664     // Send the samples to the serial port.
665     ***************************************************/
666     if (wait_for_samples && !samples_ready)
667     {
668         usb_serial.println("samples_ready not set");
669         wait_for_samples = false;
670     }
672     if (samples_ready)
673     {
674         dbg_sample_counter++;
676         if (pps_set && timestamp_set) 
677         {
678             send_samples_with_timestamp();
679             timestamp_set = false;
680             pps_set = false;
681             digitalWrite(46, LOW);
682             digitalWrite(47, LOW);
683             sec_slts++;
684         }
685         // TODO: Handle the situation where the PPS is set, but no timestamp
686         // was issued by the GPS. The PPS of the GPS has to be set to active
687         // also if no GPS-Lock is available. Try to figure out how to get a
688         // valid timestamp within the limits of the GPS-clock drift using
689         // either the GPS time information itself (e.g. internal RTC) or the
690         // RTC of the GPS Timing Shield. It would be great to get the time from
691         // the GPS. This would enable the removal of the RTC components from
692         // the GPS timing shield.
693         else if (pps_set)
694         {
695             send_samples_with_timestamp();
696             pps_set = false;
697             digitalWrite(47, LOW);
698             digitalWrite(47, HIGH);
699             digitalWrite(47, LOW);
700             sec_slts++;
701         }
702         else 
703         {        
704             send_samples();
705         }
706         samples_ready = false;
707         bbb_serial_free = true;
708         /*
709         // Testing the ADC group delay.
710         if (adc.samples[0] >= 0) {
711             PORTB |= _BV(PB7);
712         }
713         else {
714             PORTB &= ~_BV(PB7);
715         }
716         // End testing the ADC group delay.
717         */
718         digitalWrite(49, LOW);
719     }
722     /***************************************************
723     // Check and parse bytes from the GPS.
724     ***************************************************/
725     gps_byte_available = gps_serial.available();
726     if (gps_byte_available > 0)
727     {
728         gps_parsed = gps.read();
729     }
732     /***************************************************
733     // Copy the timestamp from the GPS buffer to the 
734     // timestamp variable.
735     ***************************************************/
736     if (gps.timestamp_init)
737     {
738         if (!gps.timestamp_buf_empty && gps.timestamp_empty)
739         {
740             gps.next_timepulse = gps.next_timepulse_buf;
741             gps.timestamp_buf_empty = true;
742             gps.timestamp_empty = false;
743             timestamp_set = true;
744             digitalWrite(46, HIGH);
745             sec_slts = 0;
746         }
747     }
748     else
749     {
750         //usb_serial.println("Timestamp not init.");
751     }
753     if (gps.timestamp_race_error)
754     {
755         usb_serial.println("ERROR - timestamp race condition.");
756         gps.timestamp_race_error = false;
757     }
762     /***************************************************
763     // React on the updated GPS navigation status.
764     ***************************************************/
765     if (gps.nav_status_changed)
766     {
767         gps.nav_status_changed = false;
768     }
771     /***************************************************
772     // React on the updated GPS UTC time.
773     ***************************************************/
774     if (gps.nav_timeutc_changed)
775     {
776         // Send the timestamp paket using the timestamp marker id.
777         /*
778         rw_smp_utc_time_t msg;
779         msg.id = ts_marker_id - 1;
780         msg.year = gps.timeutc.year;
781         msg.month = gps.timeutc.month;
782         msg.day = gps.timeutc.day;
783         msg.hour = gps.timeutc.hour;
784         msg.min = gps.timeutc.min;
785         msg.sec = gps.timeutc.sec;
786         msg.validutc = gps.timeutc.valid.validutc;
787         msg.gps_fix = gps.get_gps_fix();
788         msg.gps_fix_ok = gps.get_gps_fix_ok();
789         send_ruwai_message(RW_CLASS_SMP, RW_SMP_ID_UTC_TIME, &msg, sizeof(msg));
790         */
791         gps.nav_timeutc_changed = false;
792     }
795     /***************************************************
796     // React on the updated GPS position.
797     ***************************************************/
798     if (gps.nav_position_changed && bbb_serial_free)
799     {
800         //status_msg = "[gps_pos] ";
801         //status_msg = status_msg + gps.nav_position.lon + "," + gps.nav_position.lat + "," + gps.nav_position.height + "," + gps.nav_position.h_msl + "," + gps.nav_position.h_acc + "," + gps.nav_position.v_acc;
802         rw_soh_gpspos_t msg;
803         msg.i_tow = gps.nav_position.i_tow;
804         msg.lon = gps.nav_position.lon;
805         msg.lat = gps.nav_position.lat;
806         msg.height = gps.nav_position.height;
807         ruwai_control.send_message(RW_CLASS_SOH, RW_SOH_ID_GPSPOS, &msg, sizeof(msg));
808         gps.nav_position_changed = false;
809     }
812     /***************************************************
813     // Handle the bytes available at the ruwai control
814     // port.
815     ***************************************************/
816     ruwai_byte_available = RwSerial3.available();
817     if (ruwai_byte_available > 0)
818     {
819         ruwai_parsed = ruwai_control.read();
820     }
822     if (ruwai_parsed)
823     {
824         if (ruwai_control.rcv_ack_sync_changed)
825         {
826             debug_print("sync in record mode");
827             ruwai_control.send_status(RW_STATUS_NOTICE, "Received sync request in record mode.");
828             arduino_reconnect();
829         }
830         /*
831         String msg = "timepulse2 frequency: ";
832         msg.concat(gps.get_timepulse2_frequency());
833         usb_serial.println(msg);
834         msg = "timepulse2 frequency locked: ";
835         msg.concat(gps.get_timepulse2_frequency_locked());
836         usb_serial.println(msg);
837         parsed = false;
838         */
839     }
843 void
844 data_ready_isr()
846     //pin_state_48 = !pin_state_48;
847     if (adc_data_ready)
848     {
849         digitalWrite(48, HIGH);
850         /*
851         usb_serial.println("adr race");
852         usb_serial.print(adc_data_ready);
853         usb_serial.print(";");
854         usb_serial.print(samples_ready);
855         usb_serial.print(";");
856         usb_serial.println(pps_set);
857         */
858     }
859     adc_data_ready = true;
860     // Directly access the LED pin of the mega2560.
861     if (count == 10)
862     {
863         PORTB ^= _BV(PB7);
864         count = 0;
865     }
866     else
867     {
868         count++;
869     }
870     //usb_serial.println("DRDY");
873 void
874 gps_pps_isr()
876     digitalWrite(47, HIGH);
877     pps_set = true;
878     //usb_serial.println("PPS");
882 void
883 send_samples()
885     rw_smp_24bit_t msg;
886     /*
887     msg.samples[0] = (int32_t) test_counter;
888     msg.samples[1] = (int32_t) test_counter;
889     msg.samples[2] = (int32_t) test_counter;
890     msg.samples[3] = (int32_t) test_counter;
891     test_counter++;
892     if(test_counter == 100)
893     {
894         test_counter = 0;
895     }
896     */
897     msg.samples[0] = adc.samples[0];
898     msg.samples[1] = adc.samples[1];
899     msg.samples[2] = adc.samples[2];
900     msg.samples[3] = adc.samples[3];
902     ruwai_control.send_message(RW_CLASS_SMP, RW_SMP_ID_24BIT, &msg, sizeof(msg));
905 void
906 send_samples_with_timestamp()
908     rw_smp_24bit_tsp_t msg;
909     msg.week = gps.next_timepulse.week;
910     msg.tow_ms = gps.next_timepulse.tow_ms;
911     msg.tow_sub_ms = gps.next_timepulse.tow_sub_ms;
912     msg.sec_slts = sec_slts;
913     msg.flags.utc = gps.next_timepulse.flags.utc;
914     msg.flags.timebase = gps.next_timepulse.flags.time_base;
915     msg.flags.gps_fix = gps.get_gps_fix();
916     msg.flags.gps_fix_ok = gps.get_gps_fix_ok();
917     msg.samples[0] = adc.samples[0];
918     msg.samples[1] = adc.samples[1];
919     msg.samples[2] = adc.samples[2];
920     msg.samples[3] = adc.samples[3];
921     ruwai_control.send_message(RW_CLASS_SMP, RW_SMP_ID_24BIT_TSP, &msg, sizeof(msg));
922     gps.timestamp_empty = true;
924     dbg_sample_counter = 0;
931 // The timer1 interrupt service routine.
933 ISR(TIMER1_OVF_vect)
935     debug_print();
936     debug_print("Polling GPS:");
937     //gps.poll_cfg_prt_uart();
938     //gps.poll_cfg_msg(NMEA_CLASS_STD, NMEA_STD_ID_GGA);
939     gps.poll_cfg_tp5(TIMEPULSE2);
943 // The timer1 interrupt service routine.
945 ISR(TIMER1_OVF_vect)
947     // Toggle the LED pin.
948     // Use Arduino macros to get the correct port register.
949     uint8_t port = digitalPinToPort(led);
950     uint8_t bitmask = digitalPinToBitMask(led);
951     volatile uint8_t *out;
953     out = portOutputRegister(port);
954     *out ^= bitmask;
956     count++;
958     // Directly access the LED pin of the mega2560.
959     //PORTB ^= _BV(PB7);