#include <KalmanStateEstimator.hpp>
Public Member Functions | |
virtual void | destroy () |
virtual void | destroy () |
virtual std::string | getName () const |
virtual std::string | getName () const |
void | imuCallback (const sensor_msgs::Imu::ConstPtr &msg) |
void | imuCallback (const sensor_msgs::Imu::ConstPtr &msg) |
virtual void | initialize () |
virtual void | initialize () |
void | viconCallback (const geometry_msgs::TransformStamped::ConstPtr &msg) |
void | viconCallback (const geometry_msgs::TransformStamped::ConstPtr &msg) |
virtual void | willBecomeActive () |
virtual void | willBecomeActive () |
virtual void | willBecomeInActive () |
virtual void | willBecomeInActive () |
Protected Member Functions | |
void | core () |
void | core () |
void | prediction (StateBufferElement &state, const InputBufferElement &u, double Tpred) |
void | prediction (StateBufferElement &state, const InputBufferElement &u, double Tpred) |
void | publishEstimate (const StateBufferElement &estimate) |
void | publishEstimate (const StateBufferElement &estimate) |
template<typename _BufferElement > | |
std::deque< _BufferElement > ::iterator | searchInBuffer (std::deque< _BufferElement > &buffer, double time) |
template<typename _BufferElement > | |
std::deque< _BufferElement, Eigen::aligned_allocator < _BufferElement > >::iterator | searchInBuffer (std::deque< _BufferElement, Eigen::aligned_allocator< _BufferElement > > &buffer, double time) |
Protected Attributes | |
std::deque< InputBufferElement > ::const_iterator | currentInputIndex |
std::deque< InputBufferElement, Eigen::aligned_allocator < InputBufferElement > >::const_iterator | currentInputIndex |
ros::Subscriber | imuSub |
std::deque< InputBufferElement > | inputBuffer |
std::deque< InputBufferElement, Eigen::aligned_allocator < InputBufferElement > > | inputBuffer |
StateBufferElement | internalState |
Time | intTime |
bool | isInitialized |
bool | isInitializedAngVel |
bool | isInitializedLinVel |
bool | isInitializedPose |
std::deque< MeasureBufferElement > | measureBuffer |
std::deque < MeasureBufferElement, Eigen::aligned_allocator < MeasureBufferElement > > | measureBuffer |
InputBufferElement | newInput |
boost::mutex | newInputMutex |
bool | newInputReceived |
MeasureBufferElement | newMeasure |
boost::mutex | newMeasureMutex |
bool | newMeasureReceived |
std::deque < MeasureBufferElement > ::const_iterator | nextMeasureIndex |
std::deque < MeasureBufferElement, Eigen::aligned_allocator < StateBufferElement > >::const_iterator | nextMeasureIndex |
ros::NodeHandle | nodeHandle |
KalmanStateEstimatorOptions | options |
double | predTime |
Timer | saveTimer |
std::deque< StateBufferElement > | stateBuffer |
std::deque< StateBufferElement, Eigen::aligned_allocator < StateBufferElement > > | stateBuffer |
ros::Publisher | statePub |
EigenTools | tools |
ViconHandler | viconHandler |
MeasureHandler | viconHanler |
ros::Subscriber | vicSub |
Definition at line 68 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
void telekyb_state::KalmanStateEstimator::core | ( | ) | [protected] |
Definition at line 70 of file KalmanStateEstimator/KalmanStateEstimator.cpp.
void telekyb_state::KalmanStateEstimator::core | ( | ) | [protected] |
void telekyb_state::KalmanStateEstimator::destroy | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 367 of file KalmanStateEstimator/KalmanStateEstimator.cpp.
virtual void telekyb_state::KalmanStateEstimator::destroy | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
virtual std::string telekyb_state::KalmanStateEstimator::getName | ( | ) | const [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
std::string telekyb_state::KalmanStateEstimator::getName | ( | ) | const [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 369 of file KalmanStateEstimator/KalmanStateEstimator.cpp.
void telekyb_state::KalmanStateEstimator::imuCallback | ( | const sensor_msgs::Imu::ConstPtr & | msg | ) |
void telekyb_state::KalmanStateEstimator::imuCallback | ( | const sensor_msgs::Imu::ConstPtr & | msg | ) |
Definition at line 197 of file KalmanStateEstimator/KalmanStateEstimator.cpp.
void telekyb_state::KalmanStateEstimator::initialize | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 57 of file KalmanStateEstimator/KalmanStateEstimator.cpp.
virtual void telekyb_state::KalmanStateEstimator::initialize | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
void telekyb_state::KalmanStateEstimator::prediction | ( | StateBufferElement & | state, |
const InputBufferElement & | u, | ||
double | Tpred | ||
) | [protected] |
Definition at line 262 of file KalmanStateEstimator/KalmanStateEstimator.cpp.
void telekyb_state::KalmanStateEstimator::prediction | ( | StateBufferElement & | state, |
const InputBufferElement & | u, | ||
double | Tpred | ||
) | [protected] |
void telekyb_state::KalmanStateEstimator::publishEstimate | ( | const StateBufferElement & | estimate | ) | [protected] |
Definition at line 190 of file KalmanStateEstimator/KalmanStateEstimator.cpp.
void telekyb_state::KalmanStateEstimator::publishEstimate | ( | const StateBufferElement & | estimate | ) | [protected] |
std::deque< _BufferElement >::iterator telekyb_state::KalmanStateEstimator::searchInBuffer | ( | std::deque< _BufferElement > & | buffer, |
double | time | ||
) | [protected] |
Definition at line 133 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
std::deque< _BufferElement, Eigen::aligned_allocator< _BufferElement > >::iterator telekyb_state::KalmanStateEstimator::searchInBuffer | ( | std::deque< _BufferElement, Eigen::aligned_allocator< _BufferElement > > & | buffer, |
double | time | ||
) | [protected] |
Definition at line 136 of file KalmanStateEstimator.hpp.
void telekyb_state::KalmanStateEstimator::viconCallback | ( | const geometry_msgs::TransformStamped::ConstPtr & | msg | ) |
Definition at line 223 of file KalmanStateEstimator/KalmanStateEstimator.cpp.
void telekyb_state::KalmanStateEstimator::viconCallback | ( | const geometry_msgs::TransformStamped::ConstPtr & | msg | ) |
void telekyb_state::KalmanStateEstimator::willBecomeActive | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 355 of file KalmanStateEstimator/KalmanStateEstimator.cpp.
virtual void telekyb_state::KalmanStateEstimator::willBecomeActive | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
void telekyb_state::KalmanStateEstimator::willBecomeInActive | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 362 of file KalmanStateEstimator/KalmanStateEstimator.cpp.
virtual void telekyb_state::KalmanStateEstimator::willBecomeInActive | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
std::deque<InputBufferElement>::const_iterator telekyb_state::KalmanStateEstimator::currentInputIndex [protected] |
Definition at line 93 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
std::deque<InputBufferElement, Eigen::aligned_allocator<InputBufferElement> >::const_iterator telekyb_state::KalmanStateEstimator::currentInputIndex [protected] |
Definition at line 96 of file KalmanStateEstimator.hpp.
Definition at line 85 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
std::deque<InputBufferElement> telekyb_state::KalmanStateEstimator::inputBuffer [protected] |
Definition at line 90 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
std::deque<InputBufferElement, Eigen::aligned_allocator<InputBufferElement> > telekyb_state::KalmanStateEstimator::inputBuffer [protected] |
Definition at line 93 of file KalmanStateEstimator.hpp.
Definition at line 95 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
Time telekyb_state::KalmanStateEstimator::intTime [protected] |
Definition at line 119 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
bool telekyb_state::KalmanStateEstimator::isInitialized [protected] |
Definition at line 96 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
bool telekyb_state::KalmanStateEstimator::isInitializedAngVel [protected] |
Definition at line 99 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
bool telekyb_state::KalmanStateEstimator::isInitializedLinVel [protected] |
Definition at line 97 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
bool telekyb_state::KalmanStateEstimator::isInitializedPose [protected] |
Definition at line 98 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
std::deque<MeasureBufferElement> telekyb_state::KalmanStateEstimator::measureBuffer [protected] |
Definition at line 89 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
std::deque<MeasureBufferElement, Eigen::aligned_allocator<MeasureBufferElement> > telekyb_state::KalmanStateEstimator::measureBuffer [protected] |
Definition at line 92 of file KalmanStateEstimator.hpp.
Definition at line 104 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
boost::mutex telekyb_state::KalmanStateEstimator::newInputMutex [protected] |
Definition at line 108 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
bool telekyb_state::KalmanStateEstimator::newInputReceived [protected] |
Definition at line 102 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
Definition at line 103 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
boost::mutex telekyb_state::KalmanStateEstimator::newMeasureMutex [protected] |
Definition at line 107 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
bool telekyb_state::KalmanStateEstimator::newMeasureReceived [protected] |
Definition at line 101 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
std::deque<MeasureBufferElement>::const_iterator telekyb_state::KalmanStateEstimator::nextMeasureIndex [protected] |
Definition at line 92 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
std::deque<MeasureBufferElement, Eigen::aligned_allocator<StateBufferElement> >::const_iterator telekyb_state::KalmanStateEstimator::nextMeasureIndex [protected] |
Definition at line 95 of file KalmanStateEstimator.hpp.
Definition at line 84 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
Definition at line 82 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
double telekyb_state::KalmanStateEstimator::predTime [protected] |
Definition at line 120 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
Timer telekyb_state::KalmanStateEstimator::saveTimer [protected] |
Definition at line 121 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
std::deque<StateBufferElement> telekyb_state::KalmanStateEstimator::stateBuffer [protected] |
Definition at line 88 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
std::deque<StateBufferElement, Eigen::aligned_allocator<StateBufferElement> > telekyb_state::KalmanStateEstimator::stateBuffer [protected] |
Definition at line 91 of file KalmanStateEstimator.hpp.
Definition at line 86 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
EigenTools telekyb_state::KalmanStateEstimator::tools [protected] |
Definition at line 124 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
Definition at line 115 of file KalmanStateEstimator/KalmanStateEstimator.hpp.
Definition at line 118 of file KalmanStateEstimator.hpp.
Definition at line 87 of file KalmanStateEstimator.hpp.