pub struct LOCAL_POSITION_NED_COV_DATA {
pub time_usec: u64,
pub x: f32,
pub y: f32,
pub z: f32,
pub vx: f32,
pub vy: f32,
pub vz: f32,
pub ax: f32,
pub ay: f32,
pub az: f32,
pub covariance: [f32; 45],
pub estimator_type: MavEstimatorType,
}
python_array_test
only.Expand description
id: 64 The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention).
Fields§
§time_usec: u64
Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number..
x: f32
X Position.
y: f32
Y Position.
z: f32
Z Position.
vx: f32
X Speed.
vy: f32
Y Speed.
vz: f32
Z Speed.
ax: f32
X Acceleration.
ay: f32
Y Acceleration.
az: f32
Z Acceleration.
covariance: [f32; 45]
Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array..
estimator_type: MavEstimatorType
Class id of the estimator this estimate originated from..
Implementations§
source§impl LOCAL_POSITION_NED_COV_DATA
impl LOCAL_POSITION_NED_COV_DATA
pub const ENCODED_LEN: usize = 225usize
pub const DEFAULT: Self = _
Trait Implementations§
source§impl Clone for LOCAL_POSITION_NED_COV_DATA
impl Clone for LOCAL_POSITION_NED_COV_DATA
source§fn clone(&self) -> LOCAL_POSITION_NED_COV_DATA
fn clone(&self) -> LOCAL_POSITION_NED_COV_DATA
1.0.0 · source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read moresource§impl Debug for LOCAL_POSITION_NED_COV_DATA
impl Debug for LOCAL_POSITION_NED_COV_DATA
source§impl<'de> Deserialize<'de> for LOCAL_POSITION_NED_COV_DATA
impl<'de> Deserialize<'de> for LOCAL_POSITION_NED_COV_DATA
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 MessageData for LOCAL_POSITION_NED_COV_DATA
impl MessageData for LOCAL_POSITION_NED_COV_DATA
const ID: u32 = 64u32
const NAME: &'static str = "LOCAL_POSITION_NED_COV"
const EXTRA_CRC: u8 = 191u8
const ENCODED_LEN: usize = 225usize
type Message = MavMessage
fn deser(_version: MavlinkVersion, __input: &[u8]) -> Result<Self, ParserError>
fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize
impl StructuralPartialEq for LOCAL_POSITION_NED_COV_DATA
Auto Trait Implementations§
impl Freeze for LOCAL_POSITION_NED_COV_DATA
impl RefUnwindSafe for LOCAL_POSITION_NED_COV_DATA
impl Send for LOCAL_POSITION_NED_COV_DATA
impl Sync for LOCAL_POSITION_NED_COV_DATA
impl Unpin for LOCAL_POSITION_NED_COV_DATA
impl UnwindSafe for LOCAL_POSITION_NED_COV_DATA
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§unsafe fn clone_to_uninit(&self, dst: *mut T)
unsafe fn clone_to_uninit(&self, dst: *mut T)
clone_to_uninit
)