oem7_receiver_file.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 
26 
27 #include <ros/ros.h>
28 
29 #include <boost/asio.hpp>
30 #include <fstream>
31 
32 
33 namespace novatel_oem7_driver
34 {
39  {
40  std::ifstream oem7_file_;
41 
42  size_t num_byte_read_;
43 
44 
45  public:
47  num_byte_read_(0)
48  {
49  }
50 
52  {
53  }
54 
58  virtual bool initialize(ros::NodeHandle& nh)
59  {
60  std::string oem7_file_name;;
61  nh.getParam("oem7_file_name", oem7_file_name);
62 
63  ROS_INFO_STREAM("Oem7File['" << oem7_file_name << "']");
64 
65  oem7_file_.open(oem7_file_name, std::ios::in | std::ios::binary);
66  int errno_value = errno; // Cache errno locally, in case any ROS calls /macros affect it.
67  if(!oem7_file_)
68  {
69  ROS_ERROR_STREAM("Could not open '" << oem7_file_name << "'; error= " << errno_value << " '"
70  << strerror(errno_value) << "'");
71  return false;
72  }
73 
74  return true;
75  }
76 
81  virtual bool read( boost::asio::mutable_buffer buf, size_t& rlen)
82  {
83  if(!oem7_file_)
84  {
85  ROS_ERROR_STREAM("Error accessing file." );
86  return false;
87  }
88 
89  // Workaround for automated testing:
90  // delay reporting logs so that 'rosbag record' has a chance to subscribe to the topic after they are published.
91  // Otherwise it is likely to miss messages.
92  if(num_byte_read_ == 0)
93  {
94  sleep(3); // Use absolute sleep, as this is not related to ROS internal timing.
95  }
96 
97  oem7_file_.read(boost::asio::buffer_cast<char*>(buf), boost::asio::buffer_size(buf));
98  int errno_value = errno; // Cache errno locally, in case any ROS calls /macros affect it.
99 
100  rlen = oem7_file_.gcount();
101  num_byte_read_ += rlen;
102 
103  if(oem7_file_.eof())
104  {
105  ROS_INFO_STREAM("No more input available. Read " << num_byte_read_ << " bytes." );
106 
107  return false;
108  }
109 
110  if(!oem7_file_)
111  {
112  ROS_ERROR_STREAM("Error " << errno_value << " reading input: '" << strerror(errno_value) << "'" );
113 
114  return false;
115  }
116 
117  return true;
118  }
119 
125  virtual bool write(boost::asio::const_buffer buf)
126  {
127  return false;
128  }
129  };
130 }
131 
virtual bool initialize(ros::NodeHandle &nh)
size_t num_byte_read_
Total number of bytes read from file.
virtual bool write(boost::asio::const_buffer buf)
virtual bool read(boost::asio::mutable_buffer buf, size_t &rlen)
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)


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