Struct mavio::protocol::MavTimestamp
source · pub struct MavTimestamp { /* private fields */ }
Expand description
A 48-bit timestamp used for MAVLink 2
packet signing.
MAVLink signature timestamp is a 48-bit value that equals to the number of milliseconds * 10 since the start of the MAVLink epoch (1st January 2015 GMT).
§Links
- Timestamp handling in MAVLink documentation.
Signature
is a section of MAVLink packet where timestamp is stored.
Implementations§
source§impl MavTimestamp
impl MavTimestamp
sourcepub fn from_millis(value: u64) -> Self
pub fn from_millis(value: u64) -> Self
Creates MavTimestamp
from milliseconds since the beginning of the Unix epoch.
sourcepub fn from_micros(value: u128) -> Self
pub fn from_micros(value: u128) -> Self
Creates MavTimestamp
from microseconds since the beginning of the Unix epoch.
sourcepub fn from_system_time(value: SystemTime) -> Self
pub fn from_system_time(value: SystemTime) -> Self
Creates MavTimestamp
from the SystemTime
. Uses microsecond * 10 precision.
Available only when std
feature is enabled.
sourcepub fn from_raw_u64(value: u64) -> Self
pub fn from_raw_u64(value: u64) -> Self
Creates MavTimestamp
from u64
raw value discarding two higher bytes.
Provided value
should represent Self::as_raw_u64
MAVLink 2
signature timestamp.
sourcepub fn from_bytes(bytes: &SignatureTimestampBytes) -> Self
pub fn from_bytes(bytes: &SignatureTimestampBytes) -> Self
sourcepub fn as_raw_u64(&self) -> u64
pub fn as_raw_u64(&self) -> u64
Raw MAVLink timestamp value.
Returns number of milliseconds * 10 since the start of MAVLink epoch (1st January 2015 GMT).
Use Self::as_raw_u64
to set this value.
§Links
- Timestamp handling in MAVLink documentation.
sourcepub fn set_raw_u64(&mut self, raw: u64) -> &mut Self
pub fn set_raw_u64(&mut self, raw: u64) -> &mut Self
Sets raw MAVLink timestamp value.
Use Self::as_raw_u64
to get this value.
§Links
- Timestamp handling in MAVLink documentation.
sourcepub fn as_millis_mavlink(&self) -> u64
pub fn as_millis_mavlink(&self) -> u64
MAVLink timestamp in milliseconds.
Returns timestamp as a number of milliseconds since the start of MAVLink epoch (1st January 2015 GMT).
Use Self::as_millis_mavlink
to set this value.
§Links
- Timestamp handling in MAVLink documentation.
sourcepub fn set_millis_mavlink(&mut self, millis_mavlink: u64) -> &mut Self
pub fn set_millis_mavlink(&mut self, millis_mavlink: u64) -> &mut Self
Sets MAVLink timestamp in milliseconds.
Use Self::as_millis_mavlink
to get this value.
§Links
- Timestamp handling in MAVLink documentation.
sourcepub fn as_millis(&self) -> u64
pub fn as_millis(&self) -> u64
Unix timestamp in milliseconds.
Use Self::set_millis
to set this value.
Returns value as number of milliseconds since the start of Unix epoch (1st January 1970 GMT).
§Links
- Timestamp handling in MAVLink documentation.
SIGNATURE_TIMESTAMP_OFFSET
defines offset between epochs.
sourcepub fn set_millis(&mut self, millis: u64) -> &mut Self
pub fn set_millis(&mut self, millis: u64) -> &mut Self
Sets Unix timestamp in milliseconds.
Use Self::as_millis
to get this value.
§Links
- Timestamp handling in MAVLink documentation.
sourcepub fn as_micros_mavlink(&self) -> u128
pub fn as_micros_mavlink(&self) -> u128
MAVLink timestamp in microseconds.
Returns timestamp as a number of microseconds since the start of MAVLink epoch (1st January 2015 GMT).
Use Self::set_micros_mavlink
to set this value.
§Links
- Timestamp handling in MAVLink documentation.
sourcepub fn set_micros_mavlink(&mut self, micros_mavlink: u128) -> &mut Self
pub fn set_micros_mavlink(&mut self, micros_mavlink: u128) -> &mut Self
Sets MAVLink timestamp in microseconds.
Use Self::as_micros_mavlink
to get this value.
§Links
- Timestamp handling in MAVLink documentation.
sourcepub fn as_micros(&self) -> u128
pub fn as_micros(&self) -> u128
Unix timestamp in microseconds.
Returns value as number of microseconds since the start of Unix epoch (1st January 1970 GMT).
Use Self::set_micros
to set this value.
§Links
- Timestamp handling in MAVLink documentation.
SIGNATURE_TIMESTAMP_OFFSET
defines offset between epochs.
sourcepub fn set_micros(&mut self, micros: u128) -> &mut Self
pub fn set_micros(&mut self, micros: u128) -> &mut Self
Sets Unix timestamp in microseconds.
Use Self::as_micros
to get this value.
§Links
- Timestamp handling in MAVLink documentation.
sourcepub fn to_bytes_array(&self) -> SignatureTimestampBytes
pub fn to_bytes_array(&self) -> SignatureTimestampBytes
Trait Implementations§
source§impl Clone for MavTimestamp
impl Clone for MavTimestamp
source§fn clone(&self) -> MavTimestamp
fn clone(&self) -> MavTimestamp
1.0.0 · source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read moresource§impl Debug for MavTimestamp
impl Debug for MavTimestamp
source§impl Default for MavTimestamp
impl Default for MavTimestamp
source§fn default() -> MavTimestamp
fn default() -> MavTimestamp
source§impl<'de> Deserialize<'de> for MavTimestamp
impl<'de> Deserialize<'de> for MavTimestamp
source§fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
source§impl From<[u8; 6]> for MavTimestamp
impl From<[u8; 6]> for MavTimestamp
source§fn from(bytes: SignatureTimestampBytes) -> Self
fn from(bytes: SignatureTimestampBytes) -> Self
Decodes MavTimestamp
from bytes.
Uses MavTimestamp::from_bytes
.
source§impl From<MavTimestamp> for SignatureTimestampBytes
impl From<MavTimestamp> for SignatureTimestampBytes
source§fn from(timestamp: MavTimestamp) -> Self
fn from(timestamp: MavTimestamp) -> Self
Encodes MavTimestamp
into bytes.
source§impl From<SystemTime> for MavTimestamp
impl From<SystemTime> for MavTimestamp
source§fn from(value: SystemTime) -> Self
fn from(value: SystemTime) -> Self
Creates MavTimestamp
from the SystemTime
.
Available only when std
feature is enabled. Uses Self::from_system_time
internally.
source§impl From<u64> for MavTimestamp
impl From<u64> for MavTimestamp
source§fn from(value: u64) -> Self
fn from(value: u64) -> Self
Creates MavTimestamp
from u64
raw value discarding two higher bytes.
Uses Self::from_raw_u64 internally.
source§impl Serialize for MavTimestamp
impl Serialize for MavTimestamp
impl Copy for MavTimestamp
Auto Trait Implementations§
impl Freeze for MavTimestamp
impl RefUnwindSafe for MavTimestamp
impl Send for MavTimestamp
impl Sync for MavTimestamp
impl Unpin for MavTimestamp
impl UnwindSafe for MavTimestamp
Blanket Implementations§
source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
source§default unsafe fn clone_to_uninit(&self, dst: *mut T)
default unsafe fn clone_to_uninit(&self, dst: *mut T)
clone_to_uninit
)source§impl<T> CloneToUninit for Twhere
T: Copy,
impl<T> CloneToUninit for Twhere
T: Copy,
source§unsafe fn clone_to_uninit(&self, dst: *mut T)
unsafe fn clone_to_uninit(&self, dst: *mut T)
clone_to_uninit
)