matrix_parser.hpp
Go to the documentation of this file.
1 #ifndef __FOLDING_UTILS__
2 #define __FOLDING_UTILS__
3 
4 #include <math.h>
5 #include <ros/ros.h>
6 #include <Eigen/Dense>
7 #include <stdexcept>
8 
10 {
12 {
13  public:
14  MatrixParser();
15  ~MatrixParser();
16 
28  static bool parseMatrixData(Eigen::MatrixXd &M, const std::string param_name,
29  const ros::NodeHandle &n);
30 
37  static Eigen::Matrix3d computeSkewSymmetric(const Eigen::Vector3d &v);
38 
39  private:
47  static void initializeEigenMatrix(Eigen::MatrixXd &M,
48  const std::vector<double> &vals);
49 };
50 } // namespace generic_control_toolbox
51 
52 #endif
static Eigen::Matrix3d computeSkewSymmetric(const Eigen::Vector3d &v)
static void initializeEigenMatrix(Eigen::MatrixXd &M, const std::vector< double > &vals)
static bool parseMatrixData(Eigen::MatrixXd &M, const std::string param_name, const ros::NodeHandle &n)


generic_control_toolbox
Author(s): diogo
autogenerated on Thu Jun 6 2019 19:54:44