Public Member Functions | Static Public Member Functions | Static Private Member Functions | List of all members
generic_control_toolbox::MatrixParser Class Reference

#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)
 
static void initializeEigenMatrix (Eigen::MatrixXd &M, const std::vector< double > &vals, int rows, int cols)
 

Detailed Description

Definition at line 11 of file matrix_parser.hpp.

Constructor & Destructor Documentation

generic_control_toolbox::MatrixParser::MatrixParser ( )

Definition at line 5 of file matrix_parser.cpp.

generic_control_toolbox::MatrixParser::~MatrixParser ( )

Definition at line 6 of file matrix_parser.cpp.

Member Function Documentation

Eigen::Matrix3d generic_control_toolbox::MatrixParser::computeSkewSymmetric ( const Eigen::Vector3d &  v)
static

Computed the skew-symmetric matrix of a 3-dimensional vector.

Parameters
vThe 3-dimensional vector
Returns
The skew-symmetric matrix

Definition at line 104 of file matrix_parser.cpp.

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
MThe matrix to be filled in. Will be set to the size nxn.
valsA vector with the values to fill in
Exceptions
logic_errorin case vals does not have square dimensions.

Definition at line 55 of file matrix_parser.cpp.

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
MThe matrix to be filled in. Will be set to the size nxn.
valsA vector with the values to fill in
rowsThe number of rows in the matrix.
colsThe number of cols.
Exceptions
logic_errorin case the rows or cols have invalid numbers.

Definition at line 78 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.

Parameters
MThe matrix to be initialized
param_nameThe parameter server location
nThe ros nodehandle used to query the parameter server
Exceptions
logic_errorin 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:


generic_control_toolbox
Author(s): diogo
autogenerated on Wed Apr 28 2021 03:01:15