8000 Record a maximum number of splits and then begin deleting old files by contradict · Pull Request #866 · ros/ros_comm · GitHub
[go: up one dir, main page]
More Web Proxy on the site http://driver.im/
Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Record a maximum number of splits and then begin deleting old files #866

Merged
merged 3 commits into from
Aug 15, 2016
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions tools/rosbag/include/rosbag/recorder.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
#include <queue>
#include <string>
#include <vector>
#include <list>

#include <boost/thread/condition.hpp>
#include <boost/thread/mutex.hpp>
Expand Down Expand Up @@ -104,6 +105,7 @@ struct ROSBAG_DECL RecorderOptions
uint32_t limit;
bool split;
uint64_t max_size;
uint32_t max_splits;
ros::Duration max_duration;
std::string node;
unsigned long long min_space;
Expand Down Expand Up @@ -140,6 +142,7 @@ class ROSBAG_DECL Recorder
// void doQueue(topic_tools::ShapeShifter::ConstPtr msg, std::string const& topic, boost::shared_ptr<ros::Subscriber> subscriber, boost::shared_ptr<int> count);
void doQueue(const ros::MessageEvent<topic_tools::ShapeShifter const>& msg_event, std::string const& topic, boost::shared_ptr<ros::Subscriber> subscriber, boost::shared_ptr<int> count);
void doRecord();
void checkNumSplits();
bool checkSize();
bool checkDuration(const ros::Time&);
void doRecordSnapshotter();
Expand All @@ -157,6 +160,7 @@ class ROSBAG_DECL Recorder

std::string target_filename_;
std::string write_filename_;
std::list<std::string> current_files_;

std::set<std::string> currently_recording_; //!< set of currenly recording topics
int num_subscribers_; //!< used for book-keeping of our number of subscribers
Expand Down
12 changes: 12 additions & 0 deletions tools/rosbag/src/record.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ rosbag::RecorderOptions parseOptions(int argc, char** argv) {
("bz2,j", "use BZ2 compression")
("lz4", "use LZ4 compression")
("split", po::value<int>()->implicit_value(0), "Split the bag file and continue recording when maximum size or maximum duration reached.")
("max-splits", po::value<int>()->default_value(0), "Keep a maximum of N bag files, when reaching the maximum erase the oldest one to keep a constant number of files.")
("topic", po::value< std::vector<std::string> >(), "topic to record")
("size", po::value<uint64_t>(), "The maximum size of the bag to record in MB.")
("duration", po::value<std::string>(), "Record a bag of maximum duration in seconds, unless 'm', or 'h' is appended.")
Expand Down Expand Up @@ -123,6 +124,17 @@ rosbag::RecorderOptions parseOptions(int argc, char** argv) {
opts.max_size = 1048576 * S;
}
}
if(vm.count("max-splits"))
{
if(!opts.split)
{
ROS_WARN("--max-splits is ignored without --split");
}
else
{
opts.max_splits = vm["max-splits"].as<int>();
}
}
if (vm.count("buffsize"))
{
int m = vm["buffsize"].as<int>();
Expand Down
19 changes: 19 additions & 0 deletions tools/rosbag/src/recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -393,6 +393,23 @@ void Recorder::stopWriting() {
rename(write_filename_.c_str(), target_filename_.c_str());
}

void Recorder::checkNumSplits()
{
if(options_.max_splits>0)
{
current_files_.push_back(target_filename_);
if(current_files_.size()>options_.max_splits)
{
int err = unlink(current_files_.front().c_str());
if(err != 0)
{
ROS_ERROR("Unable to remove %s: %s", current_files_.front().c_str(), strerror(errno));
}
current_files_.pop_front();
}
}
}

bool Recorder::checkSize()
{
if (options_.max_size > 0)
Expand All @@ -403,6 +420,7 @@ bool Recorder::checkSize()
{
stopWriting();
split_count_++;
checkNumSplits();
startWriting();
} else {
ros::shutdown();
Expand All @@ -425,6 +443,7 @@ bool Recorder::checkDuration(const ros::Time& t)
{
stopWriting();
split_count_++;
checkNumSplits();
start_time_ += options_.max_duration;
startWriting();
}
Expand Down
3 changes: 3 additions & 0 deletions tools/rosbag/src/rosbag/rosbag_main.py
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ def record_cmd(argv):
parser.add_option("-o", "--output-prefix", dest="prefix", default=None, action="store", help="prepend PREFIX to beginning of bag name (name will always end with date stamp)")
parser.add_option("-O", "--output-name", dest="name", default=None, action="store", help="record to bag with name NAME.bag")
parser.add_option( "--split", dest="split", 71AB default=False, callback=handle_split, action="callback", help="split the bag when maximum size or duration is reached")
parser.add_option( "--max-splits", dest="max_splits", type='int', action="store", help="Keep a maximum of N bag files, when reaching the maximum erase the oldest one to keep a constant number of files.", metavar="MAX_SPLITS")
parser.add_option( "--size", dest="size", type='int', action="store", help="record a bag of maximum size SIZE MB. (Default: infinite)", metavar="SIZE")
parser.add_option( "--duration", dest="duration", type='string',action="store", help="record a bag of maximum duration DURATION in seconds, unless 'm', or 'h' is appended.", metavar="DURATION")
parser.add_option("-b", "--buffsize", dest="buffsize", default=256, type='int', action="store", help="use an internal buffer of SIZE MB (Default: %default, 0 = infinite)", metavar="SIZE")
Expand Down Expand Up @@ -114,6 +115,8 @@ def record_cmd(argv):
if not options.duration and not options.size:
parser.error("Split specified without giving a maximum duration or size")
cmd.extend(["--split"])
if options.max_splits:
cmd.extend(["--max-splits", str(options.max_splits)])
if options.duration: cmd.extend(["--duration", options.duration])
if options.size: cmd.extend(["--size", str(options.size)])
if options.node:
Expand Down
0