src
vrpn_tracker_node.cpp
Go to the documentation of this file.
1
32
#include "
vrpn_client_ros/vrpn_client_ros.h
"
33
34
#include <string>
35
36
int
main
(
int
argc,
char
**argv)
37
{
38
ros::init
(argc, argv,
"vrpn_tracker_node"
);
39
ros::NodeHandle
nh, private_nh(
"~"
);
40
41
std::string tracker_name;
42
if
(!private_nh.
getParam
(
"tracker_name"
, tracker_name))
43
{
44
ROS_FATAL_STREAM
(
"Must provide paramter tracker_name for node "
<< private_nh.
getNamespace
());
45
}
46
47
std::string host =
vrpn_client_ros::VrpnClientRos::getHostStringFromParams
(private_nh);
48
vrpn_client_ros::VrpnTrackerRos
tracker(tracker_name, host, nh);
49
50
ros::spin
();
51
return
0;
52
}
vrpn_client_ros::VrpnClientRos::getHostStringFromParams
static std::string getHostStringFromParams(ros::NodeHandle host_nh)
Definition:
vrpn_client_ros.cpp:371
vrpn_client_ros.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ROS_FATAL_STREAM
#define ROS_FATAL_STREAM(args)
main
int main(int argc, char **argv)
Definition:
vrpn_tracker_node.cpp:36
vrpn_client_ros::VrpnTrackerRos
Definition:
vrpn_client_ros.h:55
ros::spin
ROSCPP_DECL void spin()
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
ros::NodeHandle
vrpn_client_ros
Author(s): Paul Bovbel
autogenerated on Wed Mar 2 2022 01:11:15