#include <matrix_parser.hpp>
Definition at line 11 of file matrix_parser.hpp.
◆ MatrixParser()
generic_control_toolbox::MatrixParser::MatrixParser |
( |
| ) |
|
◆ ~MatrixParser()
generic_control_toolbox::MatrixParser::~MatrixParser |
( |
| ) |
|
◆ computeSkewSymmetric()
Eigen::Matrix3d generic_control_toolbox::MatrixParser::computeSkewSymmetric |
( |
const Eigen::Vector3d & |
v | ) |
|
|
static |
Computed the skew-symmetric matrix of a 3-dimensional vector.
- Parameters
-
v | The 3-dimensional vector |
- Returns
- The skew-symmetric matrix
Definition at line 104 of file matrix_parser.cpp.
◆ initializeEigenMatrix() [1/2]
void generic_control_toolbox::MatrixParser::initializeEigenMatrix |
( |
Eigen::MatrixXd & |
M, |
|
|
const std::vector< double > & |
vals |
|
) |
| |
|
staticprivate |
Fill in a nxn matrix with the given values.
- Parameters
-
M | The matrix to be filled in. Will be set to the size nxn. |
vals | A vector with the values to fill in |
- Exceptions
-
logic_error | in case vals does not have square dimensions. |
Definition at line 55 of file matrix_parser.cpp.
◆ initializeEigenMatrix() [2/2]
void generic_control_toolbox::MatrixParser::initializeEigenMatrix |
( |
Eigen::MatrixXd & |
M, |
|
|
const std::vector< double > & |
vals, |
|
|
int |
rows, |
|
|
int |
cols |
|
) |
| |
|
staticprivate |
Fill in a rows x cols matrix with the given values.
- Parameters
-
M | The matrix to be filled in. Will be set to the size nxn. |
vals | A vector with the values to fill in |
rows | The number of rows in the matrix. |
cols | The number of cols. |
- Exceptions
-
logic_error | in case the rows or cols have invalid numbers. |
Definition at line 78 of file matrix_parser.cpp.
◆ parseMatrixData()
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.
- Parameters
-
M | The matrix to be initialized |
param_name | The parameter server location |
n | The ros nodehandle used to query the parameter server |
- Exceptions
-
logic_error | in case vals does not have square dimensions. |
- Returns
- True for success, False if parameter is not available.
Definition at line 8 of file matrix_parser.cpp.
The documentation for this class was generated from the following files: