time_handler.cpp
Go to the documentation of this file.
1 //
3 // Copyright (c) 2020 NovAtel Inc.
4 //
5 // Permission is hereby granted, free of charge, to any person obtaining a copy
6 // of this software and associated documentation files (the "Software"), to deal
7 // in the Software without restriction, including without limitation the rights
8 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 // copies of the Software, and to permit persons to whom the Software is
10 // furnished to do so, subject to the following conditions:
11 //
12 // The above copyright notice and this permission notice shall be included in all
13 // copies or substantial portions of the Software.
14 //
15 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 // SOFTWARE.
22 //
24 
26 
27 #include <oem7_ros_publisher.hpp>
28 
29 #include <ros/ros.h>
30 
32 
33 #include "novatel_oem7_msgs/TIME.h"
34 
35 namespace novatel_oem7_driver
36 {
38  {
40 
41 
42  void publishTIME(Oem7RawMessageIf::ConstPtr msg)
43  {
45  MakeROSMessage(msg, time);
46  TIME_pub_.publish(time);
47  }
48 
49  public:
51  {
52  }
53 
55  {
56  }
57 
59  {
60  TIME_pub_.setup<novatel_oem7_msgs::TIME>("TIME", nh);
61  }
62 
63  const std::vector<int>& getMessageIds()
64  {
65  static const std::vector<int> MSG_IDS({TIME_OEM7_MSGID});
66  return MSG_IDS;
67  }
68 
69  void handleMsg(Oem7RawMessageIf::ConstPtr msg)
70  {
71  publishTIME(msg);
72  }
73  };
74 }
75 
void publishTIME(Oem7RawMessageIf::ConstPtr msg)
const std::vector< int > & getMessageIds()
void initialize(ros::NodeHandle &nh)
void handleMsg(Oem7RawMessageIf::ConstPtr msg)
void publish(boost::shared_ptr< M > &msg)
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
void setup(const std::string &name, ros::NodeHandle &nh)
void MakeROSMessage(const Oem7RawMessageIf::ConstPtr &msg, boost::shared_ptr< T > &rosmsg)


novatel_oem7_driver
Author(s):
autogenerated on Tue Mar 9 2021 03:48:00