#include <StandardInertiaMatrixEstimator.hpp>
Public Member Functions | |
void | destroy () |
Eigen::Matrix3d | getInitialInertiaMatrix () const |
std::string | getName () const |
void | initialize () |
void | run (const InertiaMatrixEstimInput &input, InertiaMatrixEstimOutput &output) |
StandardInertiaMatrixEstimator () | |
virtual | ~StandardInertiaMatrixEstimator () |
Private Attributes | |
IIRFilter * | angVelFilter [3] |
Eigen::Vector3d | estGain |
IIRFilter * | estGainIntegrator [3] |
Eigen::Vector3d | estInvInertia |
IIRFilter * | estInvInertiaIntegrator [3] |
ros::Publisher | inertiaPub |
Eigen::Vector3d | integInitialGain |
Eigen::Vector3d | integInitialInvInertia |
ros::NodeHandle | nodeHandle |
StandardInertiaMatrixEstimOptions | options |
IIRFilter * | torqueFilter [3] |
Definition at line 39 of file StandardInertiaMatrixEstimator.hpp.
Definition at line 39 of file StandardInertiaMatrixEstimator.cpp.
Definition at line 98 of file StandardInertiaMatrixEstimator.cpp.
void TELEKYB_NAMESPACE::StandardInertiaMatrixEstimator::destroy | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::InertiaMatrixEstimator.
Definition at line 83 of file StandardInertiaMatrixEstimator.cpp.
Eigen::Matrix3d TELEKYB_NAMESPACE::StandardInertiaMatrixEstimator::getInitialInertiaMatrix | ( | ) | const [virtual] |
Implements TELEKYB_NAMESPACE::InertiaMatrixEstimator.
Definition at line 179 of file StandardInertiaMatrixEstimator.cpp.
std::string TELEKYB_NAMESPACE::StandardInertiaMatrixEstimator::getName | ( | ) | const [virtual] |
Implements TELEKYB_NAMESPACE::InertiaMatrixEstimator.
Definition at line 93 of file StandardInertiaMatrixEstimator.cpp.
void TELEKYB_NAMESPACE::StandardInertiaMatrixEstimator::initialize | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::InertiaMatrixEstimator.
Definition at line 46 of file StandardInertiaMatrixEstimator.cpp.
void TELEKYB_NAMESPACE::StandardInertiaMatrixEstimator::run | ( | const InertiaMatrixEstimInput & | input, |
InertiaMatrixEstimOutput & | output | ||
) | [virtual] |
Implements TELEKYB_NAMESPACE::InertiaMatrixEstimator.
Definition at line 103 of file StandardInertiaMatrixEstimator.cpp.
Definition at line 51 of file StandardInertiaMatrixEstimator.hpp.
Eigen::Vector3d TELEKYB_NAMESPACE::StandardInertiaMatrixEstimator::estGain [private] |
Definition at line 44 of file StandardInertiaMatrixEstimator.hpp.
Definition at line 55 of file StandardInertiaMatrixEstimator.hpp.
Eigen::Vector3d TELEKYB_NAMESPACE::StandardInertiaMatrixEstimator::estInvInertia [private] |
Definition at line 43 of file StandardInertiaMatrixEstimator.hpp.
Definition at line 54 of file StandardInertiaMatrixEstimator.hpp.
Definition at line 58 of file StandardInertiaMatrixEstimator.hpp.
Eigen::Vector3d TELEKYB_NAMESPACE::StandardInertiaMatrixEstimator::integInitialGain [private] |
Definition at line 47 of file StandardInertiaMatrixEstimator.hpp.
Eigen::Vector3d TELEKYB_NAMESPACE::StandardInertiaMatrixEstimator::integInitialInvInertia [private] |
Definition at line 46 of file StandardInertiaMatrixEstimator.hpp.
Definition at line 57 of file StandardInertiaMatrixEstimator.hpp.
StandardInertiaMatrixEstimOptions TELEKYB_NAMESPACE::StandardInertiaMatrixEstimator::options [private] |
Definition at line 41 of file StandardInertiaMatrixEstimator.hpp.
Definition at line 50 of file StandardInertiaMatrixEstimator.hpp.