maliput::math

Struct RollPitchYaw

Source
pub struct RollPitchYaw { /* private fields */ }
Expand description

This class represents the orientation between two arbitrary frames A and D associated with a Space-fixed (extrinsic) X-Y-Z rotation by “roll-pitch-yaw” angles [r, p, y], which is equivalent to a Body-fixed (intrinsic) Z-Y-X rotation by “yaw-pitch-roll” angles [y, p, r]. The rotation matrix R_AD associated with this roll-pitch-yaw [r, p, y] rotation sequence is equal to the matrix multiplication shown below.

       ⎡cos(y) -sin(y)  0⎤   ⎡ cos(p)  0  sin(p)⎤   ⎡1      0        0 ⎤
R_AD = ⎢sin(y)  cos(y)  0⎥ * ⎢     0   1      0 ⎥ * ⎢0  cos(r)  -sin(r)⎥
       ⎣    0       0   1⎦   ⎣-sin(p)  0  cos(p)⎦   ⎣0  sin(r)   cos(r)⎦
     =       R_AB          *        R_BC          *        R_CD

Wrapper of C++ implementation maliput::math::RollPitchYaw.

Implementations§

Source§

impl RollPitchYaw

Source

pub fn new(roll: f64, pitch: f64, yaw: f64) -> RollPitchYaw

Create a new RollPitchYaw with the given roll, pitch, and yaw angles.

Source

pub fn roll_angle(&self) -> f64

Get the roll angle of the RollPitchYaw.

Source

pub fn pitch_angle(&self) -> f64

Get the pitch angle of the RollPitchYaw.

Source

pub fn yaw_angle(&self) -> f64

Get the yaw angle of the RollPitchYaw.

Source

pub fn vector(&self) -> Vector3

Get the vector of the RollPitchYaw.

Source

pub fn set(&mut self, roll: f64, pitch: f64, yaw: f64)

Set the RollPitchYaw with the given roll, pitch, and yaw angles.

Source

pub fn set_from_quaternion(&mut self, q: &Quaternion)

Set the RollPitchYaw from the given Quaternion.

Source

pub fn to_quaternion(&self) -> Quaternion

Get the Quaternion representation of the RollPitchYaw.

Source

pub fn to_matrix(&self) -> Matrix3

Get the rotation matrix representation of the RollPitchYaw.

Source

pub fn calc_rotation_matrix_dt(&self, rpy_dt: &Vector3) -> Matrix3

Get the rotation matrix representation of the RollPitchYaw with the given rpy_dt.

§Description

Forms Ṙ, the ordinary derivative of the RotationMatrix R with respect to an independent variable t (t usually denotes time) and R is the RotationMatrix formed by this RollPitchYaw. The roll-pitch-yaw angles r, p, y are regarded as functions of t [i.e., r(t), p(t), y(t)]. The param rpy_dt Ordinary derivative of rpy with respect to an independent variable t (t usually denotes time, but not necessarily). Returns Ṙ``, the ordinary derivative of Rwith respect tot, calculated as Ṙ = ∂R/∂r * ṙ + ∂R/∂p * ṗ + ∂R/∂y * ẏ. In other words, the returned (i, j) element is ∂Rij/∂r * ṙ + ∂Rij/∂p * ṗ + ∂Rij/∂y * ẏ``.

Note: Docs are taken from the C++ implementation.

§Args
  • rpy_dt Ordinary derivative of rpy with respect to an independent variable t.
§Returns

Ordinary derivative of the RotationMatrix R with respect to an independent variable t.

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> 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, 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.