oem7_debug_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 
25 
26 #include <ros/ros.h>
27 
28 #include "oem7_debug_file.hpp"
29 
30 namespace novatel_oem7_driver
31 {
33  {
34  }
35 
36  bool Oem7DebugFile::initialize(std::string& file_name)
37  {
38  file_name_ = file_name;
39 
40  if(file_name_.size() == 0)
41  {
42  return true; // Null initialization
43  }
44 
45  oem7_file_.open(file_name_, std::ios::out | std::ios::binary | std::ios::trunc);
46  int errno_value = errno; // Cache errno locally, in case any ROS calls /macros affect it.
47  if(!oem7_file_)
48  {
49  ROS_ERROR_STREAM("Oem7DebugFile['" << file_name_ << "']: could not open; error= " << errno_value << " '"
50  << strerror(errno_value) << "'");
51  return false;
52  }
53 
54  ROS_INFO_STREAM("Oem7DebugFile['" << file_name_ << "'] opened.");
55 
56  return true;
57  }
58 
63  bool Oem7DebugFile::write(const unsigned char* buf, size_t len)
64  {
65  if(file_name_.size() == 0)
66  return true;
67 
69  return false;
70 
71  oem7_file_.write(reinterpret_cast<const char*>(buf), len);
72  int errno_value = errno; // Cache errno locally, in case any ROS calls /macros affect it.
73 
74  if(!oem7_file_)
75  {
76  ROS_ERROR_STREAM("Oem7DebugFile[" << file_name_ << "]: errno= " << errno_value << " '" << strerror(errno_value) << "'");
77  return false;
78  }
79 
80  return true;
81  }
82 }
83 
virtual bool write(const unsigned char *buf, size_t len)
ROSCPP_DECL bool isShuttingDown()
virtual bool initialize(std::string &debug_file_name)
#define ROS_INFO_STREAM(args)
std::string file_name_
Filesystem name.
#define ROS_ERROR_STREAM(args)


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