message_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 
25 #include "message_handler.hpp"
26 
27 #include <pluginlib/class_loader.h>
29 
30 
31 
32 namespace novatel_oem7_driver
33 {
38  msg_handler_loader_("novatel_oem7_driver", "novatel_oem7_driver::Oem7MessageHandlerIf")
39  {
40  // Load the plugins and create the dispatch table.
41  std::vector<std::string> msg_handler_names;
42  nh.getParam("oem7_msg_handlers", msg_handler_names);
43  for(const auto& name : msg_handler_names)
44  {
45  MessageHandlerShPtr msg_handler = msg_handler_loader_.createInstance(name);
46 
47  msg_handler->initialize(nh);
48 
49  for(int msg_id: msg_handler->getMessageIds())
50  {
51  MessageHandlerMap::iterator itr = msg_handler_map_.find(msg_id);
52  if(itr == msg_handler_map_.end())
53  {
54  msg_handler_map_[msg_id].reset(new MsgHandlerList);
55  }
56 
57  msg_handler_map_[msg_id]->push_back(msg_handler);
58  }
59  }
60  }
61 
65  void MessageHandler::handleMessage(Oem7RawMessageIf::ConstPtr raw_msg)
66  {
67  MessageHandlerMap::iterator itr = msg_handler_map_.find(raw_msg->getMessageId());
68  if(itr == msg_handler_map_.end())
69  {
70  ROS_DEBUG_STREAM("No handler for message ID= " << raw_msg->getMessageId());
71  return;
72  }
73 
74  MessageHandlerListPtr& msg_handler_list = itr->second;
75  for(auto& h: *msg_handler_list)
76  {
77  h->handleMsg(raw_msg);
78  }
79  }
80 }
81 
boost::scoped_ptr< MsgHandlerList > MessageHandlerListPtr
void handleMessage(Oem7RawMessageIf::ConstPtr raw_msg)
std::list< MessageHandlerShPtr > MsgHandlerList
MessageHandlerMap msg_handler_map_
Dispatch map for raw messages.
#define ROS_DEBUG_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
pluginlib::ClassLoader< novatel_oem7_driver::Oem7MessageHandlerIf > msg_handler_loader_
Plugin loader.


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