Go to the documentation of this file.
32 #ifndef VRPN_CLIENT_ROS_VRPN_CLIENT_ROS_H
33 #define VRPN_CLIENT_ROS_VRPN_CLIENT_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"
43 #include <vrpn_Tracker.h>
44 #include <vrpn_Connection.h>
47 #include <unordered_map>
59 typedef std::shared_ptr<VrpnTrackerRos>
Ptr;
95 static void VRPN_CALLBACK
handle_pose(
void *userData,
const vrpn_TRACKERCB tracker_pose);
97 static void VRPN_CALLBACK
handle_twist(
void *userData,
const vrpn_TRACKERVELCB tracker_twist);
99 static void VRPN_CALLBACK
handle_accel(
void *userData,
const vrpn_TRACKERACCCB tracker_accel);
106 typedef std::shared_ptr<VrpnClientRos>
Ptr;
107 typedef std::unordered_map<std::string, VrpnTrackerRos::Ptr>
TrackerMap;
144 #endif // VRPN_CLIENT_ROS_VRPN_CLIENT_ROS_H
static std::string getHostStringFromParams(ros::NodeHandle host_nh)
geometry_msgs::PoseStamped pose_msg_
std::vector< ros::Publisher > twist_pubs_
geometry_msgs::AccelStamped accel_msg_
std::shared_ptr< vrpn_Connection > ConnectionPtr
VrpnTrackerRos(std::string tracker_name, ConnectionPtr connection, ros::NodeHandle nh)
std::shared_ptr< vrpn_Tracker_Remote > TrackerRemotePtr
VrpnClientRos(ros::NodeHandle nh, ros::NodeHandle private_nh)
ros::Timer mainloop_timer
ros::NodeHandle output_nh_
std::shared_ptr< VrpnTrackerRos > Ptr
void init(std::string tracker_name, ros::NodeHandle nh, bool create_mainloop_timer)
static void VRPN_CALLBACK handle_twist(void *userData, const vrpn_TRACKERVELCB tracker_twist)
ConnectionPtr connection_
std::vector< ros::Publisher > pose_pubs_
TrackerRemotePtr tracker_remote_
std::shared_ptr< VrpnClientRos > Ptr
geometry_msgs::TwistStamped twist_msg_
ros::Timer refresh_tracker_timer_
static void VRPN_CALLBACK handle_accel(void *userData, const vrpn_TRACKERACCCB tracker_accel)
ros::Timer mainloop_timer
std::vector< ros::Publisher > accel_pubs_
geometry_msgs::TransformStamped transform_stamped_
ros::NodeHandle output_nh_
static void VRPN_CALLBACK handle_pose(void *userData, const vrpn_TRACKERCB tracker_pose)
std::unordered_map< std::string, VrpnTrackerRos::Ptr > TrackerMap
vrpn_client_ros
Author(s): Paul Bovbel
autogenerated on Wed Mar 2 2022 01:11:15