Public Types | Public Member Functions | Static Public Member Functions | Private Attributes | List of all members
vrpn_client_ros::VrpnClientRos Class Reference

#include <vrpn_client_ros.h>

Public Types

typedef std::shared_ptr< VrpnClientRosPtr
 
typedef std::unordered_map< std::string, VrpnTrackerRos::PtrTrackerMap
 

Public Member Functions

void mainloop ()
 
void updateTrackers ()
 
 VrpnClientRos (ros::NodeHandle nh, ros::NodeHandle private_nh)
 

Static Public Member Functions

static std::string getHostStringFromParams (ros::NodeHandle host_nh)
 

Private Attributes

ConnectionPtr connection_
 
std::string host_
 
ros::Timer mainloop_timer
 
ros::NodeHandle output_nh_
 
ros::Timer refresh_tracker_timer_
 
TrackerMap trackers_
 

Detailed Description

Definition at line 102 of file vrpn_client_ros.h.

Member Typedef Documentation

Definition at line 106 of file vrpn_client_ros.h.

typedef std::unordered_map<std::string, VrpnTrackerRos::Ptr> vrpn_client_ros::VrpnClientRos::TrackerMap

Definition at line 107 of file vrpn_client_ros.h.

Constructor & Destructor Documentation

vrpn_client_ros::VrpnClientRos::VrpnClientRos ( ros::NodeHandle  nh,
ros::NodeHandle  private_nh 
)

Create and initialize VrpnClientRos object in the private_nh namespace.

Definition at line 337 of file vrpn_client_ros.cpp.

Member Function Documentation

std::string vrpn_client_ros::VrpnClientRos::getHostStringFromParams ( ros::NodeHandle  host_nh)
static

Definition at line 371 of file vrpn_client_ros.cpp.

void vrpn_client_ros::VrpnClientRos::mainloop ( )

Call mainloop of underlying VRPN connection and all registered VrpnTrackerRemote objects.

Definition at line 387 of file vrpn_client_ros.cpp.

void vrpn_client_ros::VrpnClientRos::updateTrackers ( )

Examine vrpn_Connection's senders and create new trackers as necessary.

Definition at line 400 of file vrpn_client_ros.cpp.

Member Data Documentation

ConnectionPtr vrpn_client_ros::VrpnClientRos::connection_
private

Underlying VRPN connection object

Definition at line 133 of file vrpn_client_ros.h.

std::string vrpn_client_ros::VrpnClientRos::host_
private

Definition at line 127 of file vrpn_client_ros.h.

ros::Timer vrpn_client_ros::VrpnClientRos::mainloop_timer
private

Definition at line 140 of file vrpn_client_ros.h.

ros::NodeHandle vrpn_client_ros::VrpnClientRos::output_nh_
private

Definition at line 128 of file vrpn_client_ros.h.

ros::Timer vrpn_client_ros::VrpnClientRos::refresh_tracker_timer_
private

Definition at line 140 of file vrpn_client_ros.h.

TrackerMap vrpn_client_ros::VrpnClientRos::trackers_
private

Map of registered trackers, accessible by name

Definition at line 138 of file vrpn_client_ros.h.


The documentation for this class was generated from the following files:


vrpn_client_ros
Author(s): Paul Bovbel
autogenerated on Sat Jun 8 2019 04:44:59