oem7_ros_publisher.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_ROS_PUBLISHER_HPP__
26 #define __OEM7_ROS_PUBLISHER_HPP__
27 
28 
30 
31 
32 namespace novatel_oem7_driver
33 {
34 
39 {
41 
42  std::string frame_id_;
43 
44 public:
45 
46  template<typename M>
47  void setup(const std::string& name, ros::NodeHandle& nh)
48  {
49  typedef std::map<std::string, std::string> message_config_map_t;
50 
51  message_config_map_t message_config_map;
52  nh.getParam(name, message_config_map);
53 
54  message_config_map_t::iterator topic_itr = message_config_map.find("topic");
55  if(topic_itr == message_config_map.end())
56  {
57  ROS_WARN_STREAM("Message '" << name << "' will not be published.");
58  return;
59  }
60 
61  int queue_size = 100; // default size
62 
63  message_config_map_t::iterator q_size_itr = message_config_map.find("queue_size");
64  if(q_size_itr != message_config_map.end())
65  {
66  std::stringstream ss(q_size_itr->second);
67  ss >> queue_size;
68  }
69 
70  message_config_map_t::iterator frame_id_itr = message_config_map.find("frame_id");
71  if(frame_id_itr != message_config_map.end())
72  {
73  frame_id_ = frame_id_itr->second;
74  }
75 
76  ROS_INFO_STREAM("topic [" << topic_itr->second << "]: frame_id: '" << frame_id_ << "'; q size: " << queue_size);
77  ros_pub_ = nh.advertise<M>(topic_itr->second, queue_size);
78  }
79 
83  bool isEnabled()
84  {
85  return !ros_pub_.getTopic().empty();
86  }
87 
91  template <typename M>
93  {
94  if(!isEnabled())
95  {
96  return;
97  }
98 
99  SetROSHeader(frame_id_, msg);
100  ros_pub_.publish(msg);
101  }
102 
103 };
104 
105 }
106 #endif
void publish(const boost::shared_ptr< M > &message) const
std::string frame_id_
Configurable frame ID.
ros::Publisher ros_pub_
ROS publisher.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
void publish(boost::shared_ptr< M > &msg)
void setup(const std::string &name, ros::NodeHandle &nh)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
void SetROSHeader(const std::string &frame_id, boost::shared_ptr< T > &msg)
std::string getTopic() const


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