SENSOR_OFFSETS_DATA

Struct SENSOR_OFFSETS_DATA 

Source
pub struct SENSOR_OFFSETS_DATA {
    pub mag_declination: f32,
    pub raw_press: i32,
    pub raw_temp: i32,
    pub gyro_cal_x: f32,
    pub gyro_cal_y: f32,
    pub gyro_cal_z: f32,
    pub accel_cal_x: f32,
    pub accel_cal_y: f32,
    pub accel_cal_z: f32,
    pub mag_ofs_x: i16,
    pub mag_ofs_y: i16,
    pub mag_ofs_z: i16,
}
๐Ÿ‘ŽDeprecated: See MAG_CAL_REPORT, Accel Parameters, and Gyro Parameters (Deprecated since 2022-02)
Available on crate feature ardupilotmega only.
Expand description

id: 150 Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process.

Fieldsยง

ยงmag_declination: f32
๐Ÿ‘ŽDeprecated: See MAG_CAL_REPORT, Accel Parameters, and Gyro Parameters (Deprecated since 2022-02)

Magnetic declination.

ยงraw_press: i32
๐Ÿ‘ŽDeprecated: See MAG_CAL_REPORT, Accel Parameters, and Gyro Parameters (Deprecated since 2022-02)

Raw pressure from barometer.

ยงraw_temp: i32
๐Ÿ‘ŽDeprecated: See MAG_CAL_REPORT, Accel Parameters, and Gyro Parameters (Deprecated since 2022-02)

Raw temperature from barometer.

ยงgyro_cal_x: f32
๐Ÿ‘ŽDeprecated: See MAG_CAL_REPORT, Accel Parameters, and Gyro Parameters (Deprecated since 2022-02)

Gyro X calibration.

ยงgyro_cal_y: f32
๐Ÿ‘ŽDeprecated: See MAG_CAL_REPORT, Accel Parameters, and Gyro Parameters (Deprecated since 2022-02)

Gyro Y calibration.

ยงgyro_cal_z: f32
๐Ÿ‘ŽDeprecated: See MAG_CAL_REPORT, Accel Parameters, and Gyro Parameters (Deprecated since 2022-02)

Gyro Z calibration.

ยงaccel_cal_x: f32
๐Ÿ‘ŽDeprecated: See MAG_CAL_REPORT, Accel Parameters, and Gyro Parameters (Deprecated since 2022-02)

Accel X calibration.

ยงaccel_cal_y: f32
๐Ÿ‘ŽDeprecated: See MAG_CAL_REPORT, Accel Parameters, and Gyro Parameters (Deprecated since 2022-02)

Accel Y calibration.

ยงaccel_cal_z: f32
๐Ÿ‘ŽDeprecated: See MAG_CAL_REPORT, Accel Parameters, and Gyro Parameters (Deprecated since 2022-02)

Accel Z calibration.

ยงmag_ofs_x: i16
๐Ÿ‘ŽDeprecated: See MAG_CAL_REPORT, Accel Parameters, and Gyro Parameters (Deprecated since 2022-02)

Magnetometer X offset.

ยงmag_ofs_y: i16
๐Ÿ‘ŽDeprecated: See MAG_CAL_REPORT, Accel Parameters, and Gyro Parameters (Deprecated since 2022-02)

Magnetometer Y offset.

ยงmag_ofs_z: i16
๐Ÿ‘ŽDeprecated: See MAG_CAL_REPORT, Accel Parameters, and Gyro Parameters (Deprecated since 2022-02)

Magnetometer Z offset.

Implementationsยง

Trait Implementationsยง

Sourceยง

impl Clone for SENSOR_OFFSETS_DATA

Sourceยง

fn clone(&self) -> SENSOR_OFFSETS_DATA

Returns a duplicate 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 SENSOR_OFFSETS_DATA

Sourceยง

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

Formats the value using the given formatter. Read more
Sourceยง

impl Default for SENSOR_OFFSETS_DATA

Sourceยง

fn default() -> Self

Returns the โ€œdefault valueโ€ for a type. Read more
Sourceยง

impl<'de> Deserialize<'de> for SENSOR_OFFSETS_DATA

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 MessageData for SENSOR_OFFSETS_DATA

Sourceยง

const ID: u32 = 150u32

Sourceยง

const NAME: &'static str = "SENSOR_OFFSETS"

Sourceยง

const EXTRA_CRC: u8 = 134u8

Sourceยง

const ENCODED_LEN: usize = 42usize

Sourceยง

type Message = MavMessage

Sourceยง

fn deser(_version: MavlinkVersion, __input: &[u8]) -> Result<Self, ParserError>

Sourceยง

fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize

Sourceยง

impl PartialEq for SENSOR_OFFSETS_DATA

Sourceยง

fn eq(&self, other: &SENSOR_OFFSETS_DATA) -> 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 SENSOR_OFFSETS_DATA

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 StructuralPartialEq for SENSOR_OFFSETS_DATA

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, dest: *mut u8)

๐Ÿ”ฌThis is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. 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> Same for T

Sourceยง

type Output = T

Should always be Self
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>,