align_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 
27 
28 
29 #include <ros/ros.h>
30 
32 #include <novatel_oem7_msgs/HEADING2.h>
33 
34 #include <oem7_ros_publisher.hpp>
35 
36 
37 namespace novatel_oem7_driver
38 {
39 
40  /***
41  * Handler of ALIGH-related messages
42  */
44  {
46 
48  Oem7RawMessageIf::ConstPtr msg)
49  {
51  MakeROSMessage(msg, heading2);
52  HEADING2_pub_.publish(heading2);
53  }
54 
55  public:
57  {
58  }
59 
61  {
62  }
63 
65  {
66  HEADING2_pub_.setup<novatel_oem7_msgs::HEADING2>("HEADING2", nh);
67  }
68 
69  const std::vector<int>& getMessageIds()
70  {
71  static const std::vector<int> MSG_IDS({HEADING2_OEM7_MSGID});
72  return MSG_IDS;
73  }
74 
75  void handleMsg(Oem7RawMessageIf::ConstPtr msg)
76  {
77  ROS_DEBUG_STREAM("ALIGN < [id= " << msg->getMessageId() << "]");
78 
79  publishHEADING2(msg);
80  }
81  };
82 }
83 
void handleMsg(Oem7RawMessageIf::ConstPtr msg)
void initialize(ros::NodeHandle &nh)
const int HEADING2_OEM7_MSGID
void publishHEADING2(Oem7RawMessageIf::ConstPtr msg)
void publish(boost::shared_ptr< M > &msg)
#define ROS_DEBUG_STREAM(args)
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)
const std::vector< int > & getMessageIds()


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