Flexiv RDK APIs  1.5.1
utility.hpp
Go to the documentation of this file.
1 
6 #ifndef FLEXIV_RDK_UTILITY_HPP_
7 #define FLEXIV_RDK_UTILITY_HPP_
8 
9 #include "data.hpp"
10 #include <Eigen/Eigen>
11 #include <sstream>
12 
13 namespace flexiv {
14 namespace rdk {
15 namespace utility {
16 
24 inline std::array<double, 3> Quat2EulerZYX(const std::array<double, 4>& quat)
25 {
26  // Form quaternion
27  Eigen::Quaterniond q(quat[0], quat[1], quat[2], quat[3]);
28 
29  // The returned array is in [z,y,x] order
30  auto euler_ZYX = q.toRotationMatrix().eulerAngles(2, 1, 0);
31 
32  // Convert to general [x,y,z] order
33  return (std::array<double, 3> {euler_ZYX[2], euler_ZYX[1], euler_ZYX[0]});
34 }
35 
39 inline double Rad2Deg(double rad)
40 {
41  constexpr double kPi = 3.14159265358979323846;
42  return (rad / kPi * 180.0);
43 }
44 
48 template <size_t N>
49 inline std::array<double, N> Rad2Deg(const std::array<double, N>& rad_arr)
50 {
51  std::array<double, N> deg_arr;
52  for (size_t i = 0; i < N; i++) {
53  deg_arr[i] = Rad2Deg(rad_arr[i]);
54  }
55  return deg_arr;
56 }
57 
65 template <typename T>
66 inline std::string Vec2Str(
67  const std::vector<T>& vec, size_t decimal = 3, const std::string& separator = " ")
68 {
69  std::string padding = "";
70  std::ostringstream oss;
71  oss.precision(decimal);
72  oss << std::fixed;
73 
74  for (const auto& v : vec) {
75  oss << padding << v;
76  padding = separator;
77  }
78  return oss.str();
79 }
80 
88 template <typename T, size_t N>
89 inline std::string Arr2Str(
90  const std::array<T, N>& arr, size_t decimal = 3, const std::string& separator = " ")
91 {
92  std::vector<T> vec(N);
93  std::copy(arr.begin(), arr.end(), vec.begin());
94  return Vec2Str(vec, decimal, separator);
95 }
96 
104 inline std::string FlexivTypes2Str(
105  const rdk::FlexivDataTypes& variant, size_t decimal = 3, const std::string& separator = " ")
106 {
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)) {
112  return *val;
113  } else if (auto* val = std::get_if<rdk::Coord>(&variant)) {
114  return (*val).str();
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)) {
122  std::string ret;
123  // Separate two Coord by " : "
124  for (const auto& v : (*vec)) {
125  ret += v.str() + " : ";
126  }
127  // Remove the trailing " : "
128  if (!ret.empty()) {
129  ret.erase(ret.size() - 3);
130  }
131  return ret;
132  }
133  return "";
134 }
135 
144 inline bool ProgramArgsExistAny(int argc, char** argv, const std::vector<std::string>& ref_strings)
145 {
146  for (int i = 0; i < argc; i++) {
147  for (const auto& v : ref_strings) {
148  if (v == std::string(argv[i])) {
149  return true;
150  }
151  }
152  }
153  return false;
154 }
155 
164 inline bool ProgramArgsExist(int argc, char** argv, const std::string& ref_strings)
165 {
166  return ProgramArgsExistAny(argc, argv, {ref_strings});
167 }
168 
169 } /* namespace utility */
170 } /* namespace rdk */
171 } /* namespace flexiv */
172 
173 #endif /* FLEXIV_RDK_UTILITY_HPP_ */
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
Definition: data.hpp:438
std::array< double, 3 > Quat2EulerZYX(const std::array< double, 4 > &quat)
Convert quaternion to Euler angles with ZYX axis rotations.
Definition: utility.hpp:24
bool ProgramArgsExist(int argc, char **argv, const std::string &ref_strings)
Check if one specific string exists in the program arguments.
Definition: utility.hpp:164
std::string Vec2Str(const std::vector< T > &vec, size_t decimal=3, const std::string &separator=" ")
Convert an std::vector to a string.
Definition: utility.hpp:66
std::string FlexivTypes2Str(const rdk::FlexivDataTypes &variant, size_t decimal=3, const std::string &separator=" ")
Convert the commonly used std::variant to a string.
Definition: utility.hpp:104
double Rad2Deg(double rad)
Convert radians to degrees for a single value.
Definition: utility.hpp:39
bool ProgramArgsExistAny(int argc, char **argv, const std::vector< std::string > &ref_strings)
Check if any provided strings exist in the program arguments.
Definition: utility.hpp:144
std::string Arr2Str(const std::array< T, N > &arr, size_t decimal=3, const std::string &separator=" ")
Convert an std::array to a string.
Definition: utility.hpp:89