43 #include <boost/algorithm/string.hpp>
44 #include <boost/algorithm/string/split.hpp>
73 std::vector<std::string> options_strings;
76 std::vector<std::string> rov;
78 rov.push_back(
"rosrun");
79 rov.push_back(
"rosbag");
80 rov.push_back(
"record");
82 for (
auto it = options_strings.begin(); it != options_strings.end(); ++it) {
110 bool success =
false;
118 pid_t pid_rr = fork();
121 std::vector<std::string> command_strings =
123 std::vector<char *> commands;
125 for (
auto it = command_strings.begin(); it != command_strings.end(); ++it) {
126 commands.push_back(
const_cast<char *
>(it->c_str()));
130 commands.push_back(NULL);
133 int dev_null_fd = open(
"/dev/null", O_WRONLY);
135 dup2(dev_null_fd, 1);
136 dup2(dev_null_fd, 2);
139 if (execvp(commands[0], &commands[0]) != 0) {
141 ROS_ERROR(
"execvp failed! %s", strerror(errno));
143 }
else if (pid_rr > 0) {
147 ROS_DEBUG(
"successfully started the record. profile: %s", request.bag_profile_name.c_str());
159 ROS_DEBUG(
"record profile %s already recording", request.bag_profile_name.c_str());
166 ROS_DEBUG(
"successfully stopped the record. profile: %s", request.bag_profile_name.c_str());
170 ROS_ERROR(
"kill() when stopping record profile %s failed", request.bag_profile_name.c_str());
174 ROS_DEBUG(
"record profile %s already not recording", request.bag_profile_name.c_str());
179 ROS_ERROR(
"Requested record profile: %s does not exist. Check the configured "
181 request.bag_profile_name.c_str());
193 bagger::BaggingState bs_msg;
202 bs_msg.bag_profile_names.push_back(it->first);
203 bs_msg.bagging.push_back(it->second.getRecording());
205 if (it->second.getRecording()) {
209 bs_msg.bag_file_names.push_back(
"");
216 std::string bag_name =
"";
219 if (record_opts.find(
"-o") != std::string::npos) {
225 size_t start_index = record_opts.find(
"-o ") + 3;
226 size_t next_space_index = record_opts.find(
" ", start_index);
227 std::string file_path = record_opts.substr(start_index, next_space_index - start_index);
230 if (file_path.find(
"/") == std::string::npos) {
231 file_path = cwd_string + file_path;
234 boost::filesystem::path full_file_name(file_path);
237 std::vector<boost::filesystem::path> matches =
240 if (matches.size() > 0) {
241 boost::filesystem::path latest = matches[0];
242 for (
auto i : matches) {
243 std::string
s = i.stem().string();
244 s.erase(std::remove_if(
s.begin(),
s.end(), std::not1(std::ptr_fun((int (*)(
int)) std::isdigit))),
s.end());
246 std::string latest_digits(latest.string());
247 latest_digits.erase(std::remove_if(latest_digits.begin(), latest_digits.end(),
248 std::not1(std::ptr_fun((int (*)(
int)) std::isdigit))),
249 latest_digits.end());
250 if (
s > latest_digits) {
254 bag_name = latest.string();
256 }
else if (record_opts.find(
"-O") != std::string::npos) {
262 size_t start_index = record_opts.find(
"-O ") + 3;
263 size_t next_space_index = record_opts.find(
" ", start_index);
264 std::string file_path = record_opts.substr(start_index, next_space_index - start_index);
267 if (file_path.find(
".bag") == std::string::npos) {
272 if (file_path.find(
"/") == std::string::npos) {
273 file_path = cwd_string + file_path;
275 bag_name = file_path;
280 const boost::filesystem::path cwd_path(cwd_string);
283 if (bag_matches.size() > 0) {
284 boost::filesystem::path latest(
"");
286 for (
auto i : bag_matches) {
287 std::string
s = i.stem().string();
288 if (std::isdigit(
s[0])) {
289 if (latest.string() ==
"") {
292 std::string latest_digits(latest.stem().string());
293 latest_digits.erase(std::remove_if(latest_digits.begin(), latest_digits.end(),
294 std::not1(std::ptr_fun((int (*)(
int)) std::isdigit))),
295 latest_digits.end());
297 s.erase(std::remove_if(
s.begin(),
s.end(), std::not1(std::ptr_fun((int (*)(
int)) std::isdigit))),
s.end());
299 if (
s > latest_digits) {
305 bag_name = latest.string();
310 if (record_opts.find(
"--split") != std::string::npos) {
311 auto last_underscore_index = bag_name.rfind(
'_');
312 if (last_underscore_index != std::string::npos) {
313 bag_name.erase(last_underscore_index);
322 std::string match_string) {
323 std::vector<boost::filesystem::path> paths;
325 for (
auto &entry : boost::make_iterator_range(boost::filesystem::directory_iterator(dir_path), {})) {
326 if (entry.path().string().find(match_string) != std::string::npos) {
327 paths.push_back(entry.path());
335 if (
s != suffix &&
s.size() > suffix.size() &&
s.substr(
s.size() - suffix.size()) == suffix) {
336 s =
s.substr(0,
s.size() - suffix.size());
342 char path[FILENAME_MAX];
343 if (!getcwd(path,
sizeof(path))) {
346 return std::string(path) +
"/";
352 pid_t wait_result = waitpid(pn_pair.second.getRecordPID(), &status, WNOHANG);
353 if (wait_result > 0) {
354 ROS_DEBUG_STREAM(
"Record for profile " << pn_pair.first <<
" has completed");
356 pn_pair.second.setRecording(
false);
376 ROS_ERROR(
"Failed to find profile_name_to_bag_options_map in param server - "
389 int main(
int argc,
char **argv) {