#include <ViconStateEstimator.hpp>
Public Member Functions | |
virtual void | destroy () |
virtual std::string | getName () const |
virtual void | initialize () |
void | viconCallback (const geometry_msgs::PoseStamped::ConstPtr &msg) |
virtual void | willBecomeActive () |
virtual void | willBecomeInActive () |
Protected Member Functions | |
void | initVelocityFilters () |
void | velQuatToBodyOmega (const Quaternion &quat, const Quaternion &quatRates, Velocity3D &bodyOmega) |
Protected Attributes | |
IIRFilter * | angFilter [4] |
ros::NodeHandle | nodeHandle |
ViconStateEstimatorOptions | options |
IIRFilter * | smoothVelFilter [3] |
ros::Publisher | smoothVelPub |
IIRFilter * | velFilter [3] |
ros::Subscriber | viconSub |
Definition at line 48 of file ViconStateEstimator.hpp.
void telekyb_state::ViconStateEstimator::destroy | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 107 of file ViconStateEstimator.cpp.
std::string telekyb_state::ViconStateEstimator::getName | ( | ) | const [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 119 of file ViconStateEstimator.cpp.
void telekyb_state::ViconStateEstimator::initialize | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 86 of file ViconStateEstimator.cpp.
void telekyb_state::ViconStateEstimator::initVelocityFilters | ( | ) | [protected] |
Definition at line 41 of file ViconStateEstimator.cpp.
void telekyb_state::ViconStateEstimator::velQuatToBodyOmega | ( | const Quaternion & | quat, |
const Quaternion & | quatRates, | ||
Velocity3D & | bodyOmega | ||
) | [protected] |
Definition at line 71 of file ViconStateEstimator.cpp.
void telekyb_state::ViconStateEstimator::viconCallback | ( | const geometry_msgs::PoseStamped::ConstPtr & | msg | ) |
Definition at line 125 of file ViconStateEstimator.cpp.
void telekyb_state::ViconStateEstimator::willBecomeActive | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 92 of file ViconStateEstimator.cpp.
void telekyb_state::ViconStateEstimator::willBecomeInActive | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::StateEstimator.
Definition at line 101 of file ViconStateEstimator.cpp.
IIRFilter* telekyb_state::ViconStateEstimator::angFilter[4] [protected] |
Definition at line 61 of file ViconStateEstimator.hpp.
Definition at line 52 of file ViconStateEstimator.hpp.
Definition at line 50 of file ViconStateEstimator.hpp.
IIRFilter* telekyb_state::ViconStateEstimator::smoothVelFilter[3] [protected] |
Definition at line 60 of file ViconStateEstimator.hpp.
Definition at line 55 of file ViconStateEstimator.hpp.
IIRFilter* telekyb_state::ViconStateEstimator::velFilter[3] [protected] |
Definition at line 59 of file ViconStateEstimator.hpp.
Definition at line 53 of file ViconStateEstimator.hpp.