oem7_message_handler_if.hpp
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 
25 #ifndef __OEM7_MESSAGE_HANDLER_IF_HPP__
26 #define __OEM7_MESSAGE_HANDLER_IF_HPP__
27 
28 
29 #include <ros/ros.h>
30 
31 #include <vector>
32 
33 #include "oem7_raw_message_if.hpp"
35 
36 namespace novatel_oem7_driver
37 {
42  {
43  public:
44  virtual ~Oem7MessageHandlerIf(){};
45 
49  virtual void initialize(ros::NodeHandle&) = 0;
50 
54  virtual const std::vector<int>& getMessageIds() = 0;
55 
59  virtual void handleMsg(Oem7RawMessageIf::ConstPtr msg) = 0;
60  };
61 }
62 
63 
64 #endif
virtual void handleMsg(Oem7RawMessageIf::ConstPtr msg)=0
virtual const std::vector< int > & getMessageIds()=0
virtual void initialize(ros::NodeHandle &)=0


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