|
static int | binomial_coefficent (int n, int k) |
|
static bool | create_directory (std::string pathDirectory) |
|
static std_msgs::Float32MultiArray | eigenMatrixToFloat32MultiArray (Eigen::MatrixXd eigenMatrix) |
| Utility to fill the Float32MultiArray ROS message from an eigen matrix. The Float32MultiArray matrix will be stored in column major, independently from the eigen matrix that can be row major (even by default eigen matrix is column major, it can be templatizate specifing the row major) More...
|
|
static std::vector< float > | eigenVectorToStdVector (Eigen::VectorXd eigenVector) |
|
template<class KeyType , class ValueType > |
static std::vector< KeyType > | extract_keys (std::map< KeyType, ValueType > const &input_map) |
|
template<class T > |
static std::vector< std::string > | extract_keys_merged (std::map< std::set< std::string >, T > const &input_map, unsigned int max_string_number=0) |
| Extract all the string in the set keys of a map. All string are put togheter so the original meaning of each set is lost. More...
|
|
template<class T > |
static std::vector< std::string > | extract_keys_merged (std::map< std::pair< std::string, std::string >, T > const &input_map, unsigned int max_string_number=0) |
| See above, this is the version with pair instead of set. More...
|
|
static std::vector< std::string > | getFilesInDir (std::string pathFolder) |
|
static std::string | getPackagePath () |
|
template<typename keyType , typename valueType1 , typename valueType2 > |
bool | keys_equal (std::map< keyType, valueType1 > const &lhs, std::map< keyType, valueType2 > const &rhs) |
| Return false if two maps have different keys. The type of the keys (typename ) must be the same obviously, but the values (valueType1 and valueType2 ) can be anything, because they are not considered. More...
|
|
template<typename RetType , typename... Args> |
std::unique_ptr< RetType > | loadObject (std::string lib_name, std::string function_name, Args... args) |
| Utils to dynamically load an object. This is used to dynamically load a derived object from a node that only knows the base interface. For example, we call the create_object(ros::nodeHandle) method of a derived EEHAL class The object must be a library which will return a RetType pointer with the function_name This function will "convert" to smart pointer for convenience. More...
|
|
static void | out2file (std::string pathFile, std::string output) |
|
static Eigen::MatrixXd | yamlMatrixToEigen (const YAML::Node &matrixNode) |
| given a yaml node with a structure like More...
|
|
static Eigen::VectorXd | yamlVectorToEigen (const YAML::Node &vectorNode) |
|