#include <VRPNTrackerServer.hpp>
Public Member Functions | |
| void | spin () | 
| VRPNTrackerServer (const std::string &topicName_, vrpn_Connection *c_) | |
| virtual | ~VRPNTrackerServer () | 
Protected Member Functions | |
| void | sendPose () | 
| void | setPose (const Position3D &rosPosition, const Quaternion &rosRotation) | 
| void | transformStampedCallback (const geometry_msgs::TransformStamped::ConstPtr &msg) | 
Protected Attributes | |
| vrpn_Connection * | c | 
| ros::NodeHandle | nodeHandle | 
| VRPNTrackerServerOptions & | options | 
| timeval | packageTime | 
| vrpn_float64 | position [3] | 
| vrpn_float64 | rotation [4] | 
| ros::Subscriber | sub | 
| vrpn_Tracker_Server * | vts | 
Definition at line 23 of file VRPNTrackerServer.hpp.
| TELEKYB_NAMESPACE::VRPNTrackerServer::VRPNTrackerServer | ( | const std::string & | topicName_, | 
| vrpn_Connection * | c_ | ||
| ) | 
Definition at line 16 of file VRPNTrackerServer.cpp.
| TELEKYB_NAMESPACE::VRPNTrackerServer::~VRPNTrackerServer | ( | ) |  [virtual] | 
        
Definition at line 39 of file VRPNTrackerServer.cpp.
| void TELEKYB_NAMESPACE::VRPNTrackerServer::sendPose | ( | ) |  [protected] | 
        
Definition at line 56 of file VRPNTrackerServer.cpp.
| void TELEKYB_NAMESPACE::VRPNTrackerServer::setPose | ( | const Position3D & | rosPosition, | 
| const Quaternion & | rosRotation | ||
| ) |  [protected] | 
        
Definition at line 43 of file VRPNTrackerServer.cpp.
Definition at line 81 of file VRPNTrackerServer.cpp.
| void TELEKYB_NAMESPACE::VRPNTrackerServer::transformStampedCallback | ( | const geometry_msgs::TransformStamped::ConstPtr & | msg | ) |  [protected] | 
        
Definition at line 68 of file VRPNTrackerServer.cpp.
vrpn_Connection* TELEKYB_NAMESPACE::VRPNTrackerServer::c [protected] | 
        
Definition at line 25 of file VRPNTrackerServer.hpp.
Definition at line 32 of file VRPNTrackerServer.hpp.
Definition at line 34 of file VRPNTrackerServer.hpp.
timeval TELEKYB_NAMESPACE::VRPNTrackerServer::packageTime [protected] | 
        
Definition at line 30 of file VRPNTrackerServer.hpp.
vrpn_float64 TELEKYB_NAMESPACE::VRPNTrackerServer::position[3] [protected] | 
        
Definition at line 28 of file VRPNTrackerServer.hpp.
vrpn_float64 TELEKYB_NAMESPACE::VRPNTrackerServer::rotation[4] [protected] | 
        
Definition at line 29 of file VRPNTrackerServer.hpp.
Definition at line 33 of file VRPNTrackerServer.hpp.
vrpn_Tracker_Server* TELEKYB_NAMESPACE::VRPNTrackerServer::vts [protected] | 
        
Definition at line 26 of file VRPNTrackerServer.hpp.