#include <ComplementaryStateEstimator.hpp>
Definition at line 62 of file ComplementaryStateEstimator.hpp.
Definition at line 68 of file ComplementaryStateEstimator.cpp.
void telekyb_state::ComplementaryStateEstimator::destroy | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 305 of file ComplementaryStateEstimator.cpp.
std::string telekyb_state::ComplementaryStateEstimator::getName | ( | ) | const [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 315 of file ComplementaryStateEstimator.cpp.
void telekyb_state::ComplementaryStateEstimator::initializationDone | ( | ) | [protected] |
Definition at line 86 of file ComplementaryStateEstimator.cpp.
void telekyb_state::ComplementaryStateEstimator::initialize | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 75 of file ComplementaryStateEstimator.cpp.
void telekyb_state::ComplementaryStateEstimator::initVelocityFilters | ( | ) | [protected] |
Definition at line 54 of file ComplementaryStateEstimator.cpp.
void telekyb_state::ComplementaryStateEstimator::inputCallback | ( | const tk_draft_msgs::TKSmallImuConstPtr & | msg | ) |
Definition at line 151 of file ComplementaryStateEstimator.cpp.
void telekyb_state::ComplementaryStateEstimator::measureCallback | ( | const geometry_msgs::TransformStampedConstPtr & | msg | ) |
Definition at line 207 of file ComplementaryStateEstimator.cpp.
void telekyb_state::ComplementaryStateEstimator::prediction | ( | State & | state, |
double | Tpred | ||
) | [protected] |
Definition at line 125 of file ComplementaryStateEstimator.cpp.
void telekyb_state::ComplementaryStateEstimator::publishState | ( | ) | [protected] |
Definition at line 257 of file ComplementaryStateEstimator.cpp.
void telekyb_state::ComplementaryStateEstimator::spin | ( | ) | [protected] |
Definition at line 98 of file ComplementaryStateEstimator.cpp.
void telekyb_state::ComplementaryStateEstimator::willBecomeActive | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 284 of file ComplementaryStateEstimator.cpp.
void telekyb_state::ComplementaryStateEstimator::willBecomeInActive | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 298 of file ComplementaryStateEstimator.cpp.
Eigen::Vector3d telekyb_state::ComplementaryStateEstimator::angVelFiltered [protected] |
Definition at line 79 of file ComplementaryStateEstimator.hpp.
Definition at line 86 of file ComplementaryStateEstimator.hpp.
boost::mutex telekyb_state::ComplementaryStateEstimator::imuMutex [protected] |
Definition at line 96 of file ComplementaryStateEstimator.hpp.
Definition at line 84 of file ComplementaryStateEstimator.hpp.
Definition at line 105 of file ComplementaryStateEstimator.hpp.
bool telekyb_state::ComplementaryStateEstimator::isInitialized [protected] |
Definition at line 91 of file ComplementaryStateEstimator.hpp.
Definition at line 82 of file ComplementaryStateEstimator.hpp.
IIRFilter* telekyb_state::ComplementaryStateEstimator::omegaFilter[3] [protected] |
Definition at line 77 of file ComplementaryStateEstimator.hpp.
Definition at line 103 of file ComplementaryStateEstimator.hpp.
telekyb::Timer telekyb_state::ComplementaryStateEstimator::pubTimer [protected] |
Definition at line 99 of file ComplementaryStateEstimator.hpp.
bool telekyb_state::ComplementaryStateEstimator::receivedFirstInput [protected] |
Definition at line 91 of file ComplementaryStateEstimator.hpp.
bool telekyb_state::ComplementaryStateEstimator::receivedFirstMeasure [protected] |
Definition at line 91 of file ComplementaryStateEstimator.hpp.
telekyb::Timer telekyb_state::ComplementaryStateEstimator::rtTimer [protected] |
Definition at line 98 of file ComplementaryStateEstimator.hpp.
bool telekyb_state::ComplementaryStateEstimator::spinning [protected] |
Definition at line 90 of file ComplementaryStateEstimator.hpp.
Definition at line 107 of file ComplementaryStateEstimator.hpp.
boost::thread telekyb_state::ComplementaryStateEstimator::thread [protected] |
Definition at line 93 of file ComplementaryStateEstimator.hpp.
boost::mutex telekyb_state::ComplementaryStateEstimator::threadMutex [protected] |
Definition at line 94 of file ComplementaryStateEstimator.hpp.
boost::mutex telekyb_state::ComplementaryStateEstimator::viconMutex [protected] |
Definition at line 97 of file ComplementaryStateEstimator.hpp.
Definition at line 87 of file ComplementaryStateEstimator.hpp.
Definition at line 83 of file ComplementaryStateEstimator.hpp.