oem7_receiver.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 
26 
27 #include <ros/ros.h>
28 
29 #include <boost/asio.hpp>
30 
31 
32 
33 namespace novatel_oem7_driver
34 {
38  template <typename T>
40  {
41  boost::asio::io_service io_;
42 
43  enum
44  {
46  };
47 
48 
49 
50  protected:
52 
54 
57 
59  {
61  {
62  ROS_ERROR_STREAM("Oem7Receiver: Max Num IO errors exceeded: " << max_num_io_errors_);
63  return true;
64  }
65  else
66  {
67  return false;
68  }
69  }
70 
71 
75  virtual void endpoint_try_open() = 0;
76 
80  virtual size_t endpoint_read( boost::asio::mutable_buffer buf, boost::system::error_code& err) = 0;
81 
82 
86  virtual size_t endpoint_write(boost::asio::const_buffer buf, boost::system::error_code& err) = 0;
87 
92  {
93  boost::system::error_code err;
94  endpoint_.close(err);
95  ROS_ERROR_STREAM("Oem7Receiver: close error: " << err.value());
96  sleep(1.0);
97  }
98 
99  public:
101  io_(),
102  endpoint_(io_),
104  num_io_errors_(0)
105  {
106  }
107 
108  virtual ~Oem7Receiver()
109  {
110  }
111 
112  virtual bool initialize(ros::NodeHandle& h)
113  {
114  nh_ = h;
115 
116  this->nh_.getParam("oem7_max_io_errors", max_num_io_errors_);
117 
118  return true;
119  }
120 
121  virtual bool read( boost::asio::mutable_buffer buf, size_t& rlen)
122  {
123  while(!ros::isShuttingDown() && !in_error_state())
124  {
126 
127  boost::system::error_code err;
128  size_t len = endpoint_read(buf, err);
129  if(err.value() == boost::system::errc::success)
130  {
131  num_io_errors_ = 0; // Reset error counter
132 
133  rlen = len;
134  return true;
135  }
136  // else: error condition
137 
138 
139  num_io_errors_++;
140 
141  ROS_ERROR_STREAM("Oem7Receiver: read error: " << err.value()
142  <<"; endpoint open: " << endpoint_.is_open()
143  <<" errors/max: " << num_io_errors_
144  <<"/" << max_num_io_errors_);
145  endpoint_close();
146  }
147 
148  return false;
149  }
150 
151  virtual bool write(boost::asio::const_buffer buf)
152  {
154  return false;
155 
157 
158  boost::system::error_code err;
159  endpoint_write(buf, err);
160  if(err.value() != boost::system::errc::success)
161  {
162  num_io_errors_++;
163 
164  ROS_ERROR_STREAM("Oem7Receiver: write error: " << err.value() << "; endpoint open: " << endpoint_.is_open());
165  endpoint_close();
166  return false;
167  }
168 
169  return true;
170  }
171 };
172 
173 }
174 
175 
novatel_oem7_driver::Oem7Receiver::write
virtual bool write(boost::asio::const_buffer buf)
Definition: oem7_receiver.hpp:151
novatel_oem7_driver::Oem7Receiver::~Oem7Receiver
virtual ~Oem7Receiver()
Definition: oem7_receiver.hpp:108
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
novatel_oem7_driver::Oem7Receiver::nh_
ros::NodeHandle nh_
Definition: oem7_receiver.hpp:51
novatel_oem7_driver::Oem7Receiver::endpoint_
T endpoint_
boost::asio communication endoint; socket, serial port, etc.
Definition: oem7_receiver.hpp:53
novatel_oem7_driver::Oem7Receiver
Definition: oem7_receiver.hpp:39
novatel_oem7_driver::Oem7Receiver::Oem7Receiver
Oem7Receiver()
Definition: oem7_receiver.hpp:100
novatel_oem7_driver::Oem7Receiver::read
virtual bool read(boost::asio::mutable_buffer buf, size_t &rlen)
Definition: oem7_receiver.hpp:121
novatel_oem7_driver::Oem7ReceiverIf
Definition: oem7_receiver_if.hpp:38
novatel_oem7_driver::Oem7Receiver::num_io_errors_
int num_io_errors_
Number of consecuitive io errors.
Definition: oem7_receiver.hpp:56
novatel_oem7_driver::Oem7Receiver::DEFAULT_MAX_NUM_IO_ERRORS
@ DEFAULT_MAX_NUM_IO_ERRORS
Definition: oem7_receiver.hpp:45
novatel_oem7_driver::Oem7Receiver::endpoint_try_open
virtual void endpoint_try_open()=0
novatel_oem7_driver::Oem7Receiver::initialize
virtual bool initialize(ros::NodeHandle &h)
Definition: oem7_receiver.hpp:112
novatel_oem7_driver::Oem7Receiver::endpoint_read
virtual size_t endpoint_read(boost::asio::mutable_buffer buf, boost::system::error_code &err)=0
novatel_oem7_driver::Oem7Receiver::endpoint_close
void endpoint_close()
Definition: oem7_receiver.hpp:91
novatel_oem7_driver::Oem7Receiver::max_num_io_errors_
int max_num_io_errors_
Number of consecutive io errors before declaring failure and quitting.
Definition: oem7_receiver.hpp:55
ros::isShuttingDown
ROSCPP_DECL bool isShuttingDown()
novatel_oem7_driver::Oem7Receiver::in_error_state
bool in_error_state()
Definition: oem7_receiver.hpp:58
oem7_receiver_if.hpp
novatel_oem7_driver
Definition: oem7_imu.hpp:25
novatel_oem7_driver::Oem7Receiver::endpoint_write
virtual size_t endpoint_write(boost::asio::const_buffer buf, boost::system::error_code &err)=0
ros::NodeHandle
novatel_oem7_driver::Oem7Receiver::io_
boost::asio::io_service io_
Definition: oem7_receiver.hpp:41


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