#include <matrix_parser.hpp>
Public Member Functions | |
| MatrixParser () | |
| ~MatrixParser () | |
Static Public Member Functions | |
| static Eigen::Matrix3d | computeSkewSymmetric (const Eigen::Vector3d &v) |
| static bool | parseMatrixData (Eigen::MatrixXd &M, const std::string param_name, const ros::NodeHandle &n) |
Static Private Member Functions | |
| static void | initializeEigenMatrix (Eigen::MatrixXd &M, const std::vector< double > &vals) |
Definition at line 11 of file matrix_parser.hpp.
Definition at line 5 of file matrix_parser.cpp.
Definition at line 6 of file matrix_parser.cpp.
| Eigen::Matrix3d generic_control_toolbox::MatrixParser::computeSkewSymmetric | ( | const Eigen::Vector3d & | v | ) | [static] |
Computed the skew-symmetric matrix of a 3-dimensional vector.
| v | The 3-dimensional vector |
Definition at line 70 of file matrix_parser.cpp.
| void generic_control_toolbox::MatrixParser::initializeEigenMatrix | ( | Eigen::MatrixXd & | M, |
| const std::vector< double > & | vals | ||
| ) | [static, private] |
Fill in a nxn matrix with the given values.
| M | The matrix to be filled in. Will be set to the size nxn. |
| vals | A vector with the values to fill in |
| logic_error | in case vals does not have square dimensions. |
Definition at line 38 of file matrix_parser.cpp.
| bool generic_control_toolbox::MatrixParser::parseMatrixData | ( | Eigen::MatrixXd & | M, |
| const std::string | param_name, | ||
| const ros::NodeHandle & | n | ||
| ) | [static] |
Initialize a nxn matrix with values obtained from the ros parameter server.
| M | The matrix to be initialized |
| param_name | The parameter server location |
| n | The ros nodehandle used to query the parameter server |
| logic_error | in case vals does not have square dimensions. |
Definition at line 8 of file matrix_parser.cpp.