oem7_message_decoder.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 
27 
28 #include <ros/console.h>
29 
30 
31 #include <boost/scoped_ptr.hpp>
33 
34 #include "oem7_debug_file.hpp"
35 
36 
37 
38 namespace novatel_oem7_driver
39 {
40 
41  /***
42  * Parser for Oem7 messages. Obtains serial input from Oem7RawMessageParserIf; makes callbacks on Oem7RawMessageParserUserIf when Oem7 messages.
43  */
45  {
46  ros::NodeHandle nh_; // ROS Node Handle.
47 
50 
51 
52  Oem7MessageDecoderUserIf* user_; //< Parser user callback interface
53 
55 
57 
58 
59  public:
60 
64  bool initialize(
65  ros::NodeHandle& nh,
68  {
69  nh_ = nh;
70  user_ = user;
71  recvr_ = recvr;
72 
73  novatel_oem7::version_element_t major, minor, build;
75 
76  ROS_INFO_STREAM("Oem7MessageDecoderLib version: " << major << "." << minor << "." << build);
77 
79 
80  std::string decoder_dbg_file_name;
81  std::string receiver_dbg_file_name;
82  nh_.getParam("oem7_receiver_log_file", receiver_dbg_file_name);
83  nh_.getParam("oem7_decoder_log_file", decoder_dbg_file_name);
84 
85  decoder_dbg_file_.initialize( decoder_dbg_file_name);
86  receiver_dbg_file_.initialize(receiver_dbg_file_name);
87 
88 
89  return true;
90  }
91 
92  virtual bool read( boost::asio::mutable_buffer buf, size_t& s)
93  {
94  bool ok = recvr_->read(buf, s);
95  if(ok)
96  {
97  receiver_dbg_file_.write(boost::asio::buffer_cast<unsigned char*>(buf), s);
98  }
99 
100  return ok;
101  }
102 
103 
104  /*
105  * Parser service loop.
106  * Drive the parser forward to keep reading from its input stream and making message callbacks into user.
107  * Blocks until:
108  * The system is shut down / ros::ok() returns false
109  * No more input available (as a permanent condition),
110  */
111  void service()
112  {
113  try
114  {
115  while(!ros::isShuttingDown())
116  {
118  if(decoder_->readMessage(msg))
119  {
120  if(msg)
121  {
122  decoder_dbg_file_.write(msg->getMessageData(0), msg->getMessageDataLength());
123 
124  user_->onNewMessage(msg);
125  }
126  // else: No messages available now; keep retrying until we get one or decoder gives up.
127  }
128  else
129  {
130  ROS_WARN("Decoder: no more messages available.");
131  break;
132  }
133  }
134  }
135  catch(std::exception const& ex)
136  {
137  ROS_ERROR_STREAM("Decoder exception: " << ex.what());
138  }
139  }
140  };
141 
142 }
143 
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr< novatel_oem7::Oem7MessageDecoderLibIf >
novatel_oem7_driver::Oem7DebugFile
Definition: oem7_debug_file.hpp:37
s
XmlRpcServer s
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
novatel_oem7_driver::Oem7MessageDecoderUserIf
Definition: oem7_message_decoder_if.hpp:44
novatel_oem7_driver::Oem7MessageDecoder
Definition: oem7_message_decoder.cpp:44
novatel_oem7_driver::Oem7MessageDecoder::nh_
ros::NodeHandle nh_
Definition: oem7_message_decoder.cpp:48
novatel_oem7_driver::Oem7DebugFile::write
virtual bool write(const unsigned char *buf, size_t len)
Definition: oem7_debug_file.cpp:63
novatel_oem7_driver::Oem7DebugFile::initialize
virtual bool initialize(std::string &debug_file_name)
Definition: oem7_debug_file.cpp:36
ok
ROSCPP_DECL bool ok()
novatel_oem7_driver::Oem7MessageDecoderUserIf::onNewMessage
virtual void onNewMessage(boost::shared_ptr< const novatel_oem7::Oem7RawMessageIf >)=0
novatel_oem7_driver::Oem7MessageDecoder::service
void service()
Definition: oem7_message_decoder.cpp:113
novatel_oem7_driver::Oem7ReceiverIf
Definition: oem7_receiver_if.hpp:38
novatel_oem7_driver::Oem7MessageDecoder::decoder_
boost::shared_ptr< novatel_oem7::Oem7MessageDecoderLibIf > decoder_
Definition: oem7_message_decoder.cpp:58
class_list_macros.h
console.h
oem7_message_decoder_if.hpp
novatel_oem7_driver::Oem7ReceiverIf::read
virtual bool read(boost::asio::mutable_buffer, size_t &)=0
novatel_oem7_driver::Oem7MessageDecoder::decoder_dbg_file_
Oem7DebugFile decoder_dbg_file_
Definition: oem7_message_decoder.cpp:50
novatel_oem7_driver::Oem7MessageDecoderIf
Definition: oem7_message_decoder_if.hpp:61
novatel_oem7::version_element_t
short version_element_t
Definition: oem7_message_decoder_lib.hpp:37
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
ROS_WARN
#define ROS_WARN(...)
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
novatel_oem7_driver::Oem7MessageDecoder::read
virtual bool read(boost::asio::mutable_buffer buf, size_t &s)
Definition: oem7_message_decoder.cpp:94
novatel_oem7_driver::Oem7MessageDecoder::recvr_
Oem7ReceiverIf * recvr_
Definition: oem7_message_decoder.cpp:56
oem7_debug_file.hpp
ros::isShuttingDown
ROSCPP_DECL bool isShuttingDown()
novatel_oem7::GetOem7MessageDecoderLibVersion
void GetOem7MessageDecoderLibVersion(version_element_t &major, version_element_t &minor, version_element_t &spec)
Definition: oem7_message_decoder_lib.cpp:215
novatel_oem7_driver::Oem7MessageDecoder::user_
Oem7MessageDecoderUserIf * user_
Definition: oem7_message_decoder.cpp:54
novatel_oem7::GetOem7MessageDecoder
boost::shared_ptr< Oem7MessageDecoderLibIf > GetOem7MessageDecoder(Oem7MessageDecoderLibUserIf *user)
Definition: oem7_message_decoder_lib.cpp:208
novatel_oem7::Oem7MessageDecoderLibUserIf
Definition: oem7_message_decoder_lib.hpp:48
oem7_receiver_if.hpp
novatel_oem7_driver::Oem7MessageDecoder::initialize
bool initialize(ros::NodeHandle &nh, Oem7ReceiverIf *recvr, Oem7MessageDecoderUserIf *user)
Definition: oem7_message_decoder.cpp:66
oem7_message_decoder_lib.hpp
novatel_oem7_driver
Definition: oem7_imu.hpp:25
novatel_oem7_driver::Oem7MessageDecoder::receiver_dbg_file_
Oem7DebugFile receiver_dbg_file_
Definition: oem7_message_decoder.cpp:51
ros::NodeHandle


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