Struct DistanceSensor

Source
pub struct DistanceSensor {
    pub time_boot_ms: u32,
    pub min_distance: u16,
    pub max_distance: u16,
    pub current_distance: u16,
    pub type_: MavDistanceSensor,
    pub id: u8,
    pub orientation: MavSensorOrientation,
    pub covariance: u8,
    pub horizontal_fov: f32,
    pub vertical_fov: f32,
    pub quaternion: [f32; 4],
    pub signal_quality: u8,
}
Expand description

MAVLink DISTANCE_SENSOR message.

Minimum supported MAVLink version is MAVLink 1.

§Description

Distance sensor information for an onboard rangefinder.

§Encoding/Decoding

Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for DistanceSensor (encoding) and [IntoPayload] (decoding) traits. These traits are implemented by Message proc macro.

Fields§

§time_boot_ms: u32

MAVLink field time_boot_ms.

Timestamp (time since system boot).

§min_distance: u16

MAVLink field min_distance.

Minimum distance the sensor can measure

§max_distance: u16

MAVLink field max_distance.

Maximum distance the sensor can measure

§current_distance: u16

MAVLink field current_distance.

Current distance reading

§type_: MavDistanceSensor

MAVLink field type.

Type of distance sensor.

§id: u8

MAVLink field id.

Onboard ID of the sensor

§orientation: MavSensorOrientation

MAVLink field orientation.

Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270

§covariance: u8

MAVLink field covariance.

Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.

§horizontal_fov: f32

MAVLink field horizontal_fov.

Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.

§vertical_fov: f32

MAVLink field vertical_fov.

Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.

§quaternion: [f32; 4]

MAVLink field quaternion.

Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid.“

§signal_quality: u8

MAVLink field signal_quality.

Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.

Implementations§

Source§

impl DistanceSensor

Source

pub const ID: MessageId = 132u32

MavLink message ID.

Source

pub const fn spec() -> MessageInfo

Returns specification for this message.

Source

pub const fn message_id() -> MessageId

Message ID.

Source

pub const fn crc_extra() -> CrcExtra

Message CRC_EXTRA.

Minimum supported MAVLink version for this message.

Trait Implementations§

Source§

impl Clone for DistanceSensor

Source§

fn clone(&self) -> DistanceSensor

Returns a copy of the value. Read more
1.0.0 · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl Debug for DistanceSensor

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl Default for DistanceSensor

Source§

fn default() -> Self

Returns the “default value” for a type. Read more
Source§

impl<'de> Deserialize<'de> for DistanceSensor

Source§

fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>
where __D: Deserializer<'de>,

Deserialize this value from the given Serde deserializer. Read more
Source§

impl From<DistanceSensor> for Common

Source§

fn from(value: DistanceSensor) -> Self

Converts to this type from the input type.
Source§

impl IntoPayload for DistanceSensor

Source§

fn encode(&self, version: MavLinkVersion) -> Result<Payload, SpecError>

Encodes message into MAVLink payload. Read more
Source§

impl MessageSpec for DistanceSensor

Source§

fn id(&self) -> MessageId

MAVLink message ID. Read more
Minimum supported MAVLink protocol version. Read more
Source§

fn crc_extra(&self) -> CrcExtra

Message EXTRA_CRC calculated from message XML definition. Read more
Source§

impl MessageSpecStatic for DistanceSensor

Source§

fn spec() -> MessageInfo

Returns specification for this message.
Source§

fn message_id() -> MessageId

Message ID.
Source§

fn crc_extra() -> CrcExtra

Message CRC_EXTRA.
Minimum supported MAVLink version for this message.
Source§

impl NamedType for DistanceSensor

Source§

fn sid() -> SpectaID

Source§

fn named_data_type( type_map: &mut TypeCollection, generics: &[DataType], ) -> NamedDataType

this is equivalent to Type::inline but returns a NamedDataType instead.
Source§

fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType

this is equivalent to [Type::definition] but returns a NamedDataType instead.
Source§

impl PartialEq for DistanceSensor

Source§

fn eq(&self, other: &DistanceSensor) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 · Source§

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Source§

impl Serialize for DistanceSensor

Source§

fn serialize<__S>(&self, __serializer: __S) -> Result<__S::Ok, __S::Error>
where __S: Serializer,

Serialize this value into the given Serde serializer. Read more
Source§

impl TryFrom<&Payload> for DistanceSensor

Source§

type Error = SpecError

The type returned in the event of a conversion error.
Source§

fn try_from(value: &Payload) -> Result<Self, Self::Error>

Performs the conversion.
Source§

impl Type for DistanceSensor

Source§

fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType

Returns the definition of a type using the provided generics. Read more
Source§

fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference

Generates a datatype corresponding to a reference to this type, as determined by its category. Getting a reference to a type implies that it should belong in the type map (since it has to be referenced from somewhere), so the output of definition will be put into the type map.
Source§

impl Flatten for DistanceSensor

Source§

impl Message for DistanceSensor

Source§

impl StructuralPartialEq for DistanceSensor

Auto Trait Implementations§

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dst: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dst. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Source§

impl<T> DeserializeOwned for T
where T: for<'de> Deserialize<'de>,