#include <ViconHandler.hpp>
Public Member Functions | |
void | destroy () |
void | initialize () |
void | update (StateBufferElement &state, const geometry_msgs::TransformStamped &z) |
Public Attributes | |
MeasureBufferElement | lastMeasure |
Protected Member Functions | |
void | measureCallback (const geometry_msgs::TransformStamped::ConstPtr &msg) |
Protected Attributes | |
ViconHandlerOption | options |
Eigen::Quaterniond | vicOrientation |
Eigen::Vector3d | vicPosition |
Definition at line 35 of file ViconHandler.hpp.
void telekyb_state::ViconHandler::destroy | ( | ) | [virtual] |
Implements telekyb_state::SensorHandler.
void telekyb_state::ViconHandler::initialize | ( | ) | [virtual] |
Implements telekyb_state::SensorHandler.
Definition at line 23 of file ViconHandler.cpp.
void telekyb_state::ViconHandler::measureCallback | ( | const geometry_msgs::TransformStamped::ConstPtr & | msg | ) | [protected] |
Definition at line 30 of file ViconHandler.cpp.
void telekyb_state::ViconHandler::update | ( | StateBufferElement & | state, |
const geometry_msgs::TransformStamped & | z | ||
) |
Definition at line 39 of file ViconHandler.cpp.
Definition at line 50 of file ViconHandler.hpp.
Definition at line 38 of file ViconHandler.hpp.
Eigen::Quaterniond telekyb_state::ViconHandler::vicOrientation [protected] |
Definition at line 42 of file ViconHandler.hpp.
Eigen::Vector3d telekyb_state::ViconHandler::vicPosition [protected] |
Definition at line 41 of file ViconHandler.hpp.