Flexiv RDK APIs
0.10
|
Go to the source code of this file.
Functions | |
std::vector< double > | flexiv::utility::quat2EulerZYX (const std::vector< double > &quat) |
Convert quaternion to Euler angles with ZYX axis rotations. More... | |
double | flexiv::utility::rad2Deg (double rad) |
Convert radians to degrees for a single value. | |
std::vector< double > | flexiv::utility::rad2Deg (const std::vector< double > &radVec) |
Convert radians to degrees for a vector. | |
template<typename T > | |
std::string | flexiv::utility::vec2Str (const std::vector< T > &vec, size_t decimal=3, bool trailingSpace=true) |
Convert a std::vector to a string. More... | |
template<typename T , size_t N> | |
std::string | flexiv::utility::arr2Str (const std::array< T, N > &arr, size_t decimal=3, bool trailingSpace=true) |
Convert a std::array to a string. More... | |
bool | flexiv::utility::programArgsExistAny (int argc, char **argv, const std::vector< std::string > &refStrs) |
Check if any provided strings exist in the program arguments. More... | |
bool | flexiv::utility::programArgsExist (int argc, char **argv, const std::string &refStr) |
Check if one specific string exists in the program arguments. More... | |
std::string | flexiv::utility::parsePtStates (const std::vector< std::string > &ptStates, const std::string &parseTarget) |
Parse the value of a specified primitive state from the ptStates string list. More... | |
Definition in file Utility.hpp.
|
inline |
Convert a 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] | trailingSpace | Whether to include a space after the last element. |
Definition at line 101 of file Utility.hpp.
|
inline |
Parse the value of a specified primitive state from the ptStates string list.
[in] | ptStates | Primitive states string list returned from Robot::getPrimitiveStates(). |
[in] | parseTarget | Name of the primitive state to parse for. |
Definition at line 163 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, where argv[0] is the program name. |
[in] | refStr | Reference string to check against. |
Definition at line 149 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] | refStrs | Reference strings to check against. |
Definition at line 128 of file Utility.hpp.
|
inline |
Convert quaternion to Euler angles with ZYX axis rotations.
[in] | quat | Quaternion input in [w,x,y,z] order. |
InputException | if input is of wrong size. |
Definition at line 25 of file Utility.hpp.
|
inline |
Convert a 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] | trailingSpace | Whether to include a space after the last element. |
Definition at line 73 of file Utility.hpp.