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]);
 
   61 inline std::vector<double> 
Rad2Deg(
const std::vector<double>& rad_vec)
 
   63     std::vector<double> deg_vec;
 
   64     for (
const auto& v : rad_vec) {
 
   79     const std::vector<T>& vec, 
size_t decimal = 3, 
const std::string& separator = 
" ")
 
   81     std::string padding = 
"";
 
   82     std::ostringstream oss;
 
   83     oss.precision(decimal);
 
   86     for (
const auto& v : vec) {
 
  100 template <
typename T, 
size_t N>
 
  102     const std::array<T, N>& arr, 
size_t decimal = 3, 
const std::string& separator = 
" ")
 
  104     std::vector<T> vec(N);
 
  105     std::copy(arr.begin(), arr.end(), vec.begin());
 
  106     return Vec2Str(vec, decimal, separator);
 
  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)) {
 
  125     } 
else if (
auto* val = std::get_if<rdk::Coord>(&variant)) {
 
  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)) {
 
  136         for (
const auto& v : (*vec)) {
 
  137             ret += v.str() + 
" : ";
 
  141             ret.erase(ret.size() - 3);
 
  158     for (
int i = 0; i < argc; i++) {
 
  159         for (
const auto& v : ref_strings) {
 
  160             if (v == std::string(argv[i])) {
 
Header file containing various constant expressions, data structures, 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.