clock_relay_node.cpp
Go to the documentation of this file.
1 
26 #include "ros/ros.h"
27 
28 #include <vector>
29 #include <string>
30 
31 int main(int argc, char *argv[])
32 {
33  ros::init(argc, argv, "clock_relay_node");
34 
35  ros::NodeHandle private_nh("~");
36 
37  std::string parameter_namespace;
38  if (private_nh.getParam("parameter_namespace", parameter_namespace))
39  {
40  private_nh = ros::NodeHandle(parameter_namespace);
41  }
42 
43  std::string from, to;
44  if (!private_nh.getParam("from", from) && !private_nh.getParam("to", to))
45  {
46  ROS_FATAL("Must provide either 'from' and 'to' namespace parameters");
47  return 1;
48  }
49 
50  if (from == to)
51  {
52  ROS_FATAL("'from' and 'to' namespaces must not be equal");
53  return 1;
54  }
55 
56  ros::NodeHandle origin(from), target(to);
57 
58  std::string clock_relay_type;
59  if (!private_nh.getParam("clock_relay_type", clock_relay_type))
60  {
61  ROS_FATAL_STREAM("Must specify if clock relay type is source or sink");
62  return 1;
63  }
64 
65  double throttle_frequency = 0.0;
66  std::string key;
67  if (private_nh.searchParam("throttle_frequency", key))
68  {
69  std::string val;
70  private_nh.getParam(key, throttle_frequency);
71  }
72 
73  clock_relay::ClockRelay clock_relay(from, to, clock_relay_type, throttle_frequency);
74 
75  ros::spin();
76 
77  return 0;
78 }
#define ROS_FATAL(...)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char *argv[])
#define ROS_FATAL_STREAM(args)
bool searchParam(const std::string &key, std::string &result) const
bool getParam(const std::string &key, std::string &s) const


clock_relay
Author(s):
autogenerated on Wed Jul 17 2019 03:27:57