Classes | Functions
ROSEE::Utils Namespace Reference

Classes

struct  DifferentKeysException
 
class  SecondOrderFilter
 
class  Timer
 

Functions

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)
 

Function Documentation

◆ binomial_coefficent()

static int ROSEE::Utils::binomial_coefficent ( int  n,
int  k 
)
inlinestatic

Definition at line 77 of file Utils.h.

◆ create_directory()

static bool ROSEE::Utils::create_directory ( std::string  pathDirectory)
static

Definition at line 39 of file Utils.h.

◆ eigenMatrixToFloat32MultiArray()

static std_msgs::Float32MultiArray ROSEE::Utils::eigenMatrixToFloat32MultiArray ( Eigen::MatrixXd  eigenMatrix)
static

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)

Definition at line 19 of file UtilsEigen.h.

◆ eigenVectorToStdVector()

static std::vector<float> ROSEE::Utils::eigenVectorToStdVector ( Eigen::VectorXd  eigenVector)
static

Definition at line 58 of file UtilsEigen.h.

◆ extract_keys()

template<class KeyType , class ValueType >
static std::vector<KeyType> ROSEE::Utils::extract_keys ( std::map< KeyType, ValueType > const &  input_map)
static

Definition at line 95 of file Utils.h.

◆ extract_keys_merged() [1/2]

template<class T >
static std::vector<std::string> ROSEE::Utils::extract_keys_merged ( std::map< std::set< std::string >, T > const &  input_map,
unsigned int  max_string_number = 0 
)
static

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.

Parameters
input_mapthe map where extract the keys
max_string_numberthe max number of different string among all the set keys. Useful to not iterate all the map if not necessary. With default value = 0 all map is iterated.
Returns
vector of extracted string of set keys (string in this vect will be unique)

Definition at line 113 of file Utils.h.

◆ extract_keys_merged() [2/2]

template<class T >
static std::vector<std::string> ROSEE::Utils::extract_keys_merged ( std::map< std::pair< std::string, std::string >, T > const &  input_map,
unsigned int  max_string_number = 0 
)
static

See above, this is the version with pair instead of set.

Definition at line 146 of file Utils.h.

◆ getFilesInDir()

static std::vector<std::string> ROSEE::Utils::getFilesInDir ( std::string  pathFolder)
static

Definition at line 55 of file Utils.h.

◆ getPackagePath()

static std::string ROSEE::Utils::getPackagePath ( )
static

Definition at line 87 of file Utils.h.

◆ keys_equal()

template<typename keyType , typename valueType1 , typename valueType2 >
bool ROSEE::Utils::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.

Definition at line 182 of file Utils.h.

◆ loadObject()

template<typename RetType , typename... Args>
std::unique_ptr<RetType> ROSEE::Utils::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.

Parameters
lib_namethe name of the compiled library (eg DummyHal). Do not add the suffix .so
function_nameThe method of
lib_namewhich will return a RetType*.
argsarguments for the function_name , if the case
Returns
std::shared_ptr<RetType> a pointer to the new created object

Definition at line 228 of file Utils.h.

◆ out2file()

static void ROSEE::Utils::out2file ( std::string  pathFile,
std::string  output 
)
static

Definition at line 44 of file Utils.h.

◆ yamlMatrixToEigen()

static Eigen::MatrixXd ROSEE::Utils::yamlMatrixToEigen ( const YAML::Node &  matrixNode)
static

given a yaml node with a structure like

  • [1, 2, 3]
  • [4, 5, 6] "Convert" this structure into a eigen matrix
Todo:
is there a better way to do this?

Definition at line 18 of file UtilsYAML.h.

◆ yamlVectorToEigen()

static Eigen::VectorXd ROSEE::Utils::yamlVectorToEigen ( const YAML::Node &  vectorNode)
static

Definition at line 37 of file UtilsYAML.h.



end-effector
Author(s): Luca Muratore , Davide Torielli , Liana Bertoni
autogenerated on Tue Apr 5 2022 02:57:53