19 #ifndef SC_CONVERTER_HPP 20 #define SC_CONVERTER_HPP 22 #include <Eigen/Geometry> 26 Eigen::Vector3d
nedToEnu(Eigen::Vector3d ned);
27 Eigen::Vector3d
enuToNed(Eigen::Vector3d enu);
29 Eigen::Vector3d
frdToFlu(Eigen::Vector3d frd);
30 Eigen::Vector3d
fluToFrd(Eigen::Vector3d flu);
32 Eigen::Quaterniond
frdNedTofluEnu(
const Eigen::Quaterniond& q_frd_to_ned);
33 Eigen::Quaterniond
fluEnuToFrdNed(
const Eigen::Quaterniond& q_flu_to_enu);
37 #endif // SC_CONVERTER_HPP Eigen::Vector3d enuToNed(Eigen::Vector3d enu)
Eigen::Vector3d nedToEnu(Eigen::Vector3d ned)
Eigen::Vector3d frdToFlu(Eigen::Vector3d frd)
Eigen::Vector3d fluToFrd(Eigen::Vector3d flu)
Eigen::Quaterniond frdNedTofluEnu(const Eigen::Quaterniond &q_frd_to_ned)
Eigen::Quaterniond fluEnuToFrdNed(const Eigen::Quaterniond &q_flu_to_enu)