Struct mavlink::common::MavSysStatusSensor
source · pub struct MavSysStatusSensor { /* private fields */ }
common
only.Expand description
These encode the sensors whose status is sent as part of the SYS_STATUS message.
Implementations§
source§impl MavSysStatusSensor
impl MavSysStatusSensor
sourcepub const MAV_SYS_STATUS_SENSOR_3D_GYRO: Self = _
pub const MAV_SYS_STATUS_SENSOR_3D_GYRO: Self = _
0x01 3D gyro
sourcepub const MAV_SYS_STATUS_SENSOR_3D_ACCEL: Self = _
pub const MAV_SYS_STATUS_SENSOR_3D_ACCEL: Self = _
0x02 3D accelerometer
sourcepub const MAV_SYS_STATUS_SENSOR_3D_MAG: Self = _
pub const MAV_SYS_STATUS_SENSOR_3D_MAG: Self = _
0x04 3D magnetometer
sourcepub const MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE: Self = _
pub const MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE: Self = _
0x08 absolute pressure
sourcepub const MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE: Self = _
pub const MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE: Self = _
0x10 differential pressure
sourcepub const MAV_SYS_STATUS_SENSOR_GPS: Self = _
pub const MAV_SYS_STATUS_SENSOR_GPS: Self = _
0x20 GPS
sourcepub const MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW: Self = _
pub const MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW: Self = _
0x40 optical flow
sourcepub const MAV_SYS_STATUS_SENSOR_VISION_POSITION: Self = _
pub const MAV_SYS_STATUS_SENSOR_VISION_POSITION: Self = _
0x80 computer vision position
sourcepub const MAV_SYS_STATUS_SENSOR_LASER_POSITION: Self = _
pub const MAV_SYS_STATUS_SENSOR_LASER_POSITION: Self = _
0x100 laser based position
sourcepub const MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH: Self = _
pub const MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH: Self = _
0x200 external ground truth (Vicon or Leica)
sourcepub const MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL: Self = _
pub const MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL: Self = _
0x400 3D angular rate control
sourcepub const MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION: Self = _
pub const MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION: Self = _
0x800 attitude stabilization
sourcepub const MAV_SYS_STATUS_SENSOR_YAW_POSITION: Self = _
pub const MAV_SYS_STATUS_SENSOR_YAW_POSITION: Self = _
0x1000 yaw position
sourcepub const MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL: Self = _
pub const MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL: Self = _
0x2000 z/altitude control
sourcepub const MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL: Self = _
pub const MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL: Self = _
0x4000 x/y position control
sourcepub const MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS: Self = _
pub const MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS: Self = _
0x8000 motor outputs / control
sourcepub const MAV_SYS_STATUS_SENSOR_RC_RECEIVER: Self = _
pub const MAV_SYS_STATUS_SENSOR_RC_RECEIVER: Self = _
0x10000 rc receiver
sourcepub const MAV_SYS_STATUS_SENSOR_3D_GYRO2: Self = _
pub const MAV_SYS_STATUS_SENSOR_3D_GYRO2: Self = _
0x20000 2nd 3D gyro
sourcepub const MAV_SYS_STATUS_SENSOR_3D_ACCEL2: Self = _
pub const MAV_SYS_STATUS_SENSOR_3D_ACCEL2: Self = _
0x40000 2nd 3D accelerometer
sourcepub const MAV_SYS_STATUS_SENSOR_3D_MAG2: Self = _
pub const MAV_SYS_STATUS_SENSOR_3D_MAG2: Self = _
0x80000 2nd 3D magnetometer
sourcepub const MAV_SYS_STATUS_GEOFENCE: Self = _
pub const MAV_SYS_STATUS_GEOFENCE: Self = _
0x100000 geofence
sourcepub const MAV_SYS_STATUS_AHRS: Self = _
pub const MAV_SYS_STATUS_AHRS: Self = _
0x200000 AHRS subsystem health
sourcepub const MAV_SYS_STATUS_TERRAIN: Self = _
pub const MAV_SYS_STATUS_TERRAIN: Self = _
0x400000 Terrain subsystem health
sourcepub const MAV_SYS_STATUS_REVERSE_MOTOR: Self = _
pub const MAV_SYS_STATUS_REVERSE_MOTOR: Self = _
0x800000 Motors are reversed
sourcepub const MAV_SYS_STATUS_LOGGING: Self = _
pub const MAV_SYS_STATUS_LOGGING: Self = _
0x1000000 Logging
sourcepub const MAV_SYS_STATUS_SENSOR_BATTERY: Self = _
pub const MAV_SYS_STATUS_SENSOR_BATTERY: Self = _
0x2000000 Battery
sourcepub const MAV_SYS_STATUS_SENSOR_PROXIMITY: Self = _
pub const MAV_SYS_STATUS_SENSOR_PROXIMITY: Self = _
0x4000000 Proximity
sourcepub const MAV_SYS_STATUS_SENSOR_SATCOM: Self = _
pub const MAV_SYS_STATUS_SENSOR_SATCOM: Self = _
0x8000000 Satellite Communication
sourcepub const MAV_SYS_STATUS_PREARM_CHECK: Self = _
pub const MAV_SYS_STATUS_PREARM_CHECK: Self = _
0x10000000 pre-arm check status. Always healthy when armed
sourcepub const MAV_SYS_STATUS_OBSTACLE_AVOIDANCE: Self = _
pub const MAV_SYS_STATUS_OBSTACLE_AVOIDANCE: Self = _
0x20000000 Avoidance/collision prevention
sourcepub const MAV_SYS_STATUS_SENSOR_PROPULSION: Self = _
pub const MAV_SYS_STATUS_SENSOR_PROPULSION: Self = _
0x40000000 propulsion (actuator, esc, motor or propellor)
sourcepub const MAV_SYS_STATUS_EXTENSION_USED: Self = _
pub const MAV_SYS_STATUS_EXTENSION_USED: Self = _
0x80000000 Extended bit-field are used for further sensor status bits (needs to be set in onboard_control_sensors_present only)
sourcepub const fn from_bits(bits: u32) -> Option<Self>
pub const fn from_bits(bits: u32) -> Option<Self>
Convert from underlying bit representation, unless that representation contains bits that do not correspond to a flag.
sourcepub const fn from_bits_truncate(bits: u32) -> Self
pub const fn from_bits_truncate(bits: u32) -> Self
Convert from underlying bit representation, dropping any bits that do not correspond to flags.
sourcepub const unsafe fn from_bits_unchecked(bits: u32) -> Self
pub const unsafe fn from_bits_unchecked(bits: u32) -> Self
Convert from underlying bit representation, preserving all bits (even those not corresponding to a defined flag).
§Safety
The caller of the bitflags!
macro can chose to allow or
disallow extra bits for their bitflags type.
The caller of from_bits_unchecked()
has to ensure that
all bits correspond to a defined flag or that extra bits
are valid for this bitflags type.
sourcepub const fn intersects(&self, other: Self) -> bool
pub const fn intersects(&self, other: Self) -> bool
Returns true
if there are flags common to both self
and other
.
sourcepub const fn contains(&self, other: Self) -> bool
pub const fn contains(&self, other: Self) -> bool
Returns true
if all of the flags in other
are contained within self
.
sourcepub fn set(&mut self, other: Self, value: bool)
pub fn set(&mut self, other: Self, value: bool)
Inserts or removes the specified flags depending on the passed value.
sourcepub const fn intersection(self, other: Self) -> Self
pub const fn intersection(self, other: Self) -> Self
Returns the intersection between the flags in self
and
other
.
Specifically, the returned set contains only the flags which are
present in both self
and other
.
This is equivalent to using the &
operator (e.g.
ops::BitAnd
), as in flags & other
.
sourcepub const fn union(self, other: Self) -> Self
pub const fn union(self, other: Self) -> Self
Returns the union of between the flags in self
and other
.
Specifically, the returned set contains all flags which are
present in either self
or other
, including any which are
present in both (see Self::symmetric_difference
if that
is undesirable).
This is equivalent to using the |
operator (e.g.
ops::BitOr
), as in flags | other
.
sourcepub const fn difference(self, other: Self) -> Self
pub const fn difference(self, other: Self) -> Self
Returns the difference between the flags in self
and other
.
Specifically, the returned set contains all flags present in
self
, except for the ones present in other
.
It is also conceptually equivalent to the “bit-clear” operation:
flags & !other
(and this syntax is also supported).
This is equivalent to using the -
operator (e.g.
ops::Sub
), as in flags - other
.
sourcepub const fn symmetric_difference(self, other: Self) -> Self
pub const fn symmetric_difference(self, other: Self) -> Self
Returns the symmetric difference between the flags
in self
and other
.
Specifically, the returned set contains the flags present which
are present in self
or other
, but that are not present in
both. Equivalently, it contains the flags present in exactly
one of the sets self
and other
.
This is equivalent to using the ^
operator (e.g.
ops::BitXor
), as in flags ^ other
.
sourcepub const fn complement(self) -> Self
pub const fn complement(self) -> Self
Returns the complement of this set of flags.
Specifically, the returned set contains all the flags which are
not set in self
, but which are allowed for this type.
Alternatively, it can be thought of as the set difference
between Self::all()
and self
(e.g. Self::all() - self
)
This is equivalent to using the !
operator (e.g.
ops::Not
), as in !flags
.
Trait Implementations§
source§impl Binary for MavSysStatusSensor
impl Binary for MavSysStatusSensor
source§impl BitAnd for MavSysStatusSensor
impl BitAnd for MavSysStatusSensor
source§impl BitAndAssign for MavSysStatusSensor
impl BitAndAssign for MavSysStatusSensor
source§fn bitand_assign(&mut self, other: Self)
fn bitand_assign(&mut self, other: Self)
Disables all flags disabled in the set.
source§impl BitOr for MavSysStatusSensor
impl BitOr for MavSysStatusSensor
source§fn bitor(self, other: MavSysStatusSensor) -> Self
fn bitor(self, other: MavSysStatusSensor) -> Self
Returns the union of the two sets of flags.
source§type Output = MavSysStatusSensor
type Output = MavSysStatusSensor
|
operator.source§impl BitOrAssign for MavSysStatusSensor
impl BitOrAssign for MavSysStatusSensor
source§fn bitor_assign(&mut self, other: Self)
fn bitor_assign(&mut self, other: Self)
Adds the set of flags.
source§impl BitXor for MavSysStatusSensor
impl BitXor for MavSysStatusSensor
source§impl BitXorAssign for MavSysStatusSensor
impl BitXorAssign for MavSysStatusSensor
source§fn bitxor_assign(&mut self, other: Self)
fn bitxor_assign(&mut self, other: Self)
Toggles the set of flags.
source§impl Clone for MavSysStatusSensor
impl Clone for MavSysStatusSensor
source§fn clone(&self) -> MavSysStatusSensor
fn clone(&self) -> MavSysStatusSensor
1.0.0 · source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read moresource§impl Debug for MavSysStatusSensor
impl Debug for MavSysStatusSensor
source§impl Default for MavSysStatusSensor
impl Default for MavSysStatusSensor
source§impl<'de> Deserialize<'de> for MavSysStatusSensor
impl<'de> Deserialize<'de> for MavSysStatusSensor
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 Extend<MavSysStatusSensor> for MavSysStatusSensor
impl Extend<MavSysStatusSensor> for MavSysStatusSensor
source§fn extend<T: IntoIterator<Item = Self>>(&mut self, iterator: T)
fn extend<T: IntoIterator<Item = Self>>(&mut self, iterator: T)
source§fn extend_one(&mut self, item: A)
fn extend_one(&mut self, item: A)
extend_one
)source§fn extend_reserve(&mut self, additional: usize)
fn extend_reserve(&mut self, additional: usize)
extend_one
)source§impl FromIterator<MavSysStatusSensor> for MavSysStatusSensor
impl FromIterator<MavSysStatusSensor> for MavSysStatusSensor
source§fn from_iter<T: IntoIterator<Item = Self>>(iterator: T) -> Self
fn from_iter<T: IntoIterator<Item = Self>>(iterator: T) -> Self
source§impl Hash for MavSysStatusSensor
impl Hash for MavSysStatusSensor
source§impl LowerHex for MavSysStatusSensor
impl LowerHex for MavSysStatusSensor
source§impl Not for MavSysStatusSensor
impl Not for MavSysStatusSensor
source§impl Octal for MavSysStatusSensor
impl Octal for MavSysStatusSensor
source§impl Ord for MavSysStatusSensor
impl Ord for MavSysStatusSensor
source§fn cmp(&self, other: &MavSysStatusSensor) -> Ordering
fn cmp(&self, other: &MavSysStatusSensor) -> Ordering
1.21.0 · source§fn max(self, other: Self) -> Selfwhere
Self: Sized,
fn max(self, other: Self) -> Selfwhere
Self: Sized,
source§impl PartialEq for MavSysStatusSensor
impl PartialEq for MavSysStatusSensor
source§impl PartialOrd for MavSysStatusSensor
impl PartialOrd for MavSysStatusSensor
source§impl Serialize for MavSysStatusSensor
impl Serialize for MavSysStatusSensor
source§impl Sub for MavSysStatusSensor
impl Sub for MavSysStatusSensor
source§impl SubAssign for MavSysStatusSensor
impl SubAssign for MavSysStatusSensor
source§fn sub_assign(&mut self, other: Self)
fn sub_assign(&mut self, other: Self)
Disables all flags enabled in the set.
source§impl UpperHex for MavSysStatusSensor
impl UpperHex for MavSysStatusSensor
impl Copy for MavSysStatusSensor
impl Eq for MavSysStatusSensor
impl StructuralPartialEq for MavSysStatusSensor
Auto Trait Implementations§
impl Freeze for MavSysStatusSensor
impl RefUnwindSafe for MavSysStatusSensor
impl Send for MavSysStatusSensor
impl Sync for MavSysStatusSensor
impl Unpin for MavSysStatusSensor
impl UnwindSafe for MavSysStatusSensor
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
)