cs_converter.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020-2023 RaccoonLab.
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License as published by
6  * the Free Software Foundation, version 3.
7  *
8  * This program is distributed in the hope that it will be useful, but
9  * WITHOUT ANY WARRANTY; without even the implied warranty of
10  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
11  * General Public License for more details.
12  *
13  * You should have received a copy of the GNU General Public License
14  * along with this program. If not, see <http://www.gnu.org/licenses/>.
15  *
16  * Author: Dmitry Ponomarev <ponomarevda96@gmail.com>
17  */
18 
19 
20 #include "cs_converter.hpp"
21 #include <Eigen/Geometry>
22 
23 namespace Converter
24 {
25 
35 const auto Q_ENU_TO_NED = Eigen::Quaterniond(0, 0.70711, 0.70711, 0);
36 
46 const auto Q_FRD_FLU = Eigen::Quaterniond(0, 1, 0, 0);
47 
48 
49 
50 Eigen::Vector3d nedToEnu(Eigen::Vector3d ned){
51  return Q_ENU_TO_NED.inverse() * ned;
52 }
53 Eigen::Vector3d enuToNed(Eigen::Vector3d enu){
54  return Q_ENU_TO_NED * enu;
55 }
56 
57 Eigen::Vector3d frdToFlu(Eigen::Vector3d frd){
58  return Q_FRD_FLU * frd;
59 }
60 Eigen::Vector3d fluToFrd(Eigen::Vector3d flu){
61  return Q_FRD_FLU * flu;
62 }
63 
64 
65 Eigen::Quaterniond frdNedTofluEnu(const Eigen::Quaterniond& q_frd_to_ned){
66  return Q_ENU_TO_NED * q_frd_to_ned * Q_FRD_FLU;
67 }
68 
69 Eigen::Quaterniond fluEnuToFrdNed(const Eigen::Quaterniond& q_flu_to_enu){
70  return Q_ENU_TO_NED.inverse() * q_flu_to_enu * Q_FRD_FLU;
71 }
72 
73 } // namespace Converter
Converter::fluEnuToFrdNed
Eigen::Quaterniond fluEnuToFrdNed(const Eigen::Quaterniond &q_flu_to_enu)
Definition: cs_converter.cpp:69
Converter
Definition: cs_converter.cpp:23
Converter::Q_ENU_TO_NED
const auto Q_ENU_TO_NED
Quaternion for rotation between ENU and NED frames.
Definition: cs_converter.cpp:35
Converter::frdNedTofluEnu
Eigen::Quaterniond frdNedTofluEnu(const Eigen::Quaterniond &q_frd_to_ned)
Definition: cs_converter.cpp:65
Converter::fluToFrd
Eigen::Vector3d fluToFrd(Eigen::Vector3d flu)
Definition: cs_converter.cpp:60
Converter::frdToFlu
Eigen::Vector3d frdToFlu(Eigen::Vector3d frd)
Definition: cs_converter.cpp:57
Converter::Q_FRD_FLU
const auto Q_FRD_FLU
Quaternion for rotation between body FLU and body FRD frames.
Definition: cs_converter.cpp:46
Converter::nedToEnu
Eigen::Vector3d nedToEnu(Eigen::Vector3d ned)
Definition: cs_converter.cpp:50
Converter::enuToNed
Eigen::Vector3d enuToNed(Eigen::Vector3d enu)
Definition: cs_converter.cpp:53
cs_converter.hpp


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