Utility class for managing each spawned rosbag record process. More...
#include <bagger.h>
Public Member Functions | |
std::string | getName () |
Getters. More... | |
bool | getRecording () |
std::vector< std::string > | getRecordOptionsVector () |
pid_t | getRecordPID () |
RecordProcess () | |
RecordProcess (std::string name, std::string record_options) | |
void | setName (std::string name) |
void | setRecording (bool recording) |
void | setRecordOptionString (std::string record_options) |
void | setRecordPID (pid_t pid) |
Setters. More... | |
~RecordProcess () | |
Private Attributes | |
std::string | name_ |
name associated with the process - comes from the set record_profiles More... | |
std::string | record_options_ |
record options associated with the process - comes from the set record_profiles More... | |
pid_t | record_pid_ |
pid of the spawned process - used to eventually terminate it More... | |
bool | recording_ |
whether or not the rosbag record process is currently recording More... | |
Utility class for managing each spawned rosbag record process.
ROS Node for programmatic control of multiple rosbag record processes. This node reads in "record profiles" from a configuration profile and sets up a service to allow rosbag record processes for each "record profile" to be started / stopped. Each "record profile" is comprised of a name (which is used by the service to ID which process to start/stop) and options to pass rosbag record. A latched publication of the recording status for each of the "record profiles" is published every time a call to the state change service is made.
The Bagger node was created to help compartmentalize the bagging of different publications at different / the same times, and to help keep bag sizes in check, which speeds up post-mission analysis.
RecordProcess::RecordProcess | ( | ) |
Definition at line 46 of file bagger.cpp.
RecordProcess::RecordProcess | ( | std::string | name, |
std::string | record_options | ||
) |
Definition at line 53 of file bagger.cpp.
RecordProcess::~RecordProcess | ( | ) |
Definition at line 60 of file bagger.cpp.
std::string RecordProcess::getName | ( | ) |
Getters.
Definition at line 63 of file bagger.cpp.
bool RecordProcess::getRecording | ( | ) |
Definition at line 89 of file bagger.cpp.
std::vector< std::string > RecordProcess::getRecordOptionsVector | ( | ) |
Definition at line 71 of file bagger.cpp.
pid_t RecordProcess::getRecordPID | ( | ) |
Definition at line 67 of file bagger.cpp.
void RecordProcess::setName | ( | std::string | name | ) |
Definition at line 93 of file bagger.cpp.
void RecordProcess::setRecording | ( | bool | recording | ) |
Definition at line 97 of file bagger.cpp.
void RecordProcess::setRecordOptionString | ( | std::string | record_options | ) |
Definition at line 105 of file bagger.cpp.
void RecordProcess::setRecordPID | ( | pid_t | pid | ) |
Setters.
Definition at line 101 of file bagger.cpp.
|
private |
|
private |
|
private |
|
private |