Skip to content

Commit

Permalink
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Add command-line en/decrypt tools; rename libgpgme11-dev to libgpgme-…
Browse files Browse the repository at this point in the history
…dev.
jwon02 committed Nov 2, 2017
1 parent be25670 commit 932513e
Showing 4 changed files with 219 additions and 4 deletions.
5 changes: 4 additions & 1 deletion tools/rosbag/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -38,14 +38,17 @@ target_link_libraries(record rosbag)
add_executable(play src/play.cpp)
target_link_libraries(play rosbag)

add_executable(encrypt src/encrypt.cpp)
target_link_libraries(encrypt ${catkin_LIBRARIES})

install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h")
install(TARGETS rosbag
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION})
install(TARGETS record play
install(TARGETS record play encrypt
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
156 changes: 156 additions & 0 deletions tools/rosbag/src/encrypt.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,156 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2017, Open Source Robotics Foundation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

#include <iostream>

#include <boost/program_options.hpp>
#include <boost/regex.hpp>

#include <ros/ros.h>

#include "rosbag/bag.h"
#include "rosbag/view.h"

namespace po = boost::program_options;

struct EncryptorOptions
{
EncryptorOptions() { }

void buildOutbagName();

std::string plugin;
std::string param;
std::string inbag;
std::string outbag;
};

void EncryptorOptions::buildOutbagName() {
if (!outbag.empty()) {
return;
}
if (inbag.empty()) {
throw ros::Exception("Input bag is not specified.");
}
std::string::size_type pos = inbag.find_last_of('.');
if (pos == std::string::npos) {
throw ros::Exception("Input bag name has no extension.");
}
outbag = inbag.substr(0, pos) + std::string(".out") + inbag.substr(pos);
}

//! Parse the command-line arguments for encrypt options
EncryptorOptions parseOptions(int argc, char** argv) {
EncryptorOptions opts;

po::options_description desc("Allowed options");

desc.add_options()
("help,h", "produce help message")
("plugin,p", po::value<std::string>()->default_value("rosbag/AesCbcEncryptor"), "encryptor name")
("param,r", po::value<std::string>()->default_value("*"), "encryptor parameter")
("inbag", po::value<std::string>(), "bag file to encrypt")
("outbag,o", po::value<std::string>(), "bag file encrypted")
;

po::positional_options_description p;
p.add("inbag", -1);

po::variables_map vm;

try
{
po::store(po::command_line_parser(argc, argv).options(desc).positional(p).run(), vm);
} catch (boost::program_options::invalid_command_line_syntax& e)
{
throw ros::Exception(e.what());
} catch (boost::program_options::unknown_option& e)
{
throw ros::Exception(e.what());
}

if (vm.count("help")) {
std::cout << desc << std::endl;
exit(0);
}

if (vm.count("plugin"))
opts.plugin = vm["plugin"].as<std::string>();
if (vm.count("param"))
opts.param = vm["param"].as<std::string>();
if (vm.count("inbag"))
{
opts.inbag = vm["inbag"].as<std::string>();
} else {
throw ros::Exception("You must specify bag to encrypt.");
}
if (vm.count("outbag"))
opts.outbag = vm["outbag"].as<std::string>();
opts.buildOutbagName();

return opts;
}

int encrypt(EncryptorOptions const& options) {
rosbag::Bag inbag(options.inbag, rosbag::bagmode::Read);
rosbag::Bag outbag(options.outbag, rosbag::bagmode::Write);
// Compression type is per chunk, and cannot be retained.
// If chunk-by-chunk encryption is implemented, compression type could be honored.
outbag.setEncryptorPlugin(options.plugin, options.param);
rosbag::View view(inbag);
for (rosbag::View::const_iterator it = view.begin(); it != view.end(); ++it) {
outbag.write(it->getTopic(), it->getTime(), *it, it->getConnectionHeader());
}
outbag.close();
inbag.close();
return 0;
}

int main(int argc, char** argv) {
// Parse the command-line options
EncryptorOptions opts;
try {
opts = parseOptions(argc, argv);
}
catch (ros::Exception const& ex) {
ROS_ERROR("Error reading options: %s", ex.what());
return 1;
}
catch(boost::regex_error const& ex) {
ROS_ERROR("Error reading options: %s\n", ex.what());
return 1;
}

return encrypt(opts);
}
58 changes: 57 additions & 1 deletion tools/rosbag/src/rosbag/rosbag_main.py
Original file line number Diff line number Diff line change
@@ -591,6 +591,38 @@ def reindex_cmd(argv):

bag_op(args, True, lambda b: b.version > 102, op, options.output_dir, options.force, options.quiet)

def encrypt_cmd(argv):
parser = optparse.OptionParser(usage='rosbag encrypt [options] BAGFILE1 [BAGFILE2 ...]',
description='Encrypt one or more bag files.')
parser.add_option( '--output-dir', action='store', dest='output_dir', help='write to directory DIR', metavar='DIR')
parser.add_option('-f', '--force', action='store_true', dest='force', help='force overwriting of backup file if it exists')
parser.add_option('-q', '--quiet', action='store_true', dest='quiet', help='suppress noncritical messages')
parser.add_option("-p", "--plugin", action='store', dest="plugin", default='rosbag/AesCbcEncryptor', help='encryptor plugin name')
parser.add_option("-r", "--param", action='store', dest="param", default='*', help='encryptor plugin parameter')
(options, args) = parser.parse_args(argv)

if len(args) < 1:
parser.error('You must specify at least one bag file.')

op = lambda inbag, outbag, quiet: change_encryption_op(inbag, outbag, options.plugin, options.param, options.quiet)

bag_op(args, False, lambda b: False, op, options.output_dir, options.force, options.quiet)

def decrypt_cmd(argv):
parser = optparse.OptionParser(usage='rosbag decrypt [options] BAGFILE1 [BAGFILE2 ...]',
description='Decrypt one or more bag files.')
parser.add_option( '--output-dir', action='store', dest='output_dir', help='write to directory DIR', metavar='DIR')
parser.add_option('-f', '--force', action='store_true', dest='force', help='force overwriting of backup file if it exists')
parser.add_option('-q', '--quiet', action='store_true', dest='quiet', help='suppress noncritical messages')
(options, args) = parser.parse_args(argv)

if len(args) < 1:
parser.error('You must specify at least one bag file.')

op = lambda inbag, outbag, quiet: change_encryption_op(inbag, outbag, 'rosbag/NoEncryptor', '*', options.quiet)
# Note the second paramater is True: Python Bag class cannot read index information from encrypted bag files
bag_op(args, True, lambda b: False, op, options.output_dir, options.force, options.quiet)

def bag_op(inbag_filenames, allow_unindexed, copy_fn, op, output_dir=None, force=False, quiet=False):
for inbag_filename in inbag_filenames:
# Check we can read the file
@@ -618,7 +650,7 @@ def bag_op(inbag_filenames, allow_unindexed, copy_fn, op, output_dir=None, force
if outbag_filename == inbag_filename:
# Rename the input bag to ###.orig.###, and open for reading
backup_filename = '%s.orig%s' % os.path.splitext(inbag_filename)

if not force and os.path.exists(backup_filename):
if not quiet:
print('Skipping %s. Backup path %s already exists.' % (inbag_filename, backup_filename), file=sys.stderr)
@@ -634,6 +666,7 @@ def bag_op(inbag_filenames, allow_unindexed, copy_fn, op, output_dir=None, force
continue

source_filename = backup_filename

else:
if copy:
shutil.copy(inbag_filename, outbag_filename)
@@ -742,6 +775,27 @@ def reindex_op(inbag, outbag, quiet):
pass
meter.finish()

def change_encryption_op(inbag, outbag, plugin, param, quiet):
# Output file must be closed before written by the encrypt process
outbag.close()

encryptpath = roslib.packages.find_node('rosbag', 'encrypt')
if not encryptpath:
parser.error("Cannot find rosbag/encrypt executable")
cmd = [encryptpath[0]]
cmd.extend([inbag.filename])
cmd.extend(['-o', outbag.filename])
cmd.extend(['-p', plugin])
cmd.extend(['-r', param])

old_handler = signal.signal(
signal.SIGTERM,
lambda signum, frame: _stop_process(signum, frame, old_handler, process)
)

process = subprocess.Popen(cmd)
process.wait()

class RosbagCmds(UserDict):
def __init__(self):
UserDict.__init__(self)
@@ -878,6 +932,8 @@ def rosbagmain(argv=None):
cmds.add_cmd('compress', compress_cmd, 'Compress one or more bag files.')
cmds.add_cmd('decompress', decompress_cmd, 'Decompress one or more bag files.')
cmds.add_cmd('reindex', reindex_cmd, 'Reindexes one or more bag files.')
cmds.add_cmd('encrypt', encrypt_cmd, 'Encrypt one or more bag files.')
cmds.add_cmd('decrypt', decrypt_cmd, 'Decrypt one or more bag files.')

if argv is None:
argv = sys.argv
4 changes: 2 additions & 2 deletions tools/rosbag_storage/package.xml
Original file line number Diff line number Diff line change
@@ -14,7 +14,7 @@
<build_depend>bzip2</build_depend>
<build_depend version_gte="0.3.17">cpp_common</build_depend>
<build_depend>libconsole-bridge-dev</build_depend>
<build_depend>libgpgme11-dev</build_depend>
<build_depend>libgpgme-dev</build_depend>
<build_depend>libssl-dev</build_depend>
<build_depend>pluginlib</build_depend>
<build_depend>roscpp_serialization</build_depend>
@@ -26,7 +26,7 @@
<run_depend>bzip2</run_depend>
<run_depend version_gte="0.3.17">cpp_common</run_depend>
<run_depend>libconsole-bridge-dev</run_depend>
<run_depend>libgpgme11-dev</run_depend>
<run_depend>libgpgme-dev</run_depend>
<run_depend>libssl-dev</run_depend>
<run_depend>pluginlib</run_depend>
<run_depend>roscpp_serialization</run_depend>

0 comments on commit 932513e

Please sign in to comment.