6 #ifndef FLEXIV_RDK_UTILITY_HPP_
7 #define FLEXIV_RDK_UTILITY_HPP_
10 #include <Eigen/Eigen>
24 inline std::array<double, 3>
Quat2EulerZYX(
const std::array<double, 4>& quat)
27 Eigen::Quaterniond q(quat[0], quat[1], quat[2], quat[3]);
30 auto euler_ZYX = q.toRotationMatrix().eulerAngles(2, 1, 0);
33 return (std::array<double, 3> {euler_ZYX[2], euler_ZYX[1], euler_ZYX[0]});
41 constexpr
double kPi = 3.14159265358979323846;
42 return (rad / kPi * 180.0);
49 inline std::array<double, N>
Rad2Deg(
const std::array<double, N>& rad_arr)
51 std::array<double, N> deg_arr;
52 for (
size_t i = 0; i < N; i++) {
53 deg_arr[i] =
Rad2Deg(rad_arr[i]);
67 const std::vector<T>& vec,
size_t decimal = 3,
const std::string& separator =
" ")
69 std::string padding =
"";
70 std::ostringstream oss;
71 oss.precision(decimal);
74 for (
const auto& v : vec) {
88 template <
typename T,
size_t N>
90 const std::array<T, N>& arr,
size_t decimal = 3,
const std::string& separator =
" ")
92 std::vector<T> vec(N);
93 std::copy(arr.begin(), arr.end(), vec.begin());
94 return Vec2Str(vec, decimal, separator);
107 if (
auto* val = std::get_if<int>(&variant)) {
108 return Vec2Str(std::vector<int> {*val}, decimal);
109 }
else if (
auto* val = std::get_if<double>(&variant)) {
110 return Vec2Str(std::vector<double> {*val}, decimal);
111 }
else if (
auto* val = std::get_if<std::string>(&variant)) {
113 }
else if (
auto* val = std::get_if<rdk::Coord>(&variant)) {
115 }
else if (
auto* vec = std::get_if<std::vector<int>>(&variant)) {
116 return Vec2Str(*vec, decimal, separator);
117 }
else if (
auto* vec = std::get_if<std::vector<double>>(&variant)) {
118 return Vec2Str(*vec, decimal, separator);
119 }
else if (
auto* vec = std::get_if<std::vector<std::string>>(&variant)) {
120 return Vec2Str(*vec, decimal, separator);
121 }
else if (
auto* vec = std::get_if<std::vector<rdk::Coord>>(&variant)) {
124 for (
const auto& v : (*vec)) {
125 ret += v.str() +
" : ";
129 ret.erase(ret.size() - 3);
146 for (
int i = 0; i < argc; i++) {
147 for (
const auto& v : ref_strings) {
148 if (v == std::string(argv[i])) {
Header file containing various constant expressions, data structs, and enums.
std::variant< int, double, std::string, rdk::JPos, rdk::Coord, std::vector< int >, std::vector< double >, std::vector< std::string >, std::vector< rdk::JPos >, std::vector< rdk::Coord > > FlexivDataTypes
std::array< double, 3 > Quat2EulerZYX(const std::array< double, 4 > &quat)
Convert quaternion to Euler angles with ZYX axis rotations.
bool ProgramArgsExist(int argc, char **argv, const std::string &ref_strings)
Check if one specific string exists in the program arguments.
std::string Vec2Str(const std::vector< T > &vec, size_t decimal=3, const std::string &separator=" ")
Convert an std::vector to a string.
std::string FlexivTypes2Str(const rdk::FlexivDataTypes &variant, size_t decimal=3, const std::string &separator=" ")
Convert the commonly used std::variant to a string.
double Rad2Deg(double rad)
Convert radians to degrees for a single value.
bool ProgramArgsExistAny(int argc, char **argv, const std::vector< std::string > &ref_strings)
Check if any provided strings exist in the program arguments.
std::string Arr2Str(const std::array< T, N > &arr, size_t decimal=3, const std::string &separator=" ")
Convert an std::array to a string.