vrpn_client_ros.h
Go to the documentation of this file.
1 
32 #ifndef VRPN_CLIENT_ROS_VRPN_CLIENT_ROS_H
33 #define VRPN_CLIENT_ROS_VRPN_CLIENT_ROS_H
34 
36 
37 #include "ros/ros.h"
38 #include "geometry_msgs/PoseStamped.h"
39 #include "geometry_msgs/TwistStamped.h"
40 #include "geometry_msgs/AccelStamped.h"
41 #include "geometry_msgs/TransformStamped.h"
42 
43 #include <vrpn_Tracker.h>
44 #include <vrpn_Connection.h>
45 #include <map>
46 #include <string>
47 #include <unordered_map>
48 
49 namespace vrpn_client_ros
50 {
51 
52  typedef std::shared_ptr<vrpn_Connection> ConnectionPtr;
53  typedef std::shared_ptr<vrpn_Tracker_Remote> TrackerRemotePtr;
54 
56  {
57  public:
58 
59  typedef std::shared_ptr<VrpnTrackerRos> Ptr;
64  VrpnTrackerRos(std::string tracker_name, ConnectionPtr connection, ros::NodeHandle nh);
65 
70  VrpnTrackerRos(std::string tracker_name, std::string host, ros::NodeHandle nh);
71 
73 
77  void mainloop();
78 
79  private:
81  std::vector<ros::Publisher> pose_pubs_, twist_pubs_, accel_pubs_;
84  std::string tracker_name;
85 
87 
88  geometry_msgs::PoseStamped pose_msg_;
89  geometry_msgs::TwistStamped twist_msg_;
90  geometry_msgs::AccelStamped accel_msg_;
91  geometry_msgs::TransformStamped transform_stamped_;
92 
93  void init(std::string tracker_name, ros::NodeHandle nh, bool create_mainloop_timer);
94 
95  static void VRPN_CALLBACK handle_pose(void *userData, const vrpn_TRACKERCB tracker_pose);
96 
97  static void VRPN_CALLBACK handle_twist(void *userData, const vrpn_TRACKERVELCB tracker_twist);
98 
99  static void VRPN_CALLBACK handle_accel(void *userData, const vrpn_TRACKERACCCB tracker_accel);
100  };
101 
103  {
104  public:
105 
106  typedef std::shared_ptr<VrpnClientRos> Ptr;
107  typedef std::unordered_map<std::string, VrpnTrackerRos::Ptr> TrackerMap;
108 
113 
114  static std::string getHostStringFromParams(ros::NodeHandle host_nh);
115 
119  void mainloop();
120 
124  void updateTrackers();
125 
126  private:
127  std::string host_;
129 
134 
139 
141  };
142 } // namespace vrpn_client_ros
143 
144 #endif // VRPN_CLIENT_ROS_VRPN_CLIENT_ROS_H
vrpn_client_ros::VrpnClientRos::getHostStringFromParams
static std::string getHostStringFromParams(ros::NodeHandle host_nh)
Definition: vrpn_client_ros.cpp:371
vrpn_client_ros::VrpnClientRos::updateTrackers
void updateTrackers()
Definition: vrpn_client_ros.cpp:400
vrpn_client_ros::VrpnTrackerRos::broadcast_tf_
bool broadcast_tf_
Definition: vrpn_client_ros.h:83
vrpn_client_ros.h
vrpn_client_ros::VrpnTrackerRos::pose_msg_
geometry_msgs::PoseStamped pose_msg_
Definition: vrpn_client_ros.h:88
vrpn_client_ros::VrpnTrackerRos::twist_pubs_
std::vector< ros::Publisher > twist_pubs_
Definition: vrpn_client_ros.h:81
vrpn_client_ros::VrpnTrackerRos::accel_msg_
geometry_msgs::AccelStamped accel_msg_
Definition: vrpn_client_ros.h:90
vrpn_client_ros::ConnectionPtr
std::shared_ptr< vrpn_Connection > ConnectionPtr
Definition: vrpn_client_ros.h:52
ros.h
vrpn_client_ros::VrpnTrackerRos::VrpnTrackerRos
VrpnTrackerRos(std::string tracker_name, ConnectionPtr connection, ros::NodeHandle nh)
Definition: vrpn_client_ros.cpp:63
vrpn_client_ros::TrackerRemotePtr
std::shared_ptr< vrpn_Tracker_Remote > TrackerRemotePtr
Definition: vrpn_client_ros.h:53
vrpn_client_ros::VrpnClientRos::VrpnClientRos
VrpnClientRos(ros::NodeHandle nh, ros::NodeHandle private_nh)
Definition: vrpn_client_ros.cpp:337
vrpn_client_ros::VrpnClientRos::mainloop_timer
ros::Timer mainloop_timer
Definition: vrpn_client_ros.h:140
vrpn_client_ros::VrpnTrackerRos::output_nh_
ros::NodeHandle output_nh_
Definition: vrpn_client_ros.h:82
vrpn_client_ros::VrpnTrackerRos::Ptr
std::shared_ptr< VrpnTrackerRos > Ptr
Definition: vrpn_client_ros.h:59
vrpn_client_ros::VrpnTrackerRos::init
void init(std::string tracker_name, ros::NodeHandle nh, bool create_mainloop_timer)
Definition: vrpn_client_ros.cpp:92
vrpn_client_ros::VrpnClientRos::trackers_
TrackerMap trackers_
Definition: vrpn_client_ros.h:138
vrpn_client_ros::VrpnTrackerRos::handle_twist
static void VRPN_CALLBACK handle_twist(void *userData, const vrpn_TRACKERVELCB tracker_twist)
Definition: vrpn_client_ros.cpp:227
vrpn_client_ros::VrpnClientRos::connection_
ConnectionPtr connection_
Definition: vrpn_client_ros.h:133
vrpn_client_ros::VrpnTrackerRos::pose_pubs_
std::vector< ros::Publisher > pose_pubs_
Definition: vrpn_client_ros.h:81
vrpn_client_ros::VrpnTrackerRos::use_server_time_
bool use_server_time_
Definition: vrpn_client_ros.h:83
vrpn_client_ros::VrpnClientRos::host_
std::string host_
Definition: vrpn_client_ros.h:127
vrpn_client_ros::VrpnTrackerRos::tracker_remote_
TrackerRemotePtr tracker_remote_
Definition: vrpn_client_ros.h:80
vrpn_client_ros::VrpnClientRos
Definition: vrpn_client_ros.h:102
vrpn_client_ros::VrpnClientRos::Ptr
std::shared_ptr< VrpnClientRos > Ptr
Definition: vrpn_client_ros.h:106
vrpn_client_ros::VrpnTrackerRos::mainloop
void mainloop()
Definition: vrpn_client_ros.cpp:137
vrpn_client_ros::VrpnTrackerRos::process_sensor_id_
bool process_sensor_id_
Definition: vrpn_client_ros.h:83
vrpn_client_ros::VrpnTrackerRos::twist_msg_
geometry_msgs::TwistStamped twist_msg_
Definition: vrpn_client_ros.h:89
vrpn_client_ros::VrpnTrackerRos::~VrpnTrackerRos
~VrpnTrackerRos()
Definition: vrpn_client_ros.cpp:129
vrpn_client_ros::VrpnClientRos::mainloop
void mainloop()
Definition: vrpn_client_ros.cpp:387
vrpn_client_ros::VrpnClientRos::refresh_tracker_timer_
ros::Timer refresh_tracker_timer_
Definition: vrpn_client_ros.h:140
vrpn_client_ros::VrpnTrackerRos::tracker_name
std::string tracker_name
Definition: vrpn_client_ros.h:84
vrpn_client_ros::VrpnTrackerRos::handle_accel
static void VRPN_CALLBACK handle_accel(void *userData, const vrpn_TRACKERACCCB tracker_accel)
Definition: vrpn_client_ros.cpp:282
vrpn_client_ros::VrpnTrackerRos::mainloop_timer
ros::Timer mainloop_timer
Definition: vrpn_client_ros.h:86
vrpn_client_ros::VrpnTrackerRos::accel_pubs_
std::vector< ros::Publisher > accel_pubs_
Definition: vrpn_client_ros.h:81
vrpn_client_ros::VrpnTrackerRos
Definition: vrpn_client_ros.h:55
vrpn_client_ros::VrpnTrackerRos::transform_stamped_
geometry_msgs::TransformStamped transform_stamped_
Definition: vrpn_client_ros.h:91
vrpn_client_ros
Definition: vrpn_client_ros.h:49
vrpn_client_ros::VrpnClientRos::output_nh_
ros::NodeHandle output_nh_
Definition: vrpn_client_ros.h:128
vrpn_client_ros::VrpnTrackerRos::handle_pose
static void VRPN_CALLBACK handle_pose(void *userData, const vrpn_TRACKERCB tracker_pose)
Definition: vrpn_client_ros.cpp:142
vrpn_client_ros::VrpnClientRos::TrackerMap
std::unordered_map< std::string, VrpnTrackerRos::Ptr > TrackerMap
Definition: vrpn_client_ros.h:107
ros::Timer
ros::NodeHandle


vrpn_client_ros
Author(s): Paul Bovbel
autogenerated on Wed Mar 2 2022 01:11:15