time_processor.h
Go to the documentation of this file.
1 
25 #ifndef MESSAGE_RELAY_PROCESSOR_TIME_PROCESSOR_H
26 #define MESSAGE_RELAY_PROCESSOR_TIME_PROCESSOR_H
27 
28 #include "ros/ros.h"
29 
30 #include <boost/unordered_map.hpp>
31 #include <string>
32 #include <vector>
33 
34 namespace message_relay
35 {
36 
38 {
39 public:
41 
42  enum Operation
43  {
45  };
46 
47  static ConstPtr create(std::string offset_operation_string, ros::Duration offset = ros::Duration(0.0));
48 
49  static ConstPtr create(Operation offset_operation, ros::Duration offset = ros::Duration(0.0));
50 
51  void process(ros::Time &time) const;
52 
53  static ConstPtr inverse(const ConstPtr &processor);
54 
55 private:
56  TimeProcessor(Operation offset_operation, ros::Duration offset);
57 
58  static const boost::unordered_map<std::string, Operation> operation_name_map_;
59  static const boost::unordered_map<Operation, Operation> operation_inverse_map_;
60 
63 };
64 
65 } // namespace message_relay
66 
67 #endif // MESSAGE_RELAY_PROCESSOR_TIME_PROCESSOR_H
boost::shared_ptr< const TimeProcessor > ConstPtr
static const boost::unordered_map< Operation, Operation > operation_inverse_map_
void process(ros::Time &time) const
static ConstPtr inverse(const ConstPtr &processor)
static ConstPtr create(std::string offset_operation_string, ros::Duration offset=ros::Duration(0.0))
static const boost::unordered_map< std::string, Operation > operation_name_map_
TimeProcessor(Operation offset_operation, ros::Duration offset)


message_relay
Author(s):
autogenerated on Wed Jul 17 2019 03:27:53