1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
//
// Copyright (C) 2018 Kubos Corporation
//
// Licensed under the Apache License, Version 2.0 (the "License")
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
//

use failure::Error;
use kubos_service::{process_errors, push_err, run};
use log::{error, info};
use novatel_oem6_api::Log::*;
use novatel_oem6_api::*;
use std::sync::mpsc::{sync_channel, Receiver, SyncSender, TryRecvError, TrySendError};
use std::sync::{Arc, Mutex, RwLock};
use std::thread;
use std::time::Duration;

use crate::objects::*;

pub const RECV_TIMEOUT: Duration = Duration::from_millis(350);

pub struct LockData {
    pub status: Mutex<LockStatus>,
    pub info: Mutex<LockInfo>,
}

impl LockData {
    pub fn new() -> Self {
        LockData {
            status: Mutex::new(LockStatus::default()),
            info: Mutex::new(LockInfo::default()),
        }
    }

    pub fn update_status(&self, status: LockStatus) {
        let mut local = self.status.lock().unwrap();
        *local = status;
    }

    pub fn update_info(&self, info: LockInfo) {
        let mut local = self.info.lock().unwrap();
        *local = info;
    }
}

// Listen for log messages from the OEM6 and route data to the appropriate
// listener or structure.
//
// The OEM6 will send us one of three log messages:
// - Lock information. The OEM6 will likely be set up to output this data
//   once per second.
// - Version information. This data will be output immediately upon request by
//   the `noop` and `get_test_results` functions
// - Error information. If enabled, this will be output by the OEM6 when an
//   error or event occurs.
pub fn log_thread(
    oem: &OEM6,
    data: &Arc<LockData>,
    error_send: &SyncSender<RxStatusEventLog>,
    version_send: &SyncSender<VersionLog>,
) {
    loop {
        match oem.get_log().unwrap_or_else(|err| {
            error!("get_log failed: {:?}. Log read thread bailing", err);
            panic!("Underlying read thread no longer communicating")
        }) {
            BestXYZ(log) => {
                if log.pos_status == 0 && log.vel_status == 0 {
                    data.update_info(LockInfo {
                        time: OEMTime {
                            week: i32::from(log.week),
                            ms: log.ms,
                        },
                        position: log.position,
                        velocity: log.velocity,
                    });
                }
                data.update_status(LockStatus {
                    time_status: log.time_status,
                    time: OEMTime {
                        week: i32::from(log.week),
                        ms: log.ms,
                    },
                    position_status: log.pos_status,
                    position_type: log.pos_type,
                    velocity_status: log.vel_status,
                    velocity_type: log.vel_type,
                });
            }
            RxStatusEvent(log) => error_send
                .try_send(log)
                .or_else::<TrySendError<RxStatusEventLog>, _>(|err| match err {
                    // Our buffer is full, but the receiver should still be alive, so let's keep going
                    TrySendError::Full(_) => Ok(()),
                    TrySendError::Disconnected(_) => {
                        let msg =
                            "Error receiver disconnected. Assuming system has become corrupted";
                        error!("{}", msg);
                        panic!("{}", msg);
                    }
                })
                .unwrap(),
            Version(log) => version_send
                .try_send(log)
                .or_else::<TrySendError<VersionLog>, _>(|err| match err {
                    // Our buffer is full, but the receiver should still be alive, so let's keep going
                    TrySendError::Full(_) => Ok(()),
                    TrySendError::Disconnected(_) => {
                        let msg =
                            "Version receiver disconnected. Assuming system has become corrupted";
                        error!("{}", msg);
                        panic!("{}", msg)
                    }
                })
                .unwrap(),
        }
    }
}

#[derive(Clone)]
pub struct Subsystem {
    pub oem: OEM6,
    pub last_cmd: Arc<RwLock<AckCommand>>,
    pub errors: Arc<RwLock<Vec<String>>>,
    pub lock_data: Arc<LockData>,
    pub error_recv: Arc<Mutex<Receiver<RxStatusEventLog>>>,
    pub version_recv: Arc<Mutex<Receiver<VersionLog>>>,
}

impl Subsystem {
    pub fn new(bus: &str, data: Arc<LockData>) -> OEMResult<Subsystem> {
        let (log_send, log_recv) = sync_channel(5);
        let (response_send, response_recv) = sync_channel(5);
        let (response_abbrv_send, response_abbrv_recv) = sync_channel(5);

        let oem = OEM6::new(
            bus,
            BaudRate::Baud9600,
            log_recv,
            response_recv,
            response_abbrv_recv,
        )?;

        let rx_conn = oem.conn.clone();
        thread::spawn(move || {
            read_thread(&rx_conn, &log_send, &response_send, &response_abbrv_send)
        });

        let (error_send, error_recv) = sync_channel(10);
        let (version_send, version_recv) = sync_channel(1);

        let data_ref = data.clone();
        let oem_ref = oem.clone();
        thread::spawn(move || log_thread(&oem_ref, &data_ref, &error_send, &version_send));

        info!("Kubos OEM6 service started");

        Ok(Subsystem {
            oem,
            last_cmd: Arc::new(RwLock::new(AckCommand::None)),
            errors: Arc::new(RwLock::new(vec![])),
            lock_data: data,
            error_recv: Arc::new(Mutex::new(error_recv)),
            version_recv: Arc::new(Mutex::new(version_recv)),
        })
    }

    fn get_version_log(&self) -> Result<VersionLog, String> {
        let result = match self.oem.request_version() {
            Ok(_) => match self
                .version_recv
                .lock()
                .map_err(|err| format!("Failed to obtain version_recv mutex: {:?}", err))?
                .recv_timeout(RECV_TIMEOUT)
            {
                Ok(log) => Ok(log),
                Err(err) => Err(format!("Failed to receive version info - {}", err)),
            },
            Err(err) => Err(process_errors!(err)),
        };

        if result.is_err() {
            error!("{:?}", result);
        }

        result
    }

    // Queries

    pub fn get_errors(&self) {
        if let Ok(recv) = self.error_recv.lock() {
            match recv.try_recv() {
                Ok(msg) => {
                    push_err!(
                        self.errors,
                        format!(
                            "RxStatusEvent({}, {}, {}): {}",
                            msg.word, msg.bit, msg.event, msg.description
                        )
                    );

                    while let Ok(err) = recv.try_recv() {
                        push_err!(
                            self.errors,
                            format!(
                                "RxStatusEvent({}, {}, {}): {}",
                                err.word, err.bit, err.event, err.description
                            )
                        );
                    }
                }
                Err(err) => match err {
                    // Do nothing. This is the good case
                    TryRecvError::Empty => {}
                    // We've lost connection with the errors channel
                    TryRecvError::Disconnected => {
                        push_err!(self.errors, "Errors sender disconnected".to_owned());
                    }
                },
            }
        } else {
            push_err!(self.errors, "Failed to obtain error_recv mutex".to_owned());
        }
    }

    pub fn get_power(&self) -> Result<GetPowerResponse, Error> {
        let (state, uptime) = if self.get_version_log().is_ok() {
            (PowerState::On, 1)
        } else {
            (PowerState::Off, 0)
        };

        Ok(GetPowerResponse { state, uptime })
    }

    pub fn get_system_status(&self) -> Result<SystemStatus, Error> {
        self.get_errors();

        let mut errors = match self.errors.read() {
            Ok(master_vec) => master_vec.clone(),
            _ => {
                error!("get_system_status - Failed to borrow master errors vector");
                vec!["Error: Failed to borrow master errors vector".to_owned()]
            }
        };

        let status = match self.get_version_log() {
            Ok(log) => log.recv_status,
            Err(err) => {
                errors.push(format!("System Status: {}", err));
                /* My first thought was to use ReceiverStatusFlags::empty(),
                 * but I'm worried that that is easily mistaken for this function
                 * actually having succeeded
                 */
                ReceiverStatusFlags::all()
            }
        };

        Ok(SystemStatus {
            status: ReceiverStatus(status),
            errors,
        })
    }

    pub fn get_lock_status(&self) -> Result<LockStatus, Error> {
        Ok(self.lock_data.status.lock().unwrap().clone())
    }

    pub fn get_lock_info(&self) -> Result<LockInfo, Error> {
        Ok(self.lock_data.info.lock().unwrap().clone())
    }

    pub fn get_test_results(&self) -> Result<IntegrationTestResults, Error> {
        let telem = self.get_telemetry()?;

        Ok(IntegrationTestResults {
            success: telem.debug.is_some(),
            errors: telem.nominal.system_status.errors.join("; "),
            telemetry_debug: telem.debug.clone(),
            telemetry_nominal: telem.nominal,
        })
    }

    pub fn get_telemetry(&self) -> Result<Telemetry, Error> {
        self.get_errors();

        let mut errors = match self.errors.read() {
            Ok(master_vec) => master_vec.clone(),
            _ => {
                error!("get_telemetry - Failed to borrow master errors vector");
                vec!["Error: Failed to borrow master errors vector".to_owned()]
            }
        };

        let (status, version_info) = match self.get_version_log() {
            Ok(log) => (
                log.recv_status,
                Some(VersionInfo {
                    num_components: log.num_components as i32,
                    components: log
                        .components
                        .iter()
                        .map(|comp| VersionComponent(comp.clone()))
                        .collect(),
                }),
            ),
            Err(err) => {
                let temp = format!("Get Telemetry: {}", err);
                errors.push(temp.clone());
                push_err!(self.errors, temp);
                (ReceiverStatusFlags::all(), None)
            }
        };

        let lock_status = self.get_lock_status().ok();
        let lock_info = self.get_lock_info().ok();

        Ok(Telemetry {
            nominal: TelemetryNominal {
                system_status: SystemStatus {
                    status: ReceiverStatus(status),
                    errors,
                },
                lock_status,
                lock_info,
            },
            debug: version_info,
        })
    }

    // Mutations

    pub fn noop(&self) -> Result<GenericResponse, Error> {
        let result = self.get_version_log();

        let success = result.is_ok();

        let errors = match result {
            Ok(_) => "".to_owned(),
            Err(err) => {
                let temp = format!("Noop: {}", err);
                push_err!(self.errors, temp);
                err
            }
        };

        Ok(GenericResponse { success, errors })
    }

    pub fn configure_hardware(
        &self,
        input: Vec<ConfigStruct>,
    ) -> Result<ConfigureHardwareResponse, Error> {
        let mut success = true;
        let mut errors = "".to_owned();
        let mut config = "".to_owned();

        for entry in input.iter() {
            let result = run!(
                match entry.option {
                    ConfigOption::LogErrorData => self.oem.request_errors(entry.hold),
                    ConfigOption::LogPositionData => {
                        self.oem
                            .request_position(entry.interval, entry.offset, entry.hold)
                    }
                    ConfigOption::UnlogAll => self.oem.request_unlog_all(entry.hold),
                    ConfigOption::UnlogErrorData => {
                        self.oem.request_unlog(MessageID::RxStatusEvent)
                    }
                    ConfigOption::UnlogPositionData => self.oem.request_unlog(MessageID::BestXYZ),
                },
                self.errors
            );

            success &= result.is_ok();
            if let Err(err) = result {
                if !errors.is_empty() {
                    errors.push_str(". ");
                }
                errors.push_str(&format!("{:?}: {}", entry.option, err));
            }

            if !config.is_empty() {
                config.push_str(", ");
            }
            config.push_str(&format!("{:?}(Hold: {})", entry.option, entry.hold));
            if entry.interval != 0.0 {
                config.push_str(&format!(": {}+{}sec", entry.interval, entry.offset));
            }
        }

        Ok(ConfigureHardwareResponse {
            success,
            errors,
            config,
        })
    }

    pub fn passthrough(&self, command: String) -> Result<GenericResponse, Error> {
        // Convert the hex values in the string into actual hex values
        // Ex. "c3c2" -> [0xc3, 0xc2]
        let tx: Vec<u8> = command
            .as_bytes()
            .chunks(2)
            .map(|chunk| u8::from_str_radix(::std::str::from_utf8(chunk).unwrap(), 16).unwrap())
            .collect();

        let result = run!(self.oem.passthrough(tx.as_slice()), self.errors);

        Ok(GenericResponse {
            success: result.is_ok(),
            errors: match result {
                Ok(_) => "".to_owned(),
                Err(err) => err,
            },
        })
    }
}