dbc_bag.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015-2020, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include <ros/ros.h>
36 #include <ros/package.h>
37 #include <rosbag/bag.h>
38 #include <rosbag/view.h>
39 #include <boost/foreach.hpp>
40 #include <can_msgs/Frame.h>
41 
42 #include "CanExtractor.h"
43 
44 void printHelp() {
45  printf("Usage: dbc_bag <bag_file> <topic> <dbc_file> [dbc_files]... [-O output_file]\n");
46  printf(" [--unknown / -u] [--expand / -e]\n");
47  printf(" [--lz4] [--bz2]\n");
48  printf(" [--help / -h]\n");
49 }
50 
51 int main(int argc, char** argv)
52 {
53  // Arguments
54  std::string bag_file_in;
55  std::string bag_file_out;
56  std::string topic;
57  std::vector<std::string> dbc_files;
58  bool _expand = false;
59  bool _unknown = false;
60  bool _lz4 = false;
61  bool _bz2 = false;
62 
63  // Parse command line arguments
64  unsigned int count = 0;
65  for (int i = 1; i < argc; i++) {
66  std::string str = argv[i];
67  if (str == "--help" || str == "-h") {
68  printHelp();
69  return 0;
70  } else if (str == "--unknown" || str == "-u") {
71  _unknown = true;
72  } else if (str == "--expand" || str == "-e") {
73  _expand = true;
74  } else if (str == "--lz4") {
75  _lz4 = true;
76  } else if (str == "--bz2") {
77  _bz2 = true;
78  } else if (str == "-O") {
79  i++;
80  if (i < argc) {
81  bag_file_out = argv[i];
82  }
83  } else {
84  if (count == 0) {
85  bag_file_in = str;
86  } else if (count == 1) {
87  topic = str;
88  } else {
89  dbc_files.push_back(str);
90  }
91  count++;
92  }
93  }
94  if (count < 3) {
95  printHelp();
96  return 1;
97  }
98  if (bag_file_out.empty()) {
99  bag_file_out = bag_file_in + ".dbc.bag";
100  }
101 
102  printf("Opening input bag file: '%s'\n", bag_file_in.c_str());
103  rosbag::Bag raw_bag;
104  raw_bag.open(bag_file_in, rosbag::bagmode::Read);
105 
106  printf("Processing can_msgs/Frame on topic: '%s'\n", topic.c_str());
107  rosbag::View view(raw_bag, rosbag::TopicQuery(topic));
108 
109  printf("Opening dbc files: \n");
110  for (size_t i = 0; i < dbc_files.size(); i++) {
111  printf(" - %s\n", dbc_files[i].c_str());
112  }
113  dataspeed_can_tools::CanExtractor extractor(dbc_files, true, _expand, _unknown);
114 
115  printf("Opening output bag file: '%s'\n", bag_file_out.c_str());
117  if (_lz4) {
118  compression = rosbag::compression::LZ4;
119  } else if (_bz2) {
120  compression = rosbag::compression::BZ2;
121  }
122  extractor.openBag(bag_file_out, compression);
123 
124  const ros::Time stamp_end = view.getEndTime();
125  const ros::Time stamp_begin = view.getBeginTime();
126  if (stamp_end > stamp_begin) {
127  int last_percent = 0;
128  BOOST_FOREACH(rosbag::MessageInstance const m, view) {
129  can_msgs::Frame::ConstPtr msg = m.instantiate<can_msgs::Frame>();
131  can_msg.id = msg->id | (msg->is_extended ? 0x80000000 : 0x00000000);
132  extractor.getMessage(can_msg);
133  extractor.pubMessage(msg, m.getTime());
134 
135  int percent = 100 * (msg->header.stamp - stamp_begin).toSec() / (stamp_end - stamp_begin).toSec();
136  if (percent >= last_percent) {
137  printf("Processing: %d%% complete\n", last_percent);
138  last_percent += 10;
139  }
140  }
141  } else {
142  printf("Warning: no messages\n");
143  }
144 
145  extractor.closeBag();
146  printf("Successfully wrote parsed CAN data to bag\n");
147 
148  return 0;
149 }
150 
void open(std::string const &filename, uint32_t mode=bagmode::Read)
ros::Time const & getTime() const
boost::shared_ptr< T > instantiate() const
void printHelp()
Definition: dbc_bag.cpp:44
bool openBag(const std::string &fname, rosbag::compression::CompressionType compression=rosbag::compression::Uncompressed)
void pubMessage(const can_msgs::Frame &msg, const ros::Time &stamp=ros::Time(0))
bool getMessage(RosCanMsgStruct &can_msg)
int main(int argc, char **argv)
Definition: dbc_bag.cpp:51


dataspeed_can_tools
Author(s): Micho Radovnikovich
autogenerated on Thu Jul 9 2020 03:41:59