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.
The 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: u32MAVLink field time_boot_ms.
Timestamp (time since system boot).
min_distance: u16MAVLink field min_distance.
Minimum distance the sensor can measure
max_distance: u16MAVLink field max_distance.
Maximum distance the sensor can measure
current_distance: u16MAVLink field current_distance.
Current distance reading
type_: MavDistanceSensorMAVLink field type.
Type of distance sensor.
id: u8MAVLink field id.
Onboard ID of the sensor
orientation: MavSensorOrientationMAVLink 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: u8MAVLink field covariance.
Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.
horizontal_fov: f32MAVLink 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: f32MAVLink 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: u8MAVLink 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
impl DistanceSensor
Sourcepub const fn spec() -> MessageInfo
pub const fn spec() -> MessageInfo
Returns specification for this message.
Sourcepub const fn message_id() -> MessageId
pub const fn message_id() -> MessageId
Message ID.
Sourcepub const fn min_supported_mavlink_version() -> MavLinkVersion
pub const fn min_supported_mavlink_version() -> MavLinkVersion
Minimum supported MAVLink version for this message.
Trait Implementations§
Source§impl Clone for DistanceSensor
impl Clone for DistanceSensor
Source§fn clone(&self) -> DistanceSensor
fn clone(&self) -> DistanceSensor
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for DistanceSensor
impl Debug for DistanceSensor
Source§impl Default for DistanceSensor
impl Default for DistanceSensor
Source§impl<'de> Deserialize<'de> for DistanceSensor
impl<'de> Deserialize<'de> for DistanceSensor
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<DistanceSensor> for Common
impl From<DistanceSensor> for Common
Source§fn from(value: DistanceSensor) -> Self
fn from(value: DistanceSensor) -> Self
Source§impl IntoPayload for DistanceSensor
impl IntoPayload for DistanceSensor
Source§impl MessageSpec for DistanceSensor
impl MessageSpec for DistanceSensor
Source§impl MessageSpecStatic for DistanceSensor
impl MessageSpecStatic for DistanceSensor
Source§fn spec() -> MessageInfo
fn spec() -> MessageInfo
Source§fn message_id() -> MessageId
fn message_id() -> MessageId
ID.Source§fn min_supported_mavlink_version() -> MavLinkVersion
fn min_supported_mavlink_version() -> MavLinkVersion
Source§impl NamedType for DistanceSensor
impl NamedType for DistanceSensor
fn sid() -> SpectaID
Source§fn named_data_type(
type_map: &mut TypeCollection,
generics: &[DataType],
) -> NamedDataType
fn named_data_type( type_map: &mut TypeCollection, generics: &[DataType], ) -> NamedDataType
Source§fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
Source§impl PartialEq for DistanceSensor
impl PartialEq for DistanceSensor
Source§impl Serialize for DistanceSensor
impl Serialize for DistanceSensor
Source§impl TryFrom<&Payload> for DistanceSensor
impl TryFrom<&Payload> for DistanceSensor
Source§impl Type for DistanceSensor
impl Type for DistanceSensor
Source§fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
Source§fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
definition will be put into the type map.