From 8f3983fe536ecec4e7249260809195f3be301eb6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Ant=C3=B4nio=20Cardoso?= Date: Fri, 4 Oct 2024 00:00:51 -0300 Subject: [PATCH] src: Use our timestamp functions instead of chrono --- src/drivers/rest/data.rs | 6 ++++-- src/drivers/tlog/reader.rs | 5 ++--- src/drivers/tlog/writer.rs | 4 ++-- src/protocol.rs | 4 ++-- src/stats/accumulated/mod.rs | 6 +++--- src/stats/actor.rs | 5 +++-- 6 files changed, 16 insertions(+), 14 deletions(-) diff --git a/src/drivers/rest/data.rs b/src/drivers/rest/data.rs index 5d3637da..358f894e 100644 --- a/src/drivers/rest/data.rs +++ b/src/drivers/rest/data.rs @@ -7,6 +7,8 @@ use lazy_static::lazy_static; use mavlink::{self, Message}; use serde::{Deserialize, Serialize}; +use crate::protocol::timestamp_micros; + lazy_static! { static ref DATA: Data = Data { messages: Arc::new(Mutex::new(MAVLinkVehiclesData::default())), @@ -135,7 +137,7 @@ struct Temporal { impl Default for Temporal { fn default() -> Self { - let now_us = chrono::Local::now().timestamp_micros() as u64; + let now_us = timestamp_micros(); Self { first_update_us: now_us, last_update_us: now_us, @@ -147,7 +149,7 @@ impl Default for Temporal { impl Temporal { fn update(&mut self) { - self.last_update_us = chrono::Local::now().timestamp_micros() as u64; + self.last_update_us = timestamp_micros(); self.counter = self.counter.wrapping_add(1); self.frequency = (10e6 * self.counter as f32) / ((self.last_update_us - self.first_update_us) as f32); diff --git a/src/drivers/tlog/reader.rs b/src/drivers/tlog/reader.rs index a28d6789..ab673f25 100644 --- a/src/drivers/tlog/reader.rs +++ b/src/drivers/tlog/reader.rs @@ -1,7 +1,6 @@ use std::{path::PathBuf, sync::Arc}; use anyhow::{Context, Result}; -use chrono::DateTime; use mavlink::ardupilotmega::MavMessage; use mavlink_server::callbacks::{Callbacks, MessageCallback}; use tokio::sync::{broadcast, RwLock}; @@ -9,7 +8,7 @@ use tracing::*; use crate::{ drivers::{Driver, DriverInfo}, - protocol::Protocol, + protocol::{check_timestamp_us, Protocol}, stats::{ accumulated::driver::{AccumulatedDriverStats, AccumulatedDriverStatsProvider}, driver::DriverUuid, @@ -85,7 +84,7 @@ impl TlogReader { u64::from_be_bytes(timestamp_bytes) }; - if DateTime::from_timestamp_micros(us_since_epoch as i64).is_none() { + if !check_timestamp_us(us_since_epoch) { warn!("Failed to convert unix time: {us_since_epoch:?}"); reader.consume(1); diff --git a/src/drivers/tlog/writer.rs b/src/drivers/tlog/writer.rs index 12d2127b..598ecc79 100644 --- a/src/drivers/tlog/writer.rs +++ b/src/drivers/tlog/writer.rs @@ -10,7 +10,7 @@ use tracing::*; use crate::{ drivers::{Driver, DriverInfo}, - protocol::Protocol, + protocol::{timestamp_micros, Protocol}, stats::{ accumulated::driver::{AccumulatedDriverStats, AccumulatedDriverStatsProvider}, driver::DriverUuid, @@ -70,7 +70,7 @@ impl TlogWriter { loop { match hub_receiver.recv().await { Ok(message) => { - let timestamp = chrono::Utc::now().timestamp_micros() as u64; + let timestamp = timestamp_micros(); self.stats.write().await.stats.update_output(&message); diff --git a/src/protocol.rs b/src/protocol.rs index 42bd8881..3e1c6c56 100644 --- a/src/protocol.rs +++ b/src/protocol.rs @@ -21,7 +21,7 @@ impl Protocol { pub fn new(origin: &str, message: MAVLinkV2MessageRaw) -> Self { Self { origin: origin.to_string(), - timestamp: chrono::Utc::now().timestamp_micros() as u64, + timestamp: timestamp_micros(), message, } } @@ -83,7 +83,7 @@ impl DerefMut for Protocol { } #[inline(always)] -pub fn generate_timestamp_us() -> u64 { +pub fn timestamp_micros() -> u64 { std::time::SystemTime::now() .duration_since(std::time::UNIX_EPOCH) .map(|duration| duration.as_micros() as u64) diff --git a/src/stats/accumulated/mod.rs b/src/stats/accumulated/mod.rs index 8df21e59..e3717d68 100644 --- a/src/stats/accumulated/mod.rs +++ b/src/stats/accumulated/mod.rs @@ -5,7 +5,7 @@ use std::sync::Arc; use serde::Serialize; -use crate::protocol::Protocol; +use crate::protocol::{timestamp_micros, Protocol}; #[derive(Clone, Debug, Serialize)] pub struct AccumulatedStatsInner { @@ -20,7 +20,7 @@ impl Default for AccumulatedStatsInner { fn default() -> Self { Self { last_message: None, - last_update_us: chrono::Utc::now().timestamp_micros() as u64, + last_update_us: timestamp_micros(), messages: 0, bytes: 0, delay: 0, @@ -31,7 +31,7 @@ impl Default for AccumulatedStatsInner { impl AccumulatedStatsInner { pub fn update(&mut self, message: &Arc) { self.last_message = Some(message.clone()); - self.last_update_us = chrono::Utc::now().timestamp_micros() as u64; + self.last_update_us = timestamp_micros(); self.bytes = self.bytes.wrapping_add(message.raw_bytes().len() as u64); self.messages = self.messages.wrapping_add(1); self.delay = self diff --git a/src/stats/actor.rs b/src/stats/actor.rs index 27dcb478..55853233 100644 --- a/src/stats/actor.rs +++ b/src/stats/actor.rs @@ -7,6 +7,7 @@ use tracing::*; use crate::{ hub, + protocol::timestamp_micros, stats::{ accumulated::{ driver::AccumulatedDriversStats, messages::AccumulatedHubMessagesStats, @@ -128,7 +129,7 @@ impl StatsActor { let last_accumulated_hub_messages_stats = Arc::new(Mutex::new(AccumulatedHubMessagesStats::default())); let hub_messages_stats = Arc::new(RwLock::new(HubMessagesStats::default())); - let start_time = Arc::new(RwLock::new(chrono::Utc::now().timestamp_micros() as u64)); + let start_time = Arc::new(RwLock::new(timestamp_micros())); Self { start_time, @@ -180,7 +181,7 @@ impl StatsActor { if let Err(error) = hub::reset_all_stats().await { error!("Failed resetting stats: {error:?}"); } - *self.start_time.write().await = chrono::Utc::now().timestamp_micros() as u64; + *self.start_time.write().await = timestamp_micros(); self.last_accumulated_drivers_stats.lock().await.clear(); driver_stats.clear();