oem7_log_nodelet.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 <ros/ros.h>
26 #include <nodelet/nodelet.h>
27 
28 #include <message_handler.hpp>
29 
30 #include "novatel_oem7_msgs/Oem7RawMsg.h"
32 
33 #include <boost/scoped_ptr.hpp>
34 
35 namespace novatel_oem7_driver
36 {
37 
38  /*
39  * Adapter: novatel_oem7_msgs::Oem7RawMsg and Oem7RawMsgIf
40  */
42  {
43  public:
44  const novatel_oem7_msgs::Oem7RawMsg::ConstPtr msg_;
45 
46  RawMsgAdapter(const novatel_oem7_msgs::Oem7RawMsg::ConstPtr& msg):
47  msg_(msg)
48  {
49  }
50 
52  {
53  assert(false);
54  return Oem7RawMessageIf::OEM7MSGTYPE_UNKNOWN;
55  }
56 
58  {
59  assert(false);
60  return Oem7RawMessageIf::OEM7MSGFMT_UNKNOWN;
61  }
62 
63  int getMessageId() const
64  {
65  const Oem7MessageCommonHeaderMem* mem =
66  reinterpret_cast<const Oem7MessageCommonHeaderMem*>(getMessageData(0));
67  return mem->message_id;
68  }
69 
70  const uint8_t* getMessageData(size_t offset) const
71  {
72  return const_cast<uint8_t*>(msg_->message_data.data()); // FIXME
73  }
74 
75  size_t getMessageDataLength() const
76  {
77  return msg_->message_data.size();
78  }
79  };
80  /*
81  * Nodelet responsible for decoding raw Oem7 messages and generating specific ROS and novatel_oem7_msg messages.
82  * Subscribes to "oem7_raw_msg", and loads plugins which advertise specific messages.
83  * Raw oem7 messages are dispatched to plugins for decoding.
84  */
86  {
87  boost::scoped_ptr<MessageHandler> msg_handler_;
88 
90 
91 
92  public:
94  {
95  }
96 
97  void onInit()
98  {
101  msg_handler_.reset(new MessageHandler(priv_nh));
102 
103  oem7_raw_msg_sub_ = nh.subscribe("oem7_raw_msg", 100, &Oem7LogNodelet::oem7RawMsgCb, this);
104  }
105 
109  void oem7RawMsgCb(const novatel_oem7_msgs::Oem7RawMsg::ConstPtr& msg)
110  {
111  boost::shared_ptr<RawMsgAdapter> raw_msg = boost::make_shared<RawMsgAdapter>(msg);
112  msg_handler_->handleMessage(raw_msg);
113  }
114  };
115 }
116 
117 
novatel_oem7_driver::Oem7LogNodelet::msg_handler_
boost::scoped_ptr< MessageHandler > msg_handler_
Definition: oem7_log_nodelet.cpp:87
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
boost::shared_ptr
ros.h
novatel_oem7_driver::Oem7LogNodelet::oem7RawMsgCb
void oem7RawMsgCb(const novatel_oem7_msgs::Oem7RawMsg::ConstPtr &msg)
Definition: oem7_log_nodelet.cpp:109
novatel_oem7_driver::Oem7LogNodelet::oem7_raw_msg_sub_
ros::Subscriber oem7_raw_msg_sub_
Definition: oem7_log_nodelet.cpp:89
novatel_oem7_driver::RawMsgAdapter::getMessageDataLength
size_t getMessageDataLength() const
Definition: oem7_log_nodelet.cpp:75
novatel_oem7::Oem7RawMessageIf::Oem7MessageFormat
Oem7MessageFormat
Definition: oem7_raw_message_if.hpp:49
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
novatel_oem7_driver::RawMsgAdapter::getMessageFormat
Oem7MessageFormat getMessageFormat() const
Definition: oem7_log_nodelet.cpp:57
novatel_oem7::Oem7RawMessageIf::Oem7MessageType
Oem7MessageType
Definition: oem7_raw_message_if.hpp:41
novatel_oem7_driver::MessageHandler
Definition: message_handler.hpp:47
message_handler.hpp
novatel_oem7_driver::Oem7LogNodelet::onInit
void onInit()
Definition: oem7_log_nodelet.cpp:97
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
novatel_oem7_driver::RawMsgAdapter::getMessageData
const uint8_t * getMessageData(size_t offset) const
Definition: oem7_log_nodelet.cpp:70
novatel_oem7_driver::RawMsgAdapter::getMessageType
Oem7MessageType getMessageType() const
Definition: oem7_log_nodelet.cpp:51
novatel_oem7_driver::RawMsgAdapter::getMessageId
int getMessageId() const
Definition: oem7_log_nodelet.cpp:63
novatel_oem7_driver::Oem7LogNodelet::Oem7LogNodelet
Oem7LogNodelet()
Definition: oem7_log_nodelet.cpp:93
nodelet::Nodelet
novatel_oem7_driver::RawMsgAdapter
Definition: oem7_log_nodelet.cpp:41
nodelet.h
oem7_messages.h
novatel_oem7_driver::RawMsgAdapter::msg_
const novatel_oem7_msgs::Oem7RawMsg::ConstPtr msg_
Definition: oem7_log_nodelet.cpp:44
novatel_oem7::Oem7RawMessageIf
Definition: oem7_raw_message_if.hpp:35
novatel_oem7_driver::Oem7LogNodelet
Definition: oem7_log_nodelet.cpp:85
novatel_oem7_driver::RawMsgAdapter::RawMsgAdapter
RawMsgAdapter(const novatel_oem7_msgs::Oem7RawMsg::ConstPtr &msg)
Definition: oem7_log_nodelet.cpp:46
novatel_oem7_driver
Definition: oem7_imu.hpp:25
ros::NodeHandle
ros::Subscriber
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7LogNodelet, nodelet::Nodelet)


novatel_oem7_driver
Author(s):
autogenerated on Sat Feb 3 2024 03:51:34