dbc_bag.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015-2018, Dataspeed Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Dataspeed Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #include <ros/ros.h>
00036 #include <ros/package.h>
00037 #include <rosbag/bag.h>
00038 #include <rosbag/view.h>
00039 #include <boost/foreach.hpp>
00040 #include <can_msgs/Frame.h>
00041 
00042 #include "CanExtractor.h"
00043 
00044 void printHelp() {
00045   printf("Usage: dbc_bag <bag_file> <topic> <dbc_file> [dbc_files]... [-O output_file]\n");
00046   printf("  [--unknown / -u] [--expand / -e]\n");
00047   printf("  [--lz4] [--bz2]\n");
00048   printf("  [--help / -h]\n");
00049 }
00050 
00051 int main(int argc, char** argv)
00052 {
00053   // Arguments
00054   std::string bag_file_in;
00055   std::string bag_file_out;
00056   std::string topic;
00057   std::vector<std::string> dbc_files;
00058   bool _expand = false;
00059   bool _unknown = false;
00060   bool _lz4 = false;
00061   bool _bz2 = false;
00062 
00063   // Parse command line arguments
00064   unsigned int count = 0;
00065   for (int i = 1; i < argc; i++) {
00066     std::string str = argv[i];
00067     if (str == "--help" || str == "-h") {
00068       printHelp();
00069       return 0;
00070     } else if (str == "--unknown" || str == "-u") {
00071       _unknown = true;
00072     } else if (str == "--expand" || str == "-e") {
00073       _expand = true;
00074     } else if (str == "--lz4") {
00075       _lz4 = true;
00076     } else if (str == "--bz2") {
00077       _bz2 = true;
00078     } else if (str == "-O") {
00079       i++;
00080       if (i < argc) {
00081         bag_file_out = argv[i];
00082       }
00083     } else {
00084       if (count == 0) {
00085         bag_file_in = str;
00086       } else if (count == 1) {
00087         topic = str;
00088       } else {
00089         dbc_files.push_back(str);
00090       }
00091       count++;
00092     }
00093   }
00094   if (count < 3) {
00095     printHelp();
00096     return 1;
00097   }
00098   if (bag_file_out.empty()) {
00099     bag_file_out = bag_file_in + ".dbc.bag";
00100   }
00101 
00102   printf("Opening input bag file: '%s'\n", bag_file_in.c_str());
00103   rosbag::Bag raw_bag;
00104   raw_bag.open(bag_file_in, rosbag::bagmode::Read);
00105 
00106   printf("Processing can_msgs/Frame on topic: '%s'\n", topic.c_str());
00107   rosbag::View view(raw_bag, rosbag::TopicQuery(topic));
00108 
00109   printf("Opening dbc files: \n");
00110   for (size_t i = 0; i < dbc_files.size(); i++) {
00111     printf("  - %s\n", dbc_files[i].c_str());
00112   }
00113   dataspeed_can_tools::CanExtractor extractor(dbc_files, true, _expand, _unknown);
00114 
00115   printf("Opening output bag file: '%s'\n", bag_file_out.c_str());
00116   rosbag::compression::CompressionType compression = rosbag::compression::Uncompressed;
00117   if (_lz4) {
00118     compression = rosbag::compression::LZ4;
00119   } else if (_bz2) {
00120     compression = rosbag::compression::BZ2;
00121   }
00122   extractor.openBag(bag_file_out, compression);
00123 
00124   const ros::Time stamp_end = view.getEndTime();
00125   const ros::Time stamp_begin = view.getBeginTime();
00126   if (stamp_end > stamp_begin) {
00127     int last_percent = 0;
00128     BOOST_FOREACH(rosbag::MessageInstance const m, view) {
00129       can_msgs::Frame::ConstPtr msg = m.instantiate<can_msgs::Frame>();
00130       dataspeed_can_tools::RosCanMsgStruct can_msg;
00131       can_msg.id = msg->id;
00132       extractor.getMessage(can_msg);
00133       extractor.pubMessage(msg, m.getTime());
00134 
00135       int percent = 100 * (msg->header.stamp - stamp_begin).toSec() / (stamp_end - stamp_begin).toSec();
00136       if (percent >= last_percent) {
00137         printf("Processing: %d%% complete\n", last_percent);
00138         last_percent += 10;
00139       }
00140     }
00141   } else {
00142     printf("Warning: no messages\n");
00143   }
00144 
00145   extractor.closeBag();
00146   printf("Successfully wrote parsed CAN data to bag\n");
00147 
00148   return 0;
00149 }
00150 


dataspeed_can_tools
Author(s): Micho Radovnikovich
autogenerated on Thu Jun 6 2019 21:16:40