EEROS  1.0.0.0
API for the EEROS Real-Time Robotics Framework
EerosRosTools.hpp
Go to the documentation of this file.
1 #ifndef EEROS_ROS_TOOLS_HPP
2 #define EEROS_ROS_TOOLS_HPP
3 
4 #include <ros/ros.h>
5 #include <std_msgs/Header.h>
6 
7 #define NS_PER_SEC 1000000000
8 
9 namespace eeros {
10  namespace control {
11  namespace rosTools {
12  static ros::Time convertToRosTime(uint64_t timestampNs) {
13  ros::Time t;
14  t.sec = static_cast<double>(timestampNs) / NS_PER_SEC;
15  t.nsec = timestampNs % static_cast<uint64_t>(1e9);
16  return t;
17  }
18 
19  static void initNode(std::string name) {
20  char* args[] = {NULL};
21  int argc = sizeof(args)/sizeof(args[0]) - 1;
22  ros::init(argc, args, name); // init ROS node and name it
23  }
24  };
25  };
26 };
27 
28 
29 
30 #endif /* EEROS_ROS_TOOLS_HPP */
#define NS_PER_SEC
Definition: EerosRosTools.hpp:7
Definition: Config.hpp:14