Flexiv RDK APIs  1.6.0
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 
61 inline std::vector<double> Rad2Deg(const std::vector<double>& rad_vec)
62 {
63  std::vector<double> deg_vec;
64  for (const auto& v : rad_vec) {
65  deg_vec.push_back(Rad2Deg(v));
66  }
67  return deg_vec;
68 }
69 
77 template <typename T>
78 inline std::string Vec2Str(
79  const std::vector<T>& vec, size_t decimal = 3, const std::string& separator = " ")
80 {
81  std::string padding = "";
82  std::ostringstream oss;
83  oss.precision(decimal);
84  oss << std::fixed;
85 
86  for (const auto& v : vec) {
87  oss << padding << v;
88  padding = separator;
89  }
90  return oss.str();
91 }
92 
100 template <typename T, size_t N>
101 inline std::string Arr2Str(
102  const std::array<T, N>& arr, size_t decimal = 3, const std::string& separator = " ")
103 {
104  std::vector<T> vec(N);
105  std::copy(arr.begin(), arr.end(), vec.begin());
106  return Vec2Str(vec, decimal, separator);
107 }
108 
116 inline std::string FlexivTypes2Str(
117  const rdk::FlexivDataTypes& variant, size_t decimal = 3, const std::string& separator = " ")
118 {
119  if (auto* val = std::get_if<int>(&variant)) {
120  return Vec2Str(std::vector<int> {*val}, decimal);
121  } else if (auto* val = std::get_if<double>(&variant)) {
122  return Vec2Str(std::vector<double> {*val}, decimal);
123  } else if (auto* val = std::get_if<std::string>(&variant)) {
124  return *val;
125  } else if (auto* val = std::get_if<rdk::Coord>(&variant)) {
126  return (*val).str();
127  } else if (auto* vec = std::get_if<std::vector<int>>(&variant)) {
128  return Vec2Str(*vec, decimal, separator);
129  } else if (auto* vec = std::get_if<std::vector<double>>(&variant)) {
130  return Vec2Str(*vec, decimal, separator);
131  } else if (auto* vec = std::get_if<std::vector<std::string>>(&variant)) {
132  return Vec2Str(*vec, decimal, separator);
133  } else if (auto* vec = std::get_if<std::vector<rdk::Coord>>(&variant)) {
134  std::string ret;
135  // Separate two Coord by " : "
136  for (const auto& v : (*vec)) {
137  ret += v.str() + " : ";
138  }
139  // Remove the trailing " : "
140  if (!ret.empty()) {
141  ret.erase(ret.size() - 3);
142  }
143  return ret;
144  }
145  return "";
146 }
147 
156 inline bool ProgramArgsExistAny(int argc, char** argv, const std::vector<std::string>& ref_strings)
157 {
158  for (int i = 0; i < argc; i++) {
159  for (const auto& v : ref_strings) {
160  if (v == std::string(argv[i])) {
161  return true;
162  }
163  }
164  }
165  return false;
166 }
167 
176 inline bool ProgramArgsExist(int argc, char** argv, const std::string& ref_strings)
177 {
178  return ProgramArgsExistAny(argc, argv, {ref_strings});
179 }
180 
181 } /* namespace utility */
182 } /* namespace rdk */
183 } /* namespace flexiv */
184 
185 #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:391
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:176
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:78
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:116
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:156
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:101