oem7_receiver_net.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 #include <oem7_receiver.hpp>
27 
28 #include <ros/ros.h>
29 
30 #include <boost/asio.hpp>
31 
32 
33 namespace novatel_oem7_driver
34 {
35 
36 
37  template <class T>
38  class Oem7ReceiverNet: public Oem7Receiver<typename T::socket>
39  {
41  {
42  if(this->endpoint_.is_open())
43  {
44  return;
45  }
46 
47 
48  std::string recvr_ip_addr;
49  this->nh_.getParam("oem7_ip_addr", recvr_ip_addr);
50 
51  int recvr_port;
52  this->nh_.getParam("oem7_port", recvr_port);
53 
54  ROS_INFO_STREAM("Oem7Net " << (T::v4().protocol() == IPPROTO_TCP ? "TCP" : "UDP") <<
55  "['" << recvr_ip_addr << "' : " << recvr_port << "]");
56 
57  boost::system::error_code err;
58 
59  this->endpoint_.close(err); // Doesn't matter if we fail.
60  this->endpoint_.connect(typename T::endpoint(boost::asio::ip::address::from_string(recvr_ip_addr), recvr_port), err);
61  // Proceed regardless; successful connection does not guarantee subsequent operations will succeed.
62 
63  ROS_INFO_STREAM("Oem7Net socket open: '" << this->endpoint_.is_open() << "; OS error= " << err.value());
64 
65  static const std::string CONN_PRIMER("\r\n");
66  endpoint_write(boost::asio::buffer(CONN_PRIMER), err);
67  }
68 
69  virtual size_t endpoint_read(boost::asio::mutable_buffer buf, boost::system::error_code& err)
70  {
71  boost::array<boost::asio::mutable_buffer, 1> bufs = {buf};
72  return this->endpoint_.receive(bufs, 0, err);
73  }
74 
75  virtual size_t endpoint_write(boost::asio::const_buffer buf, boost::system::error_code& err)
76  {
77  const boost::array<boost::asio::const_buffer, 1> bufs = {buf};
78  return this->endpoint_.send(bufs, 0, err);
79  }
80  };
81 
82  class Oem7ReceiverTcp: public Oem7ReceiverNet<boost::asio::ip::tcp>{};
83  class Oem7ReceiverUdp: public Oem7ReceiverNet<boost::asio::ip::udp>{};
84 }
85 
86 
T endpoint_
boost::asio communication endoint; socket, serial port, etc.
virtual size_t endpoint_write(boost::asio::const_buffer buf, boost::system::error_code &err)
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
virtual size_t endpoint_read(boost::asio::mutable_buffer buf, boost::system::error_code &err)


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