Public Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
Bagger Class Reference

#include <bagger.h>

Public Member Functions

void attemptRecordCleanup ()
 
 Bagger ()
 

Protected Attributes

ros::ServiceServer bag_state_service_
 Service for starting / stopping rosbag record processes. More...
 
ros::Publisher bagging_state_publisher_
 For publishing the names and states of each record profile rosbag record process. More...
 
ros::NodeHandlePtr node_handle_
 
ros::NodeHandlePtr private_node_handle_
 

Private Member Functions

std::string getBagNameFromRecordOptions (std::string record_opts)
 Utility function which infers the most likely rosbag name for the passed record options. More...
 
std::string getCurrentWorkingDirectory ()
 Utility function which returns the current working directory of the executing program. More...
 
std::vector< boost::filesystem::path > getMatchingFilePathsInDirectory (const boost::filesystem::path &dir_path, std::string match_string)
 
bool onBagStateSrv (bagger::SetBagState::Request &request, bagger::SetBagState::Response &response)
 Callback for receipt of set bag state service calls. More...
 
void publishBaggingStates ()
 Convenience function for publishing the recording states for each record profile. More...
 
std::string removeSuffix (std::string s, std::string suffix)
 Returns a version of the passed string with the passed suffix removed. More...
 

Private Attributes

std::map< std::string, std::string > profile_name_to_record_options_map_
 
std::map< std::string, RecordProcessprofile_name_to_record_process_map_
 

Detailed Description

Definition at line 88 of file bagger.h.

Constructor & Destructor Documentation

Bagger::Bagger ( )

Definition at line 362 of file bagger.cpp.

Member Function Documentation

void Bagger::attemptRecordCleanup ( )

Definition at line 349 of file bagger.cpp.

std::string Bagger::getBagNameFromRecordOptions ( std::string  record_opts)
private

Utility function which infers the most likely rosbag name for the passed record options.

Definition at line 215 of file bagger.cpp.

std::string Bagger::getCurrentWorkingDirectory ( )
private

Utility function which returns the current working directory of the executing program.

Definition at line 341 of file bagger.cpp.

std::vector< boost::filesystem::path > Bagger::getMatchingFilePathsInDirectory ( const boost::filesystem::path &  dir_path,
std::string  match_string 
)
private

Searches the passed directory for any file paths that contain the passed match string. Returns a vector of paths containing all such matches

Definition at line 321 of file bagger.cpp.

bool Bagger::onBagStateSrv ( bagger::SetBagState::Request &  request,
bagger::SetBagState::Response &  response 
)
private

Callback for receipt of set bag state service calls.

Definition at line 109 of file bagger.cpp.

void Bagger::publishBaggingStates ( )
private

Convenience function for publishing the recording states for each record profile.

Definition at line 192 of file bagger.cpp.

std::string Bagger::removeSuffix ( std::string  s,
std::string  suffix 
)
private

Returns a version of the passed string with the passed suffix removed.

Definition at line 334 of file bagger.cpp.

Member Data Documentation

ros::ServiceServer Bagger::bag_state_service_
protected

Service for starting / stopping rosbag record processes.

Definition at line 93 of file bagger.h.

ros::Publisher Bagger::bagging_state_publisher_
protected

For publishing the names and states of each record profile rosbag record process.

Definition at line 91 of file bagger.h.

ros::NodeHandlePtr Bagger::node_handle_
protected

Definition at line 96 of file bagger.h.

ros::NodeHandlePtr Bagger::private_node_handle_
protected

Definition at line 98 of file bagger.h.

std::map<std::string, std::string> Bagger::profile_name_to_record_options_map_
private

Definition at line 118 of file bagger.h.

std::map<std::string, RecordProcess> Bagger::profile_name_to_record_process_map_
private

Definition at line 119 of file bagger.h.


The documentation for this class was generated from the following files:


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