Functions | Variables
Converter Namespace Reference

Functions

Eigen::Vector3d enuToNed (Eigen::Vector3d enu)
 
Eigen::Quaterniond fluEnuToFrdNed (const Eigen::Quaterniond &q_flu_to_enu)
 
Eigen::Vector3d fluToFrd (Eigen::Vector3d flu)
 
Eigen::Quaterniond frdNedTofluEnu (const Eigen::Quaterniond &q_frd_to_ned)
 
Eigen::Vector3d frdToFlu (Eigen::Vector3d frd)
 
Eigen::Vector3d nedToEnu (Eigen::Vector3d ned)
 

Variables

const auto Q_ENU_TO_NED = Eigen::Quaterniond(0, 0.70711, 0.70711, 0)
 Quaternion for rotation between ENU and NED frames. More...
 
const auto Q_FRD_FLU = Eigen::Quaterniond(0, 1, 0, 0)
 Quaternion for rotation between body FLU and body FRD frames. More...
 

Function Documentation

◆ enuToNed()

Eigen::Vector3d Converter::enuToNed ( Eigen::Vector3d  enu)

Definition at line 53 of file cs_converter.cpp.

◆ fluEnuToFrdNed()

Eigen::Quaterniond Converter::fluEnuToFrdNed ( const Eigen::Quaterniond &  q_flu_to_enu)

Definition at line 69 of file cs_converter.cpp.

◆ fluToFrd()

Eigen::Vector3d Converter::fluToFrd ( Eigen::Vector3d  flu)

Definition at line 60 of file cs_converter.cpp.

◆ frdNedTofluEnu()

Eigen::Quaterniond Converter::frdNedTofluEnu ( const Eigen::Quaterniond &  q_frd_to_ned)

Definition at line 65 of file cs_converter.cpp.

◆ frdToFlu()

Eigen::Vector3d Converter::frdToFlu ( Eigen::Vector3d  frd)

Definition at line 57 of file cs_converter.cpp.

◆ nedToEnu()

Eigen::Vector3d Converter::nedToEnu ( Eigen::Vector3d  ned)

Definition at line 50 of file cs_converter.cpp.

Variable Documentation

◆ Q_ENU_TO_NED

const auto Converter::Q_ENU_TO_NED = Eigen::Quaterniond(0, 0.70711, 0.70711, 0)

Quaternion for rotation between ENU and NED frames.

NED to ENU: +PI/2 rotation about Z (Down) followed by a +PI rotation around X (old North/new East) ENU to NED: +PI/2 rotation about Z (Up) followed by a +PI rotation about X (old East/new North)

Note
Example: NED_px4 = Q_ENU_TO_NED * ENU_ros NED_ros = Q_ENU_TO_NED.inverse() * ENU_px4

Definition at line 35 of file cs_converter.cpp.

◆ Q_FRD_FLU

const auto Converter::Q_FRD_FLU = Eigen::Quaterniond(0, 1, 0, 0)

Quaternion for rotation between body FLU and body FRD frames.

+PI rotation around X (Forward) axis rotates from Forward, Right, Down (aircraft) to Forward, Left, Up (base_link) frames and vice-versa.

Note
Example: FRD_px4 = Q_FRD_FLU * FLU_ros FRD_ros = Q_FRD_FLU * FLU_px4

Definition at line 46 of file cs_converter.cpp.



inno_vtol_dynamics
Author(s): Roman Fedorenko, Dmitry Ponomarev, Ezra Tal, Winter Guerra
autogenerated on Mon Dec 9 2024 03:13:35