bagger.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Square Robot, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Square Robot, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
46 #ifndef SRC_BAGGER_INCLUDE_BAGGER_BAGGER_H_
47 #define SRC_BAGGER_INCLUDE_BAGGER_BAGGER_H_
48 
49 #include <ros/ros.h>
50 #include <boost/filesystem.hpp>
51 #include <map>
52 #include <string>
53 #include <vector>
54 
55 #include <bagger/BaggingState.h>
56 #include <bagger/SetBagState.h>
57 
60 public:
61  RecordProcess();
62  RecordProcess(std::string name, std::string record_options);
64 
66  std::string getName();
67  pid_t getRecordPID();
68  bool getRecording();
69  std::vector<std::string> getRecordOptionsVector();
70 
72  void setRecordPID(pid_t pid);
73  void setName(std::string name);
74  void setRecordOptionString(std::string record_options);
75  void setRecording(bool recording);
76 
77 private:
79  std::string name_;
81  std::string record_options_;
83  bool recording_;
85  pid_t record_pid_;
86 };
87 
88 class Bagger {
89 protected:
94 
95  // Normal node handle
97  // Private node handle, used for node-specific things like parameters
99 
100 private:
102  bool onBagStateSrv(bagger::SetBagState::Request &request, bagger::SetBagState::Response &response);
103 
105  void publishBaggingStates();
106 
108  std::string getCurrentWorkingDirectory();
111  std::vector<boost::filesystem::path> getMatchingFilePathsInDirectory(const boost::filesystem::path &dir_path,
112  std::string match_string);
114  std::string getBagNameFromRecordOptions(std::string record_opts);
116  std::string removeSuffix(std::string s, std::string suffix);
117 
118  std::map<std::string, std::string> profile_name_to_record_options_map_;
119  std::map<std::string, RecordProcess> profile_name_to_record_process_map_;
120 
121 public:
122  Bagger();
123  void attemptRecordCleanup();
124 };
125 
126 #endif /* SRC_BAGGER_INCLUDE_BAGGER_BAGGER_H_ */
pid_t getRecordPID()
Definition: bagger.cpp:67
Definition: bagger.h:88
bool getRecording()
Definition: bagger.cpp:89
std::map< std::string, RecordProcess > profile_name_to_record_process_map_
Definition: bagger.h:119
std::vector< std::string > getRecordOptionsVector()
Definition: bagger.cpp:71
ros::Publisher bagging_state_publisher_
For publishing the names and states of each record profile rosbag record process. ...
Definition: bagger.h:91
ros::NodeHandlePtr node_handle_
Definition: bagger.h:96
void setRecording(bool recording)
Definition: bagger.cpp:97
std::map< std::string, std::string > profile_name_to_record_options_map_
Definition: bagger.h:118
bool recording_
whether or not the rosbag record process is currently recording
Definition: bagger.h:83
std::string getName()
Getters.
Definition: bagger.cpp:63
Utility class for managing each spawned rosbag record process.
Definition: bagger.h:59
ros::ServiceServer bag_state_service_
Service for starting / stopping rosbag record processes.
Definition: bagger.h:93
void setRecordOptionString(std::string record_options)
Definition: bagger.cpp:105
~RecordProcess()
Definition: bagger.cpp:60
void setName(std::string name)
Definition: bagger.cpp:93
pid_t record_pid_
pid of the spawned process - used to eventually terminate it
Definition: bagger.h:85
ros::NodeHandlePtr private_node_handle_
Definition: bagger.h:98
std::string name_
name associated with the process - comes from the set record_profiles
Definition: bagger.h:79
std::string record_options_
record options associated with the process - comes from the set record_profiles
Definition: bagger.h:81
void setRecordPID(pid_t pid)
Setters.
Definition: bagger.cpp:101


bagger
Author(s): Brenden Gibbons
autogenerated on Tue Apr 27 2021 02:29:15