oem7_receiver_port.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 {
38  class Oem7ReceiverPort: public Oem7Receiver<boost::asio::serial_port>
39  {
41  {
42  if(endpoint_.is_open())
43  {
44  return;
45  }
46 
47  std::string recvr_tty_name;
48  nh_.getParam("oem7_tty_name", recvr_tty_name);
49 
50  int baud_rate = 0; // Optional parameter
51  nh_.getParam("oem7_tty_baud", baud_rate);
52  ROS_INFO_STREAM("Oem7SerialPort['" << recvr_tty_name << "' : " << baud_rate << "]");
53 
54 
55  boost::system::error_code err;
56  // We proceed regardless of the error code.
57  // Successful connection does not guarantee subsequent operations will succeed.
58  // Attempting operations on closed ports is harmless.
59 
60  endpoint_.close(err);
61  endpoint_.open(recvr_tty_name, err);
62  ROS_INFO_STREAM("Oem7SerialPort open: '" << endpoint_.is_open() << "; err: " << err);
63 
64  if(baud_rate > 0)
65  {
66  boost::asio::serial_port_base::baud_rate baud_option(baud_rate);
67  endpoint_.set_option(baud_option, err);
68  ROS_INFO_STREAM("Oem7SerialPort set_option baud_rate: '" << baud_option.value() << " : " << err);
69  }
70  }
71 
72  virtual size_t endpoint_read(boost::asio::mutable_buffer buf, boost::system::error_code& err)
73  {
74  boost::array<boost::asio::mutable_buffer, 1> bufs = {buf};
75  return endpoint_.read_some(bufs, err);
76  }
77 
78  virtual size_t endpoint_write(boost::asio::const_buffer buf, boost::system::error_code& err)
79  {
80  boost::array<boost::asio::const_buffer, 1> bufs = {buf};
81  return endpoint_.write_some(bufs, err);
82  }
83 };
84 
85 }
86 
87 
90 
virtual size_t endpoint_read(boost::asio::mutable_buffer buf, boost::system::error_code &err)
boost::asio::serial_port 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


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