37 #include <boost/scoped_ptr.hpp> 38 #include <boost/program_options.hpp> 39 #include <boost/progress.hpp> 40 #include <boost/regex.hpp> 47 namespace po = boost::program_options;
69 std::string::size_type pos =
inbag.find_last_of(
'.');
70 if (pos == std::string::npos)
80 po::options_description desc(
"Allowed options");
83 (
"help,h",
"produce help message")
84 (
"quiet,q",
"suppress console output")
85 (
"plugin,p", po::value<std::string>()->
default_value(
"rosbag/AesCbcEncryptor"),
"encryptor name")
86 (
"param,r", po::value<std::string>()->default_value(
"*"),
"encryptor parameter")
87 (
"bz2,j",
"use BZ2 compression")
88 (
"lz4",
"use lz4 compression")
89 (
"inbag", po::value<std::string>(),
"bag file to encrypt")
90 (
"outbag,o", po::value<std::string>(),
"bag file encrypted")
93 po::positional_options_description p;
100 po::store(po::command_line_parser(argc, argv).options(desc).positional(p).
run(), vm);
102 catch (
const boost::program_options::invalid_command_line_syntax& e)
106 catch (
const boost::program_options::unknown_option& e)
111 if (vm.count(
"help"))
113 std::cout << desc << std::endl;
117 if (vm.count(
"quiet"))
119 if (vm.count(
"plugin"))
120 opts.
plugin = vm[
"plugin"].as<std::string>();
121 if (vm.count(
"param"))
122 opts.
param = vm[
"param"].as<std::string>();
127 if (vm.count(
"inbag"))
128 opts.
inbag = vm[
"inbag"].as<std::string>();
131 if (vm.count(
"outbag"))
132 opts.
outbag = vm[
"outbag"].as<std::string>();
145 default:
return "Unknown";
153 std::cout <<
"Output bag: " << options.
outbag <<
"\n";
154 std::cout <<
"Encryption: " << options.
plugin <<
":" << options.
param <<
"\n";
164 boost::scoped_ptr<boost::progress_display> progress;
166 progress.reset(
new boost::progress_display(view.
size(), std::cout,
"Progress:\n ",
" ",
" "));
169 outbag.
write(it->getTopic(), it->getTime(), *it, it->getConnectionHeader());
178 int main(
int argc,
char** argv)
188 ROS_ERROR(
"Error reading options: %s", ex.what());
191 catch (
const boost::regex_error& ex)
193 ROS_ERROR(
"Error reading options: %s\n", ex.what());
rosbag::CompressionType compression
void run(class_loader::ClassLoader *loader)
int main(int argc, char **argv)
void setCompression(CompressionType compression)
std::string getStringCompressionType(rosbag::CompressionType compression)
int encrypt(EncryptorOptions const &options)
EncryptorOptions parseOptions(int argc, char **argv)
Parse the command-line arguments for encrypt options.
void setEncryptorPlugin(const std::string &plugin_name, const std::string &plugin_param=std::string())
void write(std::string const &topic, ros::MessageEvent< T > const &event)