diff --git a/tools/rosbag/src/record.cpp b/tools/rosbag/src/record.cpp index dda378fe12..b624e4e986 100644 --- a/tools/rosbag/src/record.cpp +++ b/tools/rosbag/src/record.cpp @@ -62,7 +62,7 @@ rosbag::RecorderOptions parseOptions(int argc, char** argv) { ("bz2,j", "use BZ2 compression") ("lz4", "use LZ4 compression") ("split", po::value()->implicit_value(0), "Split the bag file and continue recording when maximum size or maximum duration reached.") - ("max-splits", po::value()->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.") + ("max-splits", po::value(), "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 >(), "topic to record") ("size", po::value(), "The maximum size of the bag to record in MB.") ("duration", po::value(), "Record a bag of maximum duration in seconds, unless 'm', or 'h' is appended.") diff --git a/tools/rosbag/src/recorder.cpp b/tools/rosbag/src/recorder.cpp index a4e995cf11..86cd8cade1 100644 --- a/tools/rosbag/src/recorder.cpp +++ b/tools/rosbag/src/recorder.cpp @@ -108,6 +108,7 @@ RecorderOptions::RecorderOptions() : limit(0), split(false), max_size(0), + max_splits(0), max_duration(-1.0), node(""), min_space(1024 * 1024 * 1024),