Go to the documentation of this file.
46 #ifndef SRC_BAGGER_INCLUDE_BAGGER_BAGGER_H_
47 #define SRC_BAGGER_INCLUDE_BAGGER_BAGGER_H_
50 #include <boost/filesystem.hpp>
55 #include <bagger/BaggingState.h>
56 #include <bagger/SetBagState.h>
102 bool onBagStateSrv(bagger::SetBagState::Request &request, bagger::SetBagState::Response &response);
112 std::string match_string);
116 std::string
removeSuffix(std::string s, std::string suffix);
void setRecordPID(pid_t pid)
Setters.
ros::NodeHandlePtr private_node_handle_
std::string getBagNameFromRecordOptions(std::string record_opts)
Utility function which infers the most likely rosbag name for the passed record options.
void setRecordOptionString(std::string record_options)
std::vector< std::string > getRecordOptionsVector()
void publishBaggingStates()
Convenience function for publishing the recording states for each record profile.
bool onBagStateSrv(bagger::SetBagState::Request &request, bagger::SetBagState::Response &response)
Callback for receipt of set bag state service calls.
std::vector< boost::filesystem::path > getMatchingFilePathsInDirectory(const boost::filesystem::path &dir_path, std::string match_string)
void setRecording(bool recording)
ros::ServiceServer bag_state_service_
Service for starting / stopping rosbag record processes.
std::map< std::string, RecordProcess > profile_name_to_record_process_map_
std::string removeSuffix(std::string s, std::string suffix)
Returns a version of the passed string with the passed suffix removed.
std::string getCurrentWorkingDirectory()
Utility function which returns the current working directory of the executing program.
ros::NodeHandlePtr node_handle_
std::string getName()
Getters.
void attemptRecordCleanup()
void setName(std::string name)
bool recording_
whether or not the rosbag record process is currently recording
std::string name_
name associated with the process - comes from the set record_profiles
std::string record_options_
record options associated with the process - comes from the set record_profiles
pid_t record_pid_
pid of the spawned process - used to eventually terminate it
ros::Publisher bagging_state_publisher_
For publishing the names and states of each record profile rosbag record process.
std::map< std::string, std::string > profile_name_to_record_options_map_
Utility class for managing each spawned rosbag record process.
bagger
Author(s): Brenden Gibbons
autogenerated on Fri Jan 5 2024 03:14:05