Flexiv RDK APIs
1.4
|
#include <Eigen/Eigen>
#include <array>
Go to the source code of this file.
Functions | |
std::array< double, 3 > | flexiv::rdk::utility::Quat2EulerZYX (const std::array< double, 4 > &quat) |
Convert quaternion to Euler angles with ZYX axis rotations. More... | |
double | flexiv::rdk::utility::Rad2Deg (double rad) |
Convert radians to degrees for a single value. | |
template<size_t N> | |
std::array< double, N > | flexiv::rdk::utility::Rad2Deg (const std::array< double, N > &rad_arr) |
Convert radians to degrees for an array. | |
template<typename T > | |
std::string | flexiv::rdk::utility::Vec2Str (const std::vector< T > &vec, size_t decimal=3, bool trailing_space=true, const std::string &separator=" ") |
Convert an std::vector to a string. More... | |
template<typename T , size_t N> | |
std::string | flexiv::rdk::utility::Arr2Str (const std::array< T, N > &arr, size_t decimal=3, bool trailing_space=true, const std::string &separator=" ") |
Convert an std::array to a string. More... | |
bool | flexiv::rdk::utility::ProgramArgsExistAny (int argc, char **argv, const std::vector< std::string > &ref_strings) |
Check if any provided strings exist in the program arguments. More... | |
bool | flexiv::rdk::utility::ProgramArgsExist (int argc, char **argv, const std::string &ref_strings) |
Check if one specific string exists in the program arguments. More... | |
std::string | flexiv::rdk::utility::ParsePtStates (const std::vector< std::string > &pt_states, const std::string &parse_target) |
Parse the value of a specified primitive state from the pt_states string list. More... | |
Definition in file utility.hpp.
|
inline |
Convert an std::array to a string.
[in] | arr | std::array of any type and size. |
[in] | decimal | Decimal places to keep for each number in the array. |
[in] | trailing_space | Whether to include a space after the last element. |
[in] | separator | Character to separate between numbers. |
Definition at line 96 of file utility.hpp.
|
inline |
Parse the value of a specified primitive state from the pt_states string list.
[in] | pt_states | Primitive states string list returned from Robot::primitive_states(). |
[in] | parse_target | Name of the primitive state to parse for. |
Definition at line 144 of file utility.hpp.
|
inline |
Check if one specific string exists in the program arguments.
[in] | argc | Argument count passed to main() of the program. |
[in] | argv | Argument vector passed to main() of the program, with argv[0] being the program name. |
[in] | ref_strings | Reference string to check against. |
Definition at line 132 of file utility.hpp.
|
inline |
Check if any provided strings exist in the program arguments.
[in] | argc | Argument count passed to main() of the program. |
[in] | argv | Argument vector passed to main() of the program, where argv[0] is the program name. |
[in] | ref_strings | Reference strings to check against. |
Definition at line 112 of file utility.hpp.
|
inline |
Convert quaternion to Euler angles with ZYX axis rotations.
[in] | quat | Quaternion input in [w,x,y,z] order. |
Definition at line 23 of file utility.hpp.
|
inline |
Convert an std::vector to a string.
[in] | vec | std::vector of any type and size. |
[in] | decimal | Decimal places to keep for each number in the vector. |
[in] | trailing_space | Whether to include a space after the last element. |
[in] | separator | Character to separate between numbers. |
Definition at line 67 of file utility.hpp.