Compare commits
14 commits
Author | SHA1 | Date | |
---|---|---|---|
97de5e451e | |||
dc1615d21f | |||
059263d7ea | |||
d71a7bb2a9 | |||
c9e80434fe | |||
5e6810cae8 | |||
7a22f14e1f | |||
9d536bdce9 | |||
09402bbf83 | |||
10c1018e07 | |||
47b333d354 | |||
ff779d0dc3 | |||
576bcfc590 | |||
e7c51f2b61 |
11 changed files with 341 additions and 319 deletions
1
.gitignore
vendored
1
.gitignore
vendored
|
@ -2,3 +2,4 @@
|
||||||
/.embuild
|
/.embuild
|
||||||
/target
|
/target
|
||||||
/Cargo.lock
|
/Cargo.lock
|
||||||
|
/secret
|
||||||
|
|
|
@ -19,7 +19,9 @@ esp-idf-hal = "0.37.4"
|
||||||
esp-idf-sys = { version = "0.31.5", features = ["binstart", "native"] }
|
esp-idf-sys = { version = "0.31.5", features = ["binstart", "native"] }
|
||||||
mqtt-protocol = "0.11.2"
|
mqtt-protocol = "0.11.2"
|
||||||
nb = "1.0.0"
|
nb = "1.0.0"
|
||||||
ublox = "0.4.2"
|
nmea0183 = "0.3.0"
|
||||||
|
serde-json-core = "0.5.0"
|
||||||
|
serde = "*"
|
||||||
|
|
||||||
[build-dependencies]
|
[build-dependencies]
|
||||||
embuild = "0.29"
|
embuild = "0.29"
|
||||||
|
|
|
@ -1,2 +1,2 @@
|
||||||
[toolchain]
|
[toolchain]
|
||||||
channel = "esp"
|
channel = "esp-1.69.0.0"
|
||||||
|
|
|
@ -1,5 +1,5 @@
|
||||||
# Rust often needs a bit of an extra main task stack size compared to C (the default is 3K)
|
# Rust often needs a bit of an extra main task stack size compared to C (the default is 3K)
|
||||||
CONFIG_ESP_MAIN_TASK_STACK_SIZE=64000
|
CONFIG_ESP_MAIN_TASK_STACK_SIZE=128000
|
||||||
|
|
||||||
# Use this to set FreeRTOS kernel tick frequency to 1000 Hz (100 Hz by default).
|
# Use this to set FreeRTOS kernel tick frequency to 1000 Hz (100 Hz by default).
|
||||||
# This allows to use 1 ms granuality for thread sleeps (10 ms by default).
|
# This allows to use 1 ms granuality for thread sleeps (10 ms by default).
|
||||||
|
|
0
secret/.keep
Normal file
0
secret/.keep
Normal file
|
@ -12,7 +12,7 @@ impl Command {
|
||||||
Command {
|
Command {
|
||||||
text: "ATI".to_string(),
|
text: "ATI".to_string(),
|
||||||
timeout: Duration::from_millis(6000),
|
timeout: Duration::from_millis(6000),
|
||||||
contains: Some("+CIEV".to_string()),
|
contains: Some("OK".to_string()),
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -236,7 +236,7 @@ impl Command {
|
||||||
Command {
|
Command {
|
||||||
text: "AT".to_string(),
|
text: "AT".to_string(),
|
||||||
timeout: Duration::from_millis(3000),
|
timeout: Duration::from_millis(3000),
|
||||||
contains: Some("+CIEV".to_string()),
|
contains: Some("OK".to_string()),
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1,11 +1,19 @@
|
||||||
|
#![allow(dead_code)]
|
||||||
|
|
||||||
pub struct GprsAp<'a> {
|
pub struct GprsAp<'a> {
|
||||||
pub apn: &'a str,
|
pub apn: &'a str,
|
||||||
pub username: &'a str,
|
pub username: &'a str,
|
||||||
pub password: &'a str,
|
pub password: &'a str,
|
||||||
}
|
}
|
||||||
|
|
||||||
pub const A1_GPRS_AP: GprsAp = GprsAp {
|
pub const A1: GprsAp = GprsAp {
|
||||||
apn: "internet",
|
apn: "internet",
|
||||||
username: "internet",
|
username: "internet",
|
||||||
password: "internet",
|
password: "internet",
|
||||||
};
|
};
|
||||||
|
|
||||||
|
pub const MTS: GprsAp = GprsAp {
|
||||||
|
apn: "gprswap",
|
||||||
|
username: "mts",
|
||||||
|
password: "064",
|
||||||
|
};
|
||||||
|
|
195
src/gps.rs
195
src/gps.rs
|
@ -3,96 +3,41 @@ use anyhow;
|
||||||
use std::{
|
use std::{
|
||||||
sync::mpsc::SyncSender,
|
sync::mpsc::SyncSender,
|
||||||
thread,
|
thread,
|
||||||
time::{Duration, Instant},
|
time::Duration,
|
||||||
io::{Read, Write},
|
io::Read,
|
||||||
};
|
};
|
||||||
|
|
||||||
use esp_idf_hal::prelude::*;
|
use esp_idf_hal::prelude::*;
|
||||||
use esp_idf_hal::serial::{self, Rx, Tx};
|
use esp_idf_hal::serial::{self, Rx, Tx};
|
||||||
|
|
||||||
use ublox::*;
|
use nmea0183::{Parser, ParseResult, Sentence, Source};
|
||||||
|
|
||||||
use crate::types::*;
|
use crate::types::Msg;
|
||||||
use crate::serial::SerialIO;
|
use crate::serial::SerialIO;
|
||||||
|
|
||||||
struct GpsModule<UART: serial::Uart> {
|
struct GpsModule<UART: serial::Uart> {
|
||||||
port: SerialIO<UART>,
|
port: SerialIO<UART>,
|
||||||
parser: Parser<Vec<u8>>,
|
|
||||||
}
|
}
|
||||||
|
|
||||||
impl<UART: serial::Uart> GpsModule<UART> {
|
impl<UART: serial::Uart> GpsModule<UART> {
|
||||||
pub fn new(tx: Tx<UART>, rx: Rx<UART>) -> Self {
|
pub fn new(tx: Tx<UART>, rx: Rx<UART>) -> Self {
|
||||||
let parser = Parser::default();
|
GpsModule {
|
||||||
GpsModule { port: SerialIO::new(tx, rx), parser }
|
port: SerialIO::new(tx, rx),
|
||||||
}
|
|
||||||
|
|
||||||
pub fn write_all(&mut self, data: &[u8]) -> std::io::Result<()> {
|
|
||||||
println!("WRITE: {:?}", data);
|
|
||||||
self.port.write(data).map(|_| ())
|
|
||||||
}
|
|
||||||
|
|
||||||
pub fn update<T: FnMut(PacketRef)>(&mut self, mut cb: T) -> std::io::Result<()> {
|
|
||||||
println!("UPDATING ... ... ...");
|
|
||||||
loop {
|
|
||||||
let mut local_buf = [0; 1024];
|
|
||||||
let nbytes = self.read_port(&mut local_buf)?;
|
|
||||||
if nbytes == 0 {
|
|
||||||
println!("no bytes to read :(");
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
// parser.consume adds the buffer to its internal buffer, and
|
|
||||||
// returns an iterator-like object we can use to process the packets
|
|
||||||
let mut it = self.parser.consume(&local_buf[..nbytes]);
|
|
||||||
while let Some(Ok(packet)) = it.next() {
|
|
||||||
println!("READ: {:?}", packet);
|
|
||||||
cb(packet);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
Ok(())
|
|
||||||
}
|
|
||||||
|
|
||||||
pub fn wait_for_ack<T: UbxPacketMeta>(&mut self, timeout: Duration) -> std::io::Result<bool> {
|
|
||||||
let mut found_packet = false;
|
|
||||||
println!("LOOKING FOR ACK ...");
|
|
||||||
let start = Instant::now();
|
|
||||||
while !found_packet && start.elapsed() < timeout {
|
|
||||||
self.update(|packet| {
|
|
||||||
if let PacketRef::AckAck(ack) = packet {
|
|
||||||
if ack.class() == T::CLASS && ack.msg_id() == T::ID {
|
|
||||||
println!("FOUND PACKET: {} {}", ack.class(), ack.msg_id());
|
|
||||||
found_packet = true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else if let PacketRef::AckNak(nak) = packet {
|
|
||||||
println!("NAK PACKET: {} {}", nak.class(), nak.msg_id());
|
|
||||||
}
|
|
||||||
})?;
|
|
||||||
}
|
|
||||||
println!("exiting wait_for_ack");
|
|
||||||
Ok(found_packet)
|
|
||||||
}
|
|
||||||
|
|
||||||
/// Reads the serial port, converting timeouts into "no data received"
|
|
||||||
fn read_port(&mut self, output: &mut [u8]) -> std::io::Result<usize> {
|
|
||||||
match self.port.read(output) {
|
|
||||||
Ok(b) => Ok(b),
|
|
||||||
Err(e) => {
|
|
||||||
if e.kind() == std::io::ErrorKind::TimedOut {
|
|
||||||
Ok(0)
|
|
||||||
} else {
|
|
||||||
Err(e)
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
pub fn main<T: Sync + Send>(
|
pub fn main<PRx,PTx>
|
||||||
tx: esp_idf_hal::gpio::Gpio12<T>,
|
(
|
||||||
rx: esp_idf_hal::gpio::Gpio13<T>,
|
tx: PTx,
|
||||||
|
rx: PRx,
|
||||||
uart: serial::UART2,
|
uart: serial::UART2,
|
||||||
sender: SyncSender<Msg>,
|
sender: SyncSender<Msg>,
|
||||||
) -> Result<(), anyhow::Error> {
|
) -> std::result::Result<(), anyhow::Error>
|
||||||
|
where
|
||||||
|
PRx: esp_idf_hal::gpio::Pin + esp_idf_hal::gpio::InputPin + esp_idf_hal::gpio::OutputPin,
|
||||||
|
PTx: esp_idf_hal::gpio::Pin + esp_idf_hal::gpio::InputPin + esp_idf_hal::gpio::OutputPin,
|
||||||
|
{
|
||||||
let serial_pins = serial::Pins {
|
let serial_pins = serial::Pins {
|
||||||
tx,
|
tx,
|
||||||
rx,
|
rx,
|
||||||
|
@ -100,100 +45,46 @@ pub fn main<T: Sync + Send>(
|
||||||
rts: None,
|
rts: None,
|
||||||
};
|
};
|
||||||
|
|
||||||
let serial_config = serial::config::Config::default()
|
|
||||||
.baudrate(Hertz(9600))
|
|
||||||
.data_bits(serial::config::DataBits::DataBits8)
|
|
||||||
.parity_none()
|
|
||||||
.flow_control(serial::config::FlowControl::None)
|
|
||||||
.stop_bits(serial::config::StopBits::STOP1);
|
|
||||||
|
|
||||||
let serial: serial::Serial<serial::UART2, _, _> = serial::Serial::new(
|
let serial: serial::Serial<serial::UART2, _, _> = serial::Serial::new(
|
||||||
uart,
|
uart,
|
||||||
serial_pins,
|
serial_pins,
|
||||||
serial_config,
|
serial::config::Config::default().baudrate(Hertz(9600)),
|
||||||
)?;
|
)?;
|
||||||
|
|
||||||
let (tx, rx) = serial.split();
|
let (tx, rx) = serial.split();
|
||||||
let mut device = GpsModule::new(tx, rx);
|
let mut device = GpsModule::new(tx, rx);
|
||||||
|
|
||||||
// Configure the device to talk UBX
|
let mut parser = Parser::new()
|
||||||
device
|
.source_only(Source::GPS)
|
||||||
.write_all(
|
.sentence_filter(Sentence::GLL | Sentence::GGA);
|
||||||
&CfgPrtUartBuilder {
|
|
||||||
portid: UartPortId::Uart1,
|
|
||||||
reserved0: 0,
|
|
||||||
tx_ready: 0,
|
|
||||||
mode: UartMode::new(DataBits::Eight, Parity::None, StopBits::One),
|
|
||||||
baud_rate: 9600,
|
|
||||||
in_proto_mask: InProtoMask::all(),
|
|
||||||
out_proto_mask: OutProtoMask::UBOX,
|
|
||||||
flags: 0,
|
|
||||||
reserved5: 0,
|
|
||||||
}
|
|
||||||
.into_packet_bytes(),
|
|
||||||
)?;
|
|
||||||
device.wait_for_ack::<CfgPrtUart>(Duration::from_millis(3000)).unwrap();
|
|
||||||
println!("CfgPrtUart acked!");
|
|
||||||
|
|
||||||
// Set interval for the NavPosVelTime packet
|
let mut c = 0;
|
||||||
println!("Sending set_rate_for::<NavPosVelTime> ...");
|
let mut nmea = [0_u8; 1024];
|
||||||
for i in 1..5 {
|
loop {
|
||||||
device
|
if let Ok(_) = device.port.read(nmea.as_mut_slice()) {
|
||||||
.write_all(
|
println!("\r\n\r\n\r\n\r\n");
|
||||||
&CfgMsgAllPortsBuilder::set_rate_for::<NavPosVelTime>([0, 1, 1, 0, 0, 0])
|
for result in parser.parse_from_bytes(&nmea[..]) {
|
||||||
.into_packet_bytes(),
|
match result {
|
||||||
)
|
Ok(ParseResult::GLL(Some(gll))) => {
|
||||||
.unwrap();
|
sender.send(Msg::Gps(gll.into()))?;
|
||||||
println!("SENT set_rate_for::<NavPosVelTime>({}) !!!", i);
|
},
|
||||||
if let Ok(true) = device.wait_for_ack::<CfgMsgSinglePort>(Duration::from_millis(3000)) {
|
Ok(ParseResult::GGA(Some(gga))) => {
|
||||||
println!("Setting rate for NavPosVelTime acked! Exiting loop ...");
|
sender.send(Msg::Gps(gga.into()))?;
|
||||||
break
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Send a packet request for the MonVer packet
|
|
||||||
//device
|
|
||||||
// .write_all(&UbxPacketRequest::request_for::<MonVer>().into_packet_bytes())
|
|
||||||
// .unwrap();
|
|
||||||
|
|
||||||
// Start reading data
|
|
||||||
println!("Opened u-blox device, waiting for solutions...");
|
|
||||||
for _ in 0..20 {
|
|
||||||
device
|
|
||||||
.update(|packet| match packet {
|
|
||||||
PacketRef::MonVer(packet) => {
|
|
||||||
println!(
|
|
||||||
"SW version: {} HW version: {}",
|
|
||||||
packet.software_version(),
|
|
||||||
packet.hardware_version()
|
|
||||||
);
|
|
||||||
println!("{:?}", packet);
|
|
||||||
}
|
|
||||||
PacketRef::NavPosVelTime(sol) => {
|
|
||||||
let has_posvel = sol.fix_type() == GpsFix::Fix3D
|
|
||||||
|| sol.fix_type() == GpsFix::GPSPlusDeadReckoning;
|
|
||||||
|
|
||||||
if has_posvel {
|
|
||||||
let pos: Position = (&sol).into();
|
|
||||||
let vel: Velocity = (&sol).into();
|
|
||||||
let solution = Solution {
|
|
||||||
latitude: pos.lat,
|
|
||||||
longitude: pos.lon,
|
|
||||||
altitude: pos.alt,
|
|
||||||
speed: vel.speed,
|
|
||||||
direction: vel.heading,
|
|
||||||
};
|
|
||||||
println!("Sol: {:?}", solution);
|
|
||||||
sender.send(Msg::Gps(solution));
|
|
||||||
}
|
}
|
||||||
|
_ => { }
|
||||||
}
|
}
|
||||||
_ => {
|
}
|
||||||
println!("{:?}", packet);
|
c = 0;
|
||||||
}
|
} else {
|
||||||
})?;
|
println!("nothing to read after {} tries ...", c);
|
||||||
thread::sleep(Duration::from_millis(1000));
|
if c > 100 {
|
||||||
|
println!("reached {} retries ... bailing!", c);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
thread::sleep(Duration::from_millis(5000));
|
||||||
|
c += 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
println!("exiting GPS sender loop :)");
|
|
||||||
Ok(())
|
Ok(())
|
||||||
}
|
}
|
||||||
|
|
66
src/main.rs
66
src/main.rs
|
@ -5,10 +5,15 @@ mod command;
|
||||||
mod modem;
|
mod modem;
|
||||||
mod serial;
|
mod serial;
|
||||||
mod types;
|
mod types;
|
||||||
|
mod gps;
|
||||||
|
|
||||||
use anyhow;
|
use anyhow;
|
||||||
use std::{thread::{self, JoinHandle}, time::Duration};
|
use std::{thread::{self, JoinHandle}, time::Duration};
|
||||||
use esp_idf_hal::peripherals::Peripherals;
|
use esp_idf_hal::peripherals::Peripherals;
|
||||||
|
use esp_idf_hal::prelude::*;
|
||||||
|
use esp_idf_hal::serial::{Pins, config::Config, Serial, UART1, Uart};
|
||||||
|
use embedded_hal::digital::v2::OutputPin;
|
||||||
|
|
||||||
use types::*;
|
use types::*;
|
||||||
|
|
||||||
fn main() -> anyhow::Result<()> {
|
fn main() -> anyhow::Result<()> {
|
||||||
|
@ -18,6 +23,25 @@ fn main() -> anyhow::Result<()> {
|
||||||
|
|
||||||
println!("Rust main thread: {:?}", thread::current());
|
println!("Rust main thread: {:?}", thread::current());
|
||||||
|
|
||||||
|
let mut threads: Vec<JoinHandle<anyhow::Result<_>>> = vec![];
|
||||||
|
|
||||||
|
// // Rx/Tx pins for the GPS modem
|
||||||
|
let gps_rx = dp.pins.gpio32;
|
||||||
|
let gps_tx = dp.pins.gpio33;
|
||||||
|
// // UART interface for the GPS modem
|
||||||
|
let gps_uart = dp.uart2;
|
||||||
|
|
||||||
|
|
||||||
|
let (gps_sender, receiver) = std::sync::mpsc::sync_channel::<Msg>(3);
|
||||||
|
//let accel_sender = gps_sender.clone();
|
||||||
|
|
||||||
|
//let _ = gps::main(gps_tx, gps_rx, gps_uart, gps_sender)?;
|
||||||
|
//threads.push(thread::spawn(move || accel::main(accel_sender)));
|
||||||
|
|
||||||
|
// ==================================
|
||||||
|
// MODEM INITIALIZATION AND MAIN LOOP
|
||||||
|
// ==================================
|
||||||
|
|
||||||
// LilyGo TTGO T-Call sim800l board serial pins.
|
// LilyGo TTGO T-Call sim800l board serial pins.
|
||||||
let modem_rx = dp.pins.gpio26;
|
let modem_rx = dp.pins.gpio26;
|
||||||
let modem_tx = dp.pins.gpio27;
|
let modem_tx = dp.pins.gpio27;
|
||||||
|
@ -28,24 +52,38 @@ fn main() -> anyhow::Result<()> {
|
||||||
// UART interface for the GSM modem
|
// UART interface for the GSM modem
|
||||||
let modem_uart = dp.uart1;
|
let modem_uart = dp.uart1;
|
||||||
|
|
||||||
let mut threads: Vec<JoinHandle<anyhow::Result<_>>> = vec![];
|
let serial_pins = Pins {
|
||||||
|
tx: modem_tx,
|
||||||
|
rx: modem_rx,
|
||||||
|
cts: None,
|
||||||
|
rts: None,
|
||||||
|
};
|
||||||
|
|
||||||
// // Rx/Tx pins for the GPS modem
|
let serial: Serial<UART1, _, _> = Serial::new(
|
||||||
// let gps_rx = dp.pins.gpio13;
|
modem_uart,
|
||||||
// let gps_tx = dp.pins.gpio12;
|
serial_pins,
|
||||||
// // UART interface for the GPS modem
|
Config::default().baudrate(Hertz(115200)),
|
||||||
// let gps_uart = dp.uart2;
|
)?;
|
||||||
|
|
||||||
|
let (tx, rx) = serial.split();
|
||||||
|
type PwrkeyOutput = esp_idf_hal::gpio::Gpio4<esp_idf_hal::gpio::Output>;
|
||||||
|
type ResetOutput = esp_idf_hal::gpio::Gpio5<esp_idf_hal::gpio::Output>;
|
||||||
|
type PowerOutput = esp_idf_hal::gpio::Gpio23<esp_idf_hal::gpio::Output>;
|
||||||
|
|
||||||
let (gps_sender, receiver) = std::sync::mpsc::sync_channel::<Msg>(1);
|
let mut mdm: modem::Modem<UART1, PwrkeyOutput, ResetOutput, PowerOutput> = modem::Modem::new(tx, rx, modem_pwrkey, modem_rst, modem_power, receiver);
|
||||||
let accel_sender = gps_sender.clone();
|
|
||||||
|
|
||||||
// let _ = gps::main(gps_tx, gps_rx, gps_uart, gps_sender)?;
|
let mqtt_username = include_str!("../secret/username").trim();
|
||||||
// threads.push(thread::spawn(move || gps::main(gps_rx, gps_tx, gps_uart, gps_sender)));
|
let mqtt_password = include_str!("../secret/password").trim();
|
||||||
thread::sleep(Duration::from_millis(1000));
|
|
||||||
threads.push(thread::spawn(move || accel::main(accel_sender)));
|
|
||||||
|
|
||||||
let _ = modem::main(modem_rx, modem_tx, modem_uart, modem_pwrkey, modem_rst, modem_power, receiver)?;
|
threads.push(thread::spawn(move || gps::main(gps_tx, gps_rx, gps_uart, gps_sender.clone())));
|
||||||
|
|
||||||
Ok(())
|
println!("======================= MAIN =======================");
|
||||||
|
mdm.init().unwrap_or(());
|
||||||
|
let _ = mdm.echo(false).unwrap_or(());
|
||||||
|
println!("resetting modem ... ");
|
||||||
|
println!("======================= MODEM =======================");
|
||||||
|
let _ = mdm.mqtt_send_position_loop("51.158.66.64", 7887, mqtt_username, mqtt_password).unwrap_or(());
|
||||||
|
let _ = mdm.tcp_close_connection().unwrap_or(());
|
||||||
|
thread::sleep(Duration::from_millis(1500));
|
||||||
|
panic!("rebooting");
|
||||||
}
|
}
|
||||||
|
|
270
src/modem.rs
270
src/modem.rs
|
@ -1,3 +1,5 @@
|
||||||
|
#![allow(dead_code)]
|
||||||
|
|
||||||
use crate::command::Command;
|
use crate::command::Command;
|
||||||
use crate::serial::SerialIO;
|
use crate::serial::SerialIO;
|
||||||
use crate::types::*;
|
use crate::types::*;
|
||||||
|
@ -11,20 +13,25 @@ use std::{
|
||||||
sync::mpsc::Receiver,
|
sync::mpsc::Receiver,
|
||||||
};
|
};
|
||||||
|
|
||||||
use esp_idf_hal::prelude::*;
|
|
||||||
use esp_idf_hal::serial::{self, Rx, Tx};
|
use esp_idf_hal::serial::{self, Rx, Tx};
|
||||||
|
|
||||||
use embedded_hal::digital::v2::OutputPin;
|
use embedded_hal::digital::v2::OutputPin;
|
||||||
|
|
||||||
use mqtt::packet::{ConnectPacket, PublishPacket, QoSWithPacketIdentifier, VariablePacket};
|
use mqtt::{
|
||||||
use mqtt::{Encodable, Decodable, TopicName};
|
Encodable,
|
||||||
|
Decodable,
|
||||||
|
TopicName,
|
||||||
|
packet::{
|
||||||
|
ConnectPacket,
|
||||||
|
PublishPacket,
|
||||||
|
QoSWithPacketIdentifier,
|
||||||
|
VariablePacket,
|
||||||
|
},
|
||||||
|
};
|
||||||
|
use serde_json_core;
|
||||||
|
|
||||||
pub type Result<T> = std::result::Result<T, ModemError>;
|
pub type Result<T> = std::result::Result<T, ModemError>;
|
||||||
|
|
||||||
pub struct Modem<UART: serial::Uart> {
|
|
||||||
serial: SerialIO<UART>,
|
|
||||||
}
|
|
||||||
|
|
||||||
#[derive(Debug)]
|
#[derive(Debug)]
|
||||||
pub enum ModemError {
|
pub enum ModemError {
|
||||||
CommandError(String),
|
CommandError(String),
|
||||||
|
@ -42,10 +49,22 @@ impl std::fmt::Display for ModemError {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
impl<UART: serial::Uart> Modem<UART> {
|
pub struct Modem<UART: serial::Uart, PWK: OutputPin, RST: OutputPin, PW: OutputPin> {
|
||||||
pub fn new(tx: Tx<UART>, rx: Rx<UART>) -> Self {
|
serial: SerialIO<UART>,
|
||||||
|
reset: RST,
|
||||||
|
power: PW,
|
||||||
|
power_key: PWK,
|
||||||
|
receiver: Receiver<Msg>,
|
||||||
|
}
|
||||||
|
|
||||||
|
impl<UART: serial::Uart, PWK: OutputPin, RST: OutputPin, PW: OutputPin> Modem<UART, PWK, RST, PW> {
|
||||||
|
pub fn new(tx: Tx<UART>, rx: Rx<UART>, mut pwrkey: PWK, mut rst: RST, mut power: PW, receiver: Receiver<Msg>) -> Self {
|
||||||
Self {
|
Self {
|
||||||
serial: SerialIO::new(tx, rx),
|
serial: SerialIO::new(tx, rx),
|
||||||
|
reset: rst,
|
||||||
|
power,
|
||||||
|
power_key: pwrkey,
|
||||||
|
receiver,
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -64,30 +83,31 @@ impl<UART: serial::Uart> Modem<UART> {
|
||||||
///
|
///
|
||||||
/// modem::init(modem_pwrkey, modem_rst, modem_power);
|
/// modem::init(modem_pwrkey, modem_rst, modem_power);
|
||||||
/// ```
|
/// ```
|
||||||
pub fn init(&mut self, mut pwrkey: impl OutputPin, mut rst: impl OutputPin, mut power: impl OutputPin) -> Result<()> {
|
pub fn init(&mut self) -> Result<()> {
|
||||||
println!("Turning SIM800L on ...");
|
println!("Turning SIM800L on ...");
|
||||||
power.set_high().map_err(|_| ModemError::SetupError("Error setting POWER to high.".to_string()))?;
|
self.power.set_high().map_err(|_| ModemError::SetupError("Error setting POWER to high.".to_string()))?;
|
||||||
//rst.set_high().map_err(|_| ModemError::SetupError("Error setting RST to high.".to_string()))?;
|
self.reset.set_high().map_err(|_| ModemError::SetupError("Error setting RST to high.".to_string()))?;
|
||||||
// Pull down PWRKEY for more than 1 second according to manual requirements
|
// Pull down PWRKEY for more than 1 second according to manual requirements
|
||||||
pwrkey.set_high().map_err(|_| ModemError::SetupError("Error setting PWRKEY to high.".to_string()))?;
|
self.power_key.set_high().map_err(|_| ModemError::SetupError("Error setting PWRKEY to high.".to_string()))?;
|
||||||
thread::sleep(Duration::from_millis(1500));
|
thread::sleep(Duration::from_millis(1500));
|
||||||
pwrkey.set_low().map_err(|_| ModemError::SetupError("Error setting PWRKEY to low.".to_string()))?;
|
self.power_key.set_low().map_err(|_| ModemError::SetupError("Error setting PWRKEY to low.".to_string()))?;
|
||||||
thread::sleep(Duration::from_millis(1000));
|
thread::sleep(Duration::from_millis(1000));
|
||||||
pwrkey.set_high().map_err(|_| ModemError::SetupError("Error setting PWRKEY to high.".to_string()))?;
|
self.power_key.set_high().map_err(|_| ModemError::SetupError("Error setting PWRKEY to high.".to_string()))?;
|
||||||
println!("Waiting for sim module to come online ...");
|
println!("Waiting for sim module to come online ...");
|
||||||
thread::sleep(Duration::from_millis(3000));
|
thread::sleep(Duration::from_millis(3000));
|
||||||
loop {
|
for _ in 0..10 {
|
||||||
match self.send_command(Command::probe()) {
|
let _ = self.send_command(Command::probe()).unwrap_or("".to_string());
|
||||||
Ok(_) => break,
|
thread::sleep(Duration::from_millis(1000));
|
||||||
_ => {
|
|
||||||
thread::sleep(Duration::from_millis(2000));
|
|
||||||
continue
|
|
||||||
},
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
self.serial.clear();
|
||||||
Ok(())
|
Ok(())
|
||||||
}
|
}
|
||||||
|
|
||||||
|
pub fn echo(&mut self, enabled: bool) -> Result<()> {
|
||||||
|
let cmd = format!("ATE{}", if enabled { 1 } else { 0 });
|
||||||
|
self.send(&cmd, "OK").map(|_| ())
|
||||||
|
}
|
||||||
|
|
||||||
/// Reads the serial RX until the `contains` string is encoutered if `contains` is Some(s), if
|
/// Reads the serial RX until the `contains` string is encoutered if `contains` is Some(s), if
|
||||||
/// None, then the first line is returned. If a timeout is reached. The timeout is provided on
|
/// None, then the first line is returned. If a timeout is reached. The timeout is provided on
|
||||||
/// input via the `timeout` argument. The first argument `contains` is checked against every
|
/// input via the `timeout` argument. The first argument `contains` is checked against every
|
||||||
|
@ -114,7 +134,7 @@ impl<UART: serial::Uart> Modem<UART> {
|
||||||
if response.contains(&c) {
|
if response.contains(&c) {
|
||||||
Ok(response)
|
Ok(response)
|
||||||
} else {
|
} else {
|
||||||
Err(ModemError::CommandError(format!("Didn't get expected ({}) from modem.", c)))
|
Err(ModemError::CommandError(format!("Didn't get expected ({}) from modem. Got: {}", c, response)))
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
Ok(response)
|
Ok(response)
|
||||||
|
@ -130,6 +150,7 @@ impl<UART: serial::Uart> Modem<UART> {
|
||||||
}
|
}
|
||||||
|
|
||||||
fn send(&mut self, at_command: &str, contains: &str) -> Result<String> {
|
fn send(&mut self, at_command: &str, contains: &str) -> Result<String> {
|
||||||
|
self.serial.clear();
|
||||||
println!("-----------------------------------------------------------");
|
println!("-----------------------------------------------------------");
|
||||||
println!("Sending {} ...", at_command);
|
println!("Sending {} ...", at_command);
|
||||||
|
|
||||||
|
@ -171,7 +192,7 @@ impl<UART: serial::Uart> Modem<UART> {
|
||||||
let _ = self.handle_prompt()?;
|
let _ = self.handle_prompt()?;
|
||||||
println!("Handled prompt OK!!");
|
println!("Handled prompt OK!!");
|
||||||
|
|
||||||
println!("Writing bytes in serial TX! ({:?})", String::from_utf8(buf.to_vec()));
|
println!("Writing bytes in serial TX! ({:?})", buf.into_iter().map(|b| char::from(*b)).collect::<String>());
|
||||||
self.serial
|
self.serial
|
||||||
.write_bytes(buf)
|
.write_bytes(buf)
|
||||||
.map_err(|err| ModemError::SendDataError(format!("{:?}", err)))?;
|
.map_err(|err| ModemError::SendDataError(format!("{:?}", err)))?;
|
||||||
|
@ -197,15 +218,15 @@ impl<UART: serial::Uart> Modem<UART> {
|
||||||
self.send_command(Command::gprs_bearer_status())
|
self.send_command(Command::gprs_bearer_status())
|
||||||
}
|
}
|
||||||
|
|
||||||
pub fn gprs_attach_ap(&mut self, apn: &str, username: &str, password: &str)-> Result<()> {
|
pub fn gprs_attach_ap(&mut self, config: crate::config::GprsAp)-> Result<()> {
|
||||||
println!("init gprs ...");
|
println!("init gprs ...");
|
||||||
let _ = self.send_command(Command::gprs_init())?;
|
let _ = self.send_command(Command::gprs_init())?;
|
||||||
|
|
||||||
println!("setting up gprs credentials for apn {}, {}:{})", apn, username, password);
|
println!("setting up gprs credentials for apn {}, {}:{})", config.apn, config.username, config.password);
|
||||||
|
|
||||||
let _ = self.send_command(Command::gprs_set_apn(apn))?;
|
let _ = self.send_command(Command::gprs_set_apn(config.apn))?;
|
||||||
let _ = self.send_command(Command::gprs_set_user(username))?;
|
let _ = self.send_command(Command::gprs_set_user(config.username))?;
|
||||||
let _ = self.send_command(Command::gprs_set_pwd(password))?;
|
let _ = self.send_command(Command::gprs_set_pwd(config.password))?;
|
||||||
|
|
||||||
Ok(())
|
Ok(())
|
||||||
}
|
}
|
||||||
|
@ -223,6 +244,7 @@ impl<UART: serial::Uart> Modem<UART> {
|
||||||
|
|
||||||
fn try_connect_gprs(&mut self) -> Result<()> {
|
fn try_connect_gprs(&mut self) -> Result<()> {
|
||||||
let mut retries = 0;
|
let mut retries = 0;
|
||||||
|
println!("TRYING TO CONNECT TO GPRS");
|
||||||
loop {
|
loop {
|
||||||
if self.is_gprs_attached()? {
|
if self.is_gprs_attached()? {
|
||||||
let _ = self.gprs_connect()?;
|
let _ = self.gprs_connect()?;
|
||||||
|
@ -258,17 +280,29 @@ impl<UART: serial::Uart> Modem<UART> {
|
||||||
|
|
||||||
pub fn tcp_connect(&mut self, addr: &str, port: u16) -> Result<()> {
|
pub fn tcp_connect(&mut self, addr: &str, port: u16) -> Result<()> {
|
||||||
let at_command = format!("AT+CIPSTART=\"TCP\",\"{}\",\"{}\"", addr, port);
|
let at_command = format!("AT+CIPSTART=\"TCP\",\"{}\",\"{}\"", addr, port);
|
||||||
let _ = self.send(&at_command, "CONNECT OK");
|
let mut reply_result = self.send(&at_command, "CONNECT OK");
|
||||||
for _ in 0..3 {
|
for _ in 0..3 {
|
||||||
if let Ok(reply) = self.command_read_response(Some("CONNECT OK".to_string())) {
|
if let Ok(reply) = reply_result {
|
||||||
println!("TCP connect replied with {}", reply);
|
println!("TCP connect replied with {}", reply);
|
||||||
break
|
break
|
||||||
|
} else {
|
||||||
|
reply_result = self.command_read_response(Some("CONNECT OK".to_string()));
|
||||||
}
|
}
|
||||||
thread::sleep(Duration::from_millis(500));
|
thread::sleep(Duration::from_millis(1000));
|
||||||
}
|
}
|
||||||
Ok(())
|
Ok(())
|
||||||
}
|
}
|
||||||
|
|
||||||
|
pub fn tls_connect(&mut self, addr: &str, port: u16) -> Result<()> {
|
||||||
|
let _ = self.tcp_connect(addr, port)?;
|
||||||
|
|
||||||
|
// ------------------------
|
||||||
|
// TLS handshake goes here.
|
||||||
|
// ------------------------
|
||||||
|
|
||||||
|
Ok(())
|
||||||
|
}
|
||||||
|
|
||||||
pub fn tcp_set_quick_mode(&mut self, mode: bool) -> Result<()> {
|
pub fn tcp_set_quick_mode(&mut self, mode: bool) -> Result<()> {
|
||||||
self.send_command(Command::tcp_set_quick_mode(mode))
|
self.send_command(Command::tcp_set_quick_mode(mode))
|
||||||
.map(|_| ())
|
.map(|_| ())
|
||||||
|
@ -280,6 +314,8 @@ impl<UART: serial::Uart> Modem<UART> {
|
||||||
}
|
}
|
||||||
|
|
||||||
pub fn tcp_manual_send(&mut self, buf: &[u8]) -> Result<()> {
|
pub fn tcp_manual_send(&mut self, buf: &[u8]) -> Result<()> {
|
||||||
|
thread::sleep(Duration::from_millis(200));
|
||||||
|
// self.serial.clear();
|
||||||
self.tcp_manual_send_data(buf)
|
self.tcp_manual_send_data(buf)
|
||||||
.map(|_| ())
|
.map(|_| ())
|
||||||
}
|
}
|
||||||
|
@ -335,8 +371,8 @@ impl<UART: serial::Uart> Modem<UART> {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
pub fn tcp_close_connection(&mut self) -> Result<String> {
|
pub fn tcp_close_connection(&mut self) -> Result<()> {
|
||||||
self.send_command(Command::tcp_close())
|
self.send_command(Command::tcp_close()).map(|_| ())
|
||||||
}
|
}
|
||||||
|
|
||||||
pub fn http_post(&mut self, url: &str, token: &str, content: &[u8]) -> Result<String> {
|
pub fn http_post(&mut self, url: &str, token: &str, content: &[u8]) -> Result<String> {
|
||||||
|
@ -450,13 +486,15 @@ impl<UART: serial::Uart> Modem<UART> {
|
||||||
Err(ModemError::ReadError("TCP server didn't respond!".into()))
|
Err(ModemError::ReadError("TCP server didn't respond!".into()))
|
||||||
}
|
}
|
||||||
|
|
||||||
fn mqtt_connect(&mut self, device_id: &str) -> anyhow::Result<()> {
|
fn mqtt_connect(&mut self, device_id: &str, username: &str, password: &str) -> anyhow::Result<()> {
|
||||||
let mut buf = Vec::new();
|
let mut buf = Vec::new();
|
||||||
let mut conn = ConnectPacket::new(device_id);
|
let mut conn = ConnectPacket::new(device_id);
|
||||||
conn.set_clean_session(true);
|
conn.set_clean_session(true);
|
||||||
conn.set_keep_alive(100);
|
conn.set_keep_alive(100);
|
||||||
|
conn.set_user_name(Some(username.to_string()));
|
||||||
|
conn.set_password(Some(password.to_string()));
|
||||||
let _ = conn.encode(&mut buf)?;
|
let _ = conn.encode(&mut buf)?;
|
||||||
self.tcp_manual_send(&mut buf).ok();
|
let _ = self.tcp_manual_send(&mut buf)?;
|
||||||
|
|
||||||
let reply = self.mqtt_receive_reply()?;
|
let reply = self.mqtt_receive_reply()?;
|
||||||
println!("mqtt decoded packet: ({:?})", reply);
|
println!("mqtt decoded packet: ({:?})", reply);
|
||||||
|
@ -476,114 +514,66 @@ impl<UART: serial::Uart> Modem<UART> {
|
||||||
message.as_bytes(),
|
message.as_bytes(),
|
||||||
);
|
);
|
||||||
let _ = packet.encode(&mut buf)?;
|
let _ = packet.encode(&mut buf)?;
|
||||||
println!("created mqtt publish packet ... ({})",
|
self.tcp_manual_send(&mut buf)?;
|
||||||
std::str::from_utf8(buf.as_slice()).unwrap_or(""));
|
Ok(())
|
||||||
self.tcp_manual_send(&mut buf).ok();
|
}
|
||||||
|
|
||||||
|
pub fn mqtt_send_position_loop(&mut self, host: &str, port: u16, username: &str, password: &str) -> anyhow::Result<()> {
|
||||||
|
if !self.is_gprs_attached()? {
|
||||||
|
let _ = self.gprs_attach_ap(crate::config::MTS)?;
|
||||||
|
let _ = self.try_connect_gprs()?;
|
||||||
|
}
|
||||||
|
// When command AT+CIPQSEND=0, it is in normal sending mode. In this mode, after user
|
||||||
|
// sends data by AT+CIPSEND, if the server receives TCP data, it will give ACK message
|
||||||
|
// to module, and the module will respond SEND OK.
|
||||||
|
let _ = self.send("AT+CIPQSEND=0", "OK");
|
||||||
|
// Enables getting data from network manually.
|
||||||
|
let _ = self.send("AT+CIPRXGET=1", "OK");
|
||||||
|
|
||||||
|
for _ in 0..5 {
|
||||||
|
if let Ok(_) = self.tcp_connect(host, port) {
|
||||||
|
break
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
let device_id = "c36a72df-5bd6-4f9b-995d-059433bc3267";
|
||||||
|
println!("connecting to MQTT with ({}:{})", username, password);
|
||||||
|
let _ = self.mqtt_connect(device_id, username, password)?;
|
||||||
|
|
||||||
|
println!("entering queue receive loop ...");
|
||||||
|
let mut err_count = 0;
|
||||||
|
let _ = loop {
|
||||||
|
match self.receiver.recv() {
|
||||||
|
Ok(Msg::Gps(solution)) => {
|
||||||
|
println!("received GPS solution {:?} | sending to mqtt ...", solution);
|
||||||
|
serde_json_core::ser::to_string::<Solution, 512>(&solution)
|
||||||
|
.map_err(|e| anyhow::Error::new(e))
|
||||||
|
.and_then(|sol| self.mqtt_publish(device_id, &sol))?;
|
||||||
|
err_count = 0;
|
||||||
|
},
|
||||||
|
Ok(Msg::Accelerometer(acc)) => {
|
||||||
|
println!("received accel {} | sending to mqtt ...", acc);
|
||||||
|
let _ = self.mqtt_publish(device_id, &format!("{:?}", acc))?;
|
||||||
|
err_count = 0;
|
||||||
|
}
|
||||||
|
Err(e) => {
|
||||||
|
if err_count < 5 {
|
||||||
|
err_count += 1;
|
||||||
|
println!("received error {} | NOT sending to mqtt ...", e);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
break
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
Ok(())
|
Ok(())
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
impl<UART: serial::Uart> std::io::Read for Modem<UART> {
|
impl<UART: serial::Uart, PWK: OutputPin, RST: OutputPin, PW: OutputPin> std::io::Read for Modem<UART, PWK, RST, PW> {
|
||||||
fn read(&mut self, buf: &mut [u8]) -> std::io::Result<usize> {
|
fn read(&mut self, buf: &mut [u8]) -> std::io::Result<usize> {
|
||||||
self.tcp_receive(buf).map_err(|_| std::io::Error::from(std::io::ErrorKind::ConnectionAborted))
|
self.tcp_receive(buf).map_err(|_| std::io::Error::from(std::io::ErrorKind::ConnectionAborted))
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
pub fn main<T: Sync + Send>(
|
|
||||||
rx: esp_idf_hal::gpio::Gpio26<T>,
|
|
||||||
tx: esp_idf_hal::gpio::Gpio27<T>,
|
|
||||||
uart: serial::UART1,
|
|
||||||
pwrkey: esp_idf_hal::gpio::Gpio4<esp_idf_hal::gpio::Output>,
|
|
||||||
rst: esp_idf_hal::gpio::Gpio5<esp_idf_hal::gpio::Output>,
|
|
||||||
power: esp_idf_hal::gpio::Gpio23<esp_idf_hal::gpio::Output>,
|
|
||||||
receiver: Receiver<Msg>,
|
|
||||||
) -> std::result::Result<(), anyhow::Error> {
|
|
||||||
let serial_pins = serial::Pins {
|
|
||||||
tx,
|
|
||||||
rx,
|
|
||||||
cts: None,
|
|
||||||
rts: None,
|
|
||||||
};
|
|
||||||
|
|
||||||
let serial: serial::Serial<serial::UART1, _, _> = serial::Serial::new(
|
|
||||||
uart,
|
|
||||||
serial_pins,
|
|
||||||
serial::config::Config::default().baudrate(Hertz(115200)),
|
|
||||||
)?;
|
|
||||||
|
|
||||||
let (tx, rx) = serial.split();
|
|
||||||
let mut mdm = Modem::new(tx, rx);
|
|
||||||
|
|
||||||
mdm.init(pwrkey, rst, power)?;
|
|
||||||
|
|
||||||
// thread::sleep(Duration::from_millis(500));
|
|
||||||
|
|
||||||
//println!("setting up client TLS cert");
|
|
||||||
//let client_cert = include_bytes!("../certs/full-bin.p12");
|
|
||||||
//let client_cert_path = "C:\\USER\\fullchain.pem";
|
|
||||||
|
|
||||||
//let _ = mdm.upload_cert(client_cert_path, client_cert)?;
|
|
||||||
//let _ = mdm.ssl_set_client_cert(client_cert_path, "t")?;
|
|
||||||
//let _ = mdm.fs_list("C:\\USER\\")?;
|
|
||||||
|
|
||||||
// Retry 5 times to open a TCP connection, otherwise fail and wait for reboot.
|
|
||||||
let mut retries = 0;
|
|
||||||
|
|
||||||
loop {
|
|
||||||
if !mdm.is_gprs_attached()? {
|
|
||||||
let _ = mdm.gprs_attach_ap(
|
|
||||||
crate::config::A1_GPRS_AP.apn,
|
|
||||||
crate::config::A1_GPRS_AP.username,
|
|
||||||
crate::config::A1_GPRS_AP.password,
|
|
||||||
)?;
|
|
||||||
}
|
|
||||||
if let Ok(()) = mdm.try_connect_gprs() {
|
|
||||||
let device_id = "c36a72df-5bd6-4f9b-995d-059433bc3267";
|
|
||||||
|
|
||||||
// When command AT+CIPQSEND=0, it is in normal sending mode. In this mode, after user
|
|
||||||
// sends data by AT+CIPSEND, if the server receives TCP data, it will give ACK message
|
|
||||||
// to module, and the module will respond SEND OK.
|
|
||||||
let _ = mdm.send("AT+CIPQSEND=0", "OK");
|
|
||||||
// Enables getting data from network manually.
|
|
||||||
let _ = mdm.send("AT+CIPRXGET=1", "OK");
|
|
||||||
|
|
||||||
if let Err(_) = mdm.tcp_connect("51.158.66.64", 7887) {
|
|
||||||
if retries < 5 {
|
|
||||||
retries += 1;
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
thread::sleep(Duration::from_millis(500));
|
|
||||||
mdm.serial.clear();
|
|
||||||
|
|
||||||
let _ = mdm.mqtt_connect(device_id)?;
|
|
||||||
|
|
||||||
println!("entering queue receive loop ...");
|
|
||||||
let mut err_count = 0;
|
|
||||||
let _ = loop {
|
|
||||||
match receiver.recv() {
|
|
||||||
Ok(Msg::Gps(solution)) => {
|
|
||||||
println!("received GPS solution {:?} | sending to mqtt ...", solution);
|
|
||||||
let _ = mdm.mqtt_publish(device_id, &format!("{:?}", solution))?;
|
|
||||||
err_count = 0;
|
|
||||||
},
|
|
||||||
Ok(Msg::Accelerometer(acc)) => {
|
|
||||||
println!("received accel {} | sending to mqtt ...", acc);
|
|
||||||
let _ = mdm.mqtt_publish(device_id, &format!("{:?}", acc))?;
|
|
||||||
err_count = 0;
|
|
||||||
}
|
|
||||||
Err(e) => {
|
|
||||||
if err_count < 5 {
|
|
||||||
err_count += 1;
|
|
||||||
println!("received error {} | NOT sending to mqtt ...", e);
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
break
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
|
||||||
let _ = mdm.tcp_close_connection()?;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
106
src/types.rs
106
src/types.rs
|
@ -1,14 +1,106 @@
|
||||||
#[derive(Debug)]
|
#![allow(dead_code)]
|
||||||
|
use nmea0183::{
|
||||||
|
GGA,
|
||||||
|
GLL,
|
||||||
|
coords::{
|
||||||
|
Latitude as NMEALatitude,
|
||||||
|
Longitude as NMEALongitude,
|
||||||
|
Hemisphere as NMEAHemisphere,
|
||||||
|
},
|
||||||
|
};
|
||||||
|
use serde::Serialize;
|
||||||
|
|
||||||
|
#[derive(Debug, Serialize)]
|
||||||
|
pub enum Hemisphere {
|
||||||
|
North,
|
||||||
|
South,
|
||||||
|
East,
|
||||||
|
West,
|
||||||
|
}
|
||||||
|
|
||||||
|
#[derive(Debug, Serialize)]
|
||||||
|
pub struct Latitude {
|
||||||
|
degrees: u8,
|
||||||
|
minutes: u8,
|
||||||
|
seconds: f32,
|
||||||
|
hemisphere: Hemisphere,
|
||||||
|
}
|
||||||
|
|
||||||
|
#[derive(Debug, Serialize)]
|
||||||
|
pub struct Longitude {
|
||||||
|
degrees: u8,
|
||||||
|
minutes: u8,
|
||||||
|
seconds: f32,
|
||||||
|
hemisphere: Hemisphere,
|
||||||
|
}
|
||||||
|
|
||||||
|
impl From<NMEALatitude> for Latitude {
|
||||||
|
fn from(lat: NMEALatitude) -> Self {
|
||||||
|
Self {
|
||||||
|
degrees: lat.degrees,
|
||||||
|
minutes: lat.minutes,
|
||||||
|
seconds: lat.seconds,
|
||||||
|
hemisphere: lat.hemisphere.into(),
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
impl From<NMEALongitude> for Longitude {
|
||||||
|
fn from(lon: NMEALongitude) -> Self {
|
||||||
|
Self {
|
||||||
|
degrees: lon.degrees,
|
||||||
|
minutes: lon.minutes,
|
||||||
|
seconds: lon.seconds,
|
||||||
|
hemisphere: lon.hemisphere.into(),
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
impl From<NMEAHemisphere> for Hemisphere {
|
||||||
|
fn from(hem: NMEAHemisphere) -> Self {
|
||||||
|
match hem {
|
||||||
|
NMEAHemisphere::North => Self::North,
|
||||||
|
NMEAHemisphere::South => Self::South,
|
||||||
|
NMEAHemisphere::East => Self::East,
|
||||||
|
NMEAHemisphere::West => Self::West,
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#[derive(Debug, Serialize)]
|
||||||
pub struct Solution {
|
pub struct Solution {
|
||||||
pub latitude: f64,
|
pub latitude: Latitude,
|
||||||
pub longitude: f64,
|
pub longitude: Longitude,
|
||||||
pub altitude: f64,
|
pub altitude: Option<f32>,
|
||||||
pub speed: f64,
|
pub speed: Option<f32>,
|
||||||
pub direction: f64,
|
pub direction: Option<f32>,
|
||||||
|
}
|
||||||
|
|
||||||
|
impl From<GGA> for Solution {
|
||||||
|
fn from(gga: GGA) -> Self {
|
||||||
|
Self {
|
||||||
|
latitude: gga.latitude.into(),
|
||||||
|
longitude: gga.longitude.into(),
|
||||||
|
altitude: Some(gga.altitude.meters),
|
||||||
|
speed: None,
|
||||||
|
direction: None,
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
impl From<GLL> for Solution {
|
||||||
|
fn from(gll: GLL) -> Self {
|
||||||
|
Self {
|
||||||
|
latitude: gll.latitude.into(),
|
||||||
|
longitude: gll.longitude.into(),
|
||||||
|
altitude: None,
|
||||||
|
speed: None,
|
||||||
|
direction: None,
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
pub enum Msg {
|
pub enum Msg {
|
||||||
Gps(Solution),
|
Gps(Solution),
|
||||||
Accelerometer(String),
|
Accelerometer(String),
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in a new issue