Struct sbp::messages::orientation::MsgOrientEuler [−][src]
pub struct MsgOrientEuler {
pub sender_id: Option<u16>,
pub tow: u32,
pub roll: i32,
pub pitch: i32,
pub yaw: i32,
pub roll_accuracy: f32,
pub pitch_accuracy: f32,
pub yaw_accuracy: f32,
pub flags: u8,
}
Expand description
Euler angles
This message reports the yaw, pitch, and roll angles of the vehicle body frame. The rotations should applied intrinsically in the order yaw, pitch, and roll in order to rotate the from a frame aligned with the local-level NED frame to the vehicle body frame. This message will only be available in future INS versions of Swift Products and is not produced by Piksi Multi or Duro.
Fields
sender_id: Option<u16>
The message sender_id
tow: u32
GPS Time of Week
roll: i32
rotation about the forward axis of the vehicle
pitch: i32
rotation about the rightward axis of the vehicle
yaw: i32
rotation about the downward axis of the vehicle
roll_accuracy: f32
Estimated standard deviation of roll
pitch_accuracy: f32
Estimated standard deviation of pitch
yaw_accuracy: f32
Estimated standard deviation of yaw
flags: u8
Status flags
Trait Implementations
The message type.
The message name.
Performs the conversion.
Get the message name.
Get the message type.
Set the sender id.
Number of bytes this message will take on the wire.
Auto Trait Implementations
impl RefUnwindSafe for MsgOrientEuler
impl Send for MsgOrientEuler
impl Sync for MsgOrientEuler
impl Unpin for MsgOrientEuler
impl UnwindSafe for MsgOrientEuler
Blanket Implementations
Mutably borrows from an owned value. Read more