Flexiv RDK APIs  1.4
Functions
utility.hpp File Reference
#include <Eigen/Eigen>
#include <array>
Include dependency graph for utility.hpp:
This graph shows which files directly or indirectly include this file:

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...
 

Detailed Description

Definition in file utility.hpp.

Function Documentation

◆ Arr2Str()

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 = " " 
)
inline

Convert an std::array to a string.

Parameters
[in]arrstd::array of any type and size.
[in]decimalDecimal places to keep for each number in the array.
[in]trailing_spaceWhether to include a space after the last element.
[in]separatorCharacter to separate between numbers.
Returns
A string with format "arr[0] arr[1] ... arr[n] ", i.e. each element followed by a space, including the last one if trailing_space = true.
Examples
basics3_primitive_execution.cpp, basics5_zero_force_torque_sensors.cpp, intermediate5_realtime_cartesian_pure_motion_control.cpp, intermediate6_realtime_cartesian_motion_force_control.cpp, and intermediate7_robot_dynamics.cpp.

Definition at line 96 of file utility.hpp.

◆ ParsePtStates()

std::string flexiv::rdk::utility::ParsePtStates ( const std::vector< std::string > &  pt_states,
const std::string &  parse_target 
)
inline

Parse the value of a specified primitive state from the pt_states string list.

Parameters
[in]pt_statesPrimitive states string list returned from Robot::primitive_states().
[in]parse_targetName of the primitive state to parse for.
Returns
Value of the specified primitive state in string format. Empty string is returned if parse_target does not exist.
Examples
basics3_primitive_execution.cpp.

Definition at line 144 of file utility.hpp.

◆ ProgramArgsExist()

bool flexiv::rdk::utility::ProgramArgsExist ( int  argc,
char **  argv,
const std::string &  ref_strings 
)
inline

Check if one specific string exists in the program arguments.

Parameters
[in]argcArgument count passed to main() of the program.
[in]argvArgument vector passed to main() of the program, with argv[0] being the program name.
[in]ref_stringsReference string to check against.
Returns
True if the program arguments contain this specific reference string.
Examples
intermediate1_realtime_joint_position_control.cpp, intermediate2_realtime_joint_impedance_control.cpp, intermediate3_realtime_joint_torque_control.cpp, intermediate5_realtime_cartesian_pure_motion_control.cpp, and intermediate6_realtime_cartesian_motion_force_control.cpp.

Definition at line 132 of file utility.hpp.

◆ ProgramArgsExistAny()

bool flexiv::rdk::utility::ProgramArgsExistAny ( int  argc,
char **  argv,
const std::vector< std::string > &  ref_strings 
)
inline

Check if any provided strings exist in the program arguments.

Parameters
[in]argcArgument count passed to main() of the program.
[in]argvArgument vector passed to main() of the program, where argv[0] is the program name.
[in]ref_stringsReference strings to check against.
Returns
True if the program arguments contain one or more reference strings.
Examples
basics1_display_robot_states.cpp, basics2_clear_fault.cpp, basics3_primitive_execution.cpp, basics4_plan_execution.cpp, basics5_zero_force_torque_sensors.cpp, basics6_gripper_control.cpp, basics7_auto_recovery.cpp, basics8_update_robot_tool.cpp, basics9_logging_behavior.cpp, intermediate1_realtime_joint_position_control.cpp, intermediate2_realtime_joint_impedance_control.cpp, intermediate3_realtime_joint_torque_control.cpp, intermediate4_realtime_joint_floating.cpp, intermediate5_realtime_cartesian_pure_motion_control.cpp, intermediate6_realtime_cartesian_motion_force_control.cpp, and intermediate7_robot_dynamics.cpp.

Definition at line 112 of file utility.hpp.

◆ Quat2EulerZYX()

std::array<double, 3> flexiv::rdk::utility::Quat2EulerZYX ( const std::array< double, 4 > &  quat)
inline

Convert quaternion to Euler angles with ZYX axis rotations.

Parameters
[in]quatQuaternion input in [w,x,y,z] order.
Returns
Euler angles in [x,y,z] order [rad].
Note
The return value, when converted to degrees, is the same Euler angles used by Move primitives.
Examples
basics3_primitive_execution.cpp.

Definition at line 23 of file utility.hpp.

◆ Vec2Str()

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 = " " 
)
inline

Convert an std::vector to a string.

Parameters
[in]vecstd::vector of any type and size.
[in]decimalDecimal places to keep for each number in the vector.
[in]trailing_spaceWhether to include a space after the last element.
[in]separatorCharacter to separate between numbers.
Returns
A string with format "vec[0] vec[1] ... vec[n] ", i.e. each element followed by a space, including the last one if trailing_space = true.
Examples
intermediate1_realtime_joint_position_control.cpp, intermediate2_realtime_joint_impedance_control.cpp, intermediate3_realtime_joint_torque_control.cpp, intermediate5_realtime_cartesian_pure_motion_control.cpp, and intermediate7_robot_dynamics.cpp.

Definition at line 67 of file utility.hpp.