#[repr(u32)]pub enum MavFrame {
Show 22 variants
MAV_FRAME_GLOBAL = 0,
MAV_FRAME_LOCAL_NED = 1,
MAV_FRAME_MISSION = 2,
MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
MAV_FRAME_LOCAL_ENU = 4,
MAV_FRAME_GLOBAL_INT = 5,
MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6,
MAV_FRAME_LOCAL_OFFSET_NED = 7,
MAV_FRAME_BODY_NED = 8,
MAV_FRAME_BODY_OFFSET_NED = 9,
MAV_FRAME_GLOBAL_TERRAIN_ALT = 10,
MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11,
MAV_FRAME_BODY_FRD = 12,
MAV_FRAME_RESERVED_13 = 13,
MAV_FRAME_RESERVED_14 = 14,
MAV_FRAME_RESERVED_15 = 15,
MAV_FRAME_RESERVED_16 = 16,
MAV_FRAME_RESERVED_17 = 17,
MAV_FRAME_RESERVED_18 = 18,
MAV_FRAME_RESERVED_19 = 19,
MAV_FRAME_LOCAL_FRD = 20,
MAV_FRAME_LOCAL_FLU = 21,
}
common
only.Expand description
Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. Global frames use the following naming conventions: - “GLOBAL”: Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. The following modifiers may be used with “GLOBAL”: - “RELATIVE_ALT”: Altitude is relative to the vehicle home position rather than MSL. - “TERRAIN_ALT”: Altitude is relative to ground level rather than MSL. - “INT”: Latitude/longitude (in degrees) are scaled by multiplying by 1E7. Local frames use the following naming conventions: - “LOCAL”: Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator (“EKF”). - “BODY”: Origin of local frame travels with the vehicle. NOTE, “BODY” does NOT indicate alignment of frame axis with vehicle attitude. - “OFFSET”: Deprecated synonym for “BODY” (origin travels with the vehicle). Not to be used for new frames. Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED).
Variants§
MAV_FRAME_GLOBAL = 0
Global (WGS84) coordinate frame + MSL altitude. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL).
MAV_FRAME_LOCAL_NED = 1
NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth.
MAV_FRAME_MISSION = 2
NOT a coordinate frame, indicates a mission command.
MAV_FRAME_GLOBAL_RELATIVE_ALT = 3
Global (WGS84) coordinate frame + altitude relative to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home position.
MAV_FRAME_LOCAL_ENU = 4
ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth.
MAV_FRAME_GLOBAL_INT = 5
Global (WGS84) coordinate frame (scaled) + MSL altitude. First value / x: latitude in degrees1E7, second value / y: longitude in degrees1E7, third value / z: positive altitude over mean sea level (MSL).
MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6
Global (WGS84) coordinate frame (scaled) + altitude relative to the home position. First value / x: latitude in degrees1E7, second value / y: longitude in degrees1E7, third value / z: positive altitude with 0 being at the altitude of the home position.
MAV_FRAME_LOCAL_OFFSET_NED = 7
NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle.
MAV_FRAME_BODY_NED = 8
Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values.
MAV_FRAME_BODY_OFFSET_NED = 9
This is the same as MAV_FRAME_BODY_FRD.
MAV_FRAME_GLOBAL_TERRAIN_ALT = 10
Global (WGS84) coordinate frame with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
Global (WGS84) coordinate frame (scaled) with AGL altitude (at the waypoint coordinate). First value / x: latitude in degrees1E7, second value / y: longitude in degrees1E7, third value / z: positive altitude in meters with 0 being at ground level in terrain model.
MAV_FRAME_BODY_FRD = 12
FRD local frame aligned to the vehicle’s attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle.
MAV_FRAME_RESERVED_13 = 13
MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up).
MAV_FRAME_RESERVED_14 = 14
MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down).
MAV_FRAME_RESERVED_15 = 15
MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up).
MAV_FRAME_RESERVED_16 = 16
MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down).
MAV_FRAME_RESERVED_17 = 17
MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up).
MAV_FRAME_RESERVED_18 = 18
MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down).
MAV_FRAME_RESERVED_19 = 19
MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up).
MAV_FRAME_LOCAL_FRD = 20
FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane.
MAV_FRAME_LOCAL_FLU = 21
FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane.
Implementations§
Trait Implementations§
source§impl<'de> Deserialize<'de> for MavFrame
impl<'de> Deserialize<'de> for MavFrame
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 FromPrimitive for MavFrame
impl FromPrimitive for MavFrame
source§fn from_i64(n: i64) -> Option<Self>
fn from_i64(n: i64) -> Option<Self>
i64
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_u64(n: u64) -> Option<Self>
fn from_u64(n: u64) -> Option<Self>
u64
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_isize(n: isize) -> Option<Self>
fn from_isize(n: isize) -> Option<Self>
isize
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_i8(n: i8) -> Option<Self>
fn from_i8(n: i8) -> Option<Self>
i8
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_i16(n: i16) -> Option<Self>
fn from_i16(n: i16) -> Option<Self>
i16
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_i32(n: i32) -> Option<Self>
fn from_i32(n: i32) -> Option<Self>
i32
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_i128(n: i128) -> Option<Self>
fn from_i128(n: i128) -> Option<Self>
i128
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned. Read moresource§fn from_usize(n: usize) -> Option<Self>
fn from_usize(n: usize) -> Option<Self>
usize
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_u8(n: u8) -> Option<Self>
fn from_u8(n: u8) -> Option<Self>
u8
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_u16(n: u16) -> Option<Self>
fn from_u16(n: u16) -> Option<Self>
u16
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_u32(n: u32) -> Option<Self>
fn from_u32(n: u32) -> Option<Self>
u32
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned.source§fn from_u128(n: u128) -> Option<Self>
fn from_u128(n: u128) -> Option<Self>
u128
to return an optional value of this type. If the
value cannot be represented by this type, then None
is returned. Read moresource§impl ToPrimitive for MavFrame
impl ToPrimitive for MavFrame
source§fn to_i64(&self) -> Option<i64>
fn to_i64(&self) -> Option<i64>
self
to an i64
. If the value cannot be
represented by an i64
, then None
is returned.source§fn to_u64(&self) -> Option<u64>
fn to_u64(&self) -> Option<u64>
self
to a u64
. If the value cannot be
represented by a u64
, then None
is returned.source§fn to_isize(&self) -> Option<isize>
fn to_isize(&self) -> Option<isize>
self
to an isize
. If the value cannot be
represented by an isize
, then None
is returned.source§fn to_i8(&self) -> Option<i8>
fn to_i8(&self) -> Option<i8>
self
to an i8
. If the value cannot be
represented by an i8
, then None
is returned.source§fn to_i16(&self) -> Option<i16>
fn to_i16(&self) -> Option<i16>
self
to an i16
. If the value cannot be
represented by an i16
, then None
is returned.source§fn to_i32(&self) -> Option<i32>
fn to_i32(&self) -> Option<i32>
self
to an i32
. If the value cannot be
represented by an i32
, then None
is returned.source§fn to_i128(&self) -> Option<i128>
fn to_i128(&self) -> Option<i128>
self
to an i128
. If the value cannot be
represented by an i128
(i64
under the default implementation), then
None
is returned. Read moresource§fn to_usize(&self) -> Option<usize>
fn to_usize(&self) -> Option<usize>
self
to a usize
. If the value cannot be
represented by a usize
, then None
is returned.source§fn to_u8(&self) -> Option<u8>
fn to_u8(&self) -> Option<u8>
self
to a u8
. If the value cannot be
represented by a u8
, then None
is returned.source§fn to_u16(&self) -> Option<u16>
fn to_u16(&self) -> Option<u16>
self
to a u16
. If the value cannot be
represented by a u16
, then None
is returned.source§fn to_u32(&self) -> Option<u32>
fn to_u32(&self) -> Option<u32>
self
to a u32
. If the value cannot be
represented by a u32
, then None
is returned.source§fn to_u128(&self) -> Option<u128>
fn to_u128(&self) -> Option<u128>
self
to a u128
. If the value cannot be
represented by a u128
(u64
under the default implementation), then
None
is returned. Read moreimpl Copy for MavFrame
impl StructuralPartialEq for MavFrame
Auto Trait Implementations§
impl Freeze for MavFrame
impl RefUnwindSafe for MavFrame
impl Send for MavFrame
impl Sync for MavFrame
impl Unpin for MavFrame
impl UnwindSafe for MavFrame
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
)