rosbag_validate_main.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2017 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #include <fstream>
18 #include <iostream>
19 #include <map>
20 #include <set>
21 #include <string>
22 
23 #include "cartographer/common/histogram.h"
26 #include "gflags/gflags.h"
27 #include "glog/logging.h"
28 #include "nav_msgs/Odometry.h"
29 #include "ros/ros.h"
30 #include "ros/time.h"
31 #include "rosbag/bag.h"
32 #include "rosbag/view.h"
33 #include "sensor_msgs/Imu.h"
34 #include "sensor_msgs/LaserScan.h"
35 #include "sensor_msgs/MultiEchoLaserScan.h"
36 #include "sensor_msgs/PointCloud2.h"
37 #include "tf2_eigen/tf2_eigen.h"
38 #include "tf2_msgs/TFMessage.h"
39 #include "tf2_ros/buffer.h"
40 #include "urdf/model.h"
41 
42 DEFINE_string(bag_filename, "", "Bag to process.");
43 DEFINE_bool(dump_timing, false,
44  "Dump per-sensor timing information in files called "
45  "timing_<frame_id>.csv in the current directory.");
46 
47 namespace cartographer_ros {
48 namespace {
49 
50 struct FrameProperties {
52  std::string topic;
53  std::vector<float> time_deltas;
54  std::unique_ptr<std::ofstream> timing_file;
55  std::string data_type;
56 };
57 
58 const double kMinLinearAcceleration = 3.;
59 const double kMaxLinearAcceleration = 30.;
60 const double kTimeDeltaSerializationSensorWarning = 0.1;
61 const double kTimeDeltaSerializationSensorError = 0.5;
62 const double kMinAverageAcceleration = 9.5;
63 const double kMaxAverageAcceleration = 10.5;
64 const double kMaxGapPointsData = 0.1;
65 const double kMaxGapImuData = 0.05;
66 const std::set<std::string> kPointDataTypes = {
67  std::string(
70  sensor_msgs::MultiEchoLaserScan>::value()),
71  std::string(
73 
74 std::unique_ptr<std::ofstream> CreateTimingFile(const std::string& frame_id) {
75  auto timing_file = ::cartographer::common::make_unique<std::ofstream>(
76  std::string("timing_") + frame_id + ".csv", std::ios_base::out);
77 
78  (*timing_file)
79  << "# Timing information for sensor with frame id: " << frame_id
80  << std::endl
81  << "# Columns are in order" << std::endl
82  << "# - packet index of the packet in the bag, first packet is 1"
83  << std::endl
84  << "# - timestamp when rosbag wrote the packet, i.e. "
85  "rosbag::MessageInstance::getTime().toNSec()"
86  << std::endl
87  << "# - timestamp when data was acquired, i.e. "
88  "message.header.stamp.toNSec()"
89  << std::endl
90  << "#" << std::endl
91  << "# The data can be read in python using" << std::endl
92  << "# import numpy" << std::endl
93  << "# np.loadtxt(<filename>, dtype='uint64')" << std::endl;
94 
95  return timing_file;
96 }
97 
98 void CheckImuMessage(const sensor_msgs::Imu& imu_message) {
99  auto linear_acceleration = ToEigen(imu_message.linear_acceleration);
100  if (std::isnan(linear_acceleration.norm()) ||
101  linear_acceleration.norm() < kMinLinearAcceleration ||
102  linear_acceleration.norm() > kMaxLinearAcceleration) {
103  LOG_FIRST_N(WARNING, 3)
104  << "frame_id " << imu_message.header.frame_id << " time "
105  << imu_message.header.stamp.toNSec() << ": IMU linear acceleration is "
106  << linear_acceleration.norm() << " m/s^2,"
107  << " expected is [" << kMinLinearAcceleration << ", "
108  << kMaxLinearAcceleration << "] m/s^2."
109  << " (It should include gravity and be given in m/s^2.)"
110  << " linear_acceleration " << linear_acceleration.transpose();
111  }
112 }
113 
114 bool IsValidPose(const geometry_msgs::Pose& pose) {
115  return ToRigid3d(pose).IsValid();
116 }
117 
118 void CheckOdometryMessage(const nav_msgs::Odometry& message) {
119  const auto& pose = message.pose.pose;
120  if (!IsValidPose(pose)) {
121  LOG_FIRST_N(ERROR, 3) << "frame_id " << message.header.frame_id << " time "
122  << message.header.stamp.toNSec()
123  << ": Odometry pose is invalid."
124  << " pose " << pose;
125  }
126 }
127 
128 void CheckTfMessage(const tf2_msgs::TFMessage& message) {
129  for (const auto& transform : message.transforms) {
130  if (transform.header.frame_id == "map") {
131  LOG_FIRST_N(ERROR, 1)
132  << "Input contains transform message from frame_id \""
133  << transform.header.frame_id << "\" to child_frame_id \""
134  << transform.child_frame_id
135  << "\". This is almost always output published by cartographer and "
136  "should not appear as input. (Unless you have some complex "
137  "remove_frames configuration, this is will not work. Simplest "
138  "solution is to record input without cartographer running.)";
139  }
140  }
141 }
142 
143 bool IsPointDataType(const std::string& data_type) {
144  return (kPointDataTypes.count(data_type) != 0);
145 }
146 
147 class RangeDataChecker {
148  public:
149  template <typename MessageType>
150  void CheckMessage(const MessageType& message) {
151  const std::string& frame_id = message.header.frame_id;
152  ros::Time current_time_stamp = message.header.stamp;
153  RangeChecksum current_checksum;
154  cartographer::common::Time time_from, time_to;
155  ReadRangeMessage(message, &current_checksum, &time_from, &time_to);
156  auto previous_time_to_it = frame_id_to_previous_time_to_.find(frame_id);
157  if (previous_time_to_it != frame_id_to_previous_time_to_.end() &&
158  previous_time_to_it->second >= time_from) {
159  if (previous_time_to_it->second >= time_to) {
160  LOG_FIRST_N(ERROR, 3) << "Sensor with frame_id \"" << frame_id
161  << "\" is not sequential in time."
162  << "Previous range message ends at time "
163  << previous_time_to_it->second
164  << ", current one at time " << time_to;
165  } else {
166  LOG_FIRST_N(WARNING, 3)
167  << "Sensor with frame_id \"" << frame_id
168  << "\" measurements overlap in time. "
169  << "Previous range message, ending at time stamp "
170  << previous_time_to_it->second
171  << ", must finish before current range message, "
172  << "which ranges from " << time_from << " to " << time_to;
173  }
174  double overlap = cartographer::common::ToSeconds(
175  previous_time_to_it->second - time_from);
176  auto it = frame_id_to_max_overlap_duration_.find(frame_id);
177  if (it == frame_id_to_max_overlap_duration_.end() ||
178  overlap > frame_id_to_max_overlap_duration_.at(frame_id)) {
179  frame_id_to_max_overlap_duration_[frame_id] = overlap;
180  }
181  }
182  frame_id_to_previous_time_to_[frame_id] = time_to;
183  if (current_checksum.first == 0) {
184  return;
185  }
186  auto it = frame_id_to_range_checksum_.find(frame_id);
187  if (it != frame_id_to_range_checksum_.end()) {
188  RangeChecksum previous_checksum = it->second;
189  if (previous_checksum == current_checksum) {
190  LOG_FIRST_N(ERROR, 3)
191  << "Sensor with frame_id \"" << frame_id
192  << "\" sends exactly the same range measurements multiple times. "
193  << "Range data at time " << current_time_stamp
194  << " equals preceding data with " << current_checksum.first
195  << " points.";
196  }
197  }
198  frame_id_to_range_checksum_[frame_id] = current_checksum;
199  }
200 
201  void PrintReport() {
202  for (auto& it : frame_id_to_max_overlap_duration_) {
203  LOG(WARNING) << "Sensor with frame_id \"" << it.first
204  << "\" range measurements have longest overlap of "
205  << it.second << " s";
206  }
207  }
208 
209  private:
210  typedef std::pair<size_t /* num_points */, Eigen::Vector4f /* points_sum */>
211  RangeChecksum;
212 
213  template <typename MessageType>
214  static void ReadRangeMessage(const MessageType& message,
215  RangeChecksum* range_checksum,
218  auto point_cloud_time = ToPointCloudWithIntensities(message);
219  const cartographer::sensor::TimedPointCloud& point_cloud =
220  std::get<0>(point_cloud_time).points;
221  *to = std::get<1>(point_cloud_time);
222  *from = *to + cartographer::common::FromSeconds(point_cloud[0][3]);
223  Eigen::Vector4f points_sum = Eigen::Vector4f::Zero();
224  for (const Eigen::Vector4f& point : point_cloud) {
225  points_sum += point;
226  }
227  if (point_cloud.size() > 0) {
228  double first_point_relative_time = point_cloud[0][3];
229  double last_point_relative_time = (*point_cloud.rbegin())[3];
230  if (first_point_relative_time > 0) {
231  LOG_FIRST_N(ERROR, 1)
232  << "Sensor with frame_id \"" << message.header.frame_id
233  << "\" has range data that has positive relative time "
234  << first_point_relative_time << " s, must negative or zero.";
235  }
236  if (last_point_relative_time != 0) {
237  LOG_FIRST_N(INFO, 1)
238  << "Sensor with frame_id \"" << message.header.frame_id
239  << "\" has range data whose last point has relative time "
240  << last_point_relative_time << " s, should be zero.";
241  }
242  }
243  *range_checksum = {point_cloud.size(), points_sum};
244  }
245 
246  std::map<std::string, RangeChecksum> frame_id_to_range_checksum_;
247  std::map<std::string, cartographer::common::Time>
249  std::map<std::string, double> frame_id_to_max_overlap_duration_;
250 };
251 
252 void Run(const std::string& bag_filename, const bool dump_timing) {
253  rosbag::Bag bag;
254  bag.open(bag_filename, rosbag::bagmode::Read);
255  rosbag::View view(bag);
256 
257  std::map<std::string, FrameProperties> frame_id_to_properties;
258  size_t message_index = 0;
259  int num_imu_messages = 0;
260  double sum_imu_acceleration = 0.;
261  RangeDataChecker range_data_checker;
262  for (const rosbag::MessageInstance& message : view) {
263  ++message_index;
264  std::string frame_id;
265  ros::Time time;
266  if (message.isType<sensor_msgs::PointCloud2>()) {
267  auto msg = message.instantiate<sensor_msgs::PointCloud2>();
268  time = msg->header.stamp;
269  frame_id = msg->header.frame_id;
270  range_data_checker.CheckMessage(*msg);
271  } else if (message.isType<sensor_msgs::MultiEchoLaserScan>()) {
272  auto msg = message.instantiate<sensor_msgs::MultiEchoLaserScan>();
273  time = msg->header.stamp;
274  frame_id = msg->header.frame_id;
275  range_data_checker.CheckMessage(*msg);
276  } else if (message.isType<sensor_msgs::LaserScan>()) {
277  auto msg = message.instantiate<sensor_msgs::LaserScan>();
278  time = msg->header.stamp;
279  frame_id = msg->header.frame_id;
280  range_data_checker.CheckMessage(*msg);
281  } else if (message.isType<sensor_msgs::Imu>()) {
282  auto msg = message.instantiate<sensor_msgs::Imu>();
283  time = msg->header.stamp;
284  frame_id = msg->header.frame_id;
285  CheckImuMessage(*msg);
286  num_imu_messages++;
287  sum_imu_acceleration += ToEigen(msg->linear_acceleration).norm();
288  } else if (message.isType<nav_msgs::Odometry>()) {
289  auto msg = message.instantiate<nav_msgs::Odometry>();
290  time = msg->header.stamp;
291  frame_id = msg->header.frame_id;
292  CheckOdometryMessage(*msg);
293  } else if (message.isType<tf2_msgs::TFMessage>()) {
294  auto msg = message.instantiate<tf2_msgs::TFMessage>();
295  CheckTfMessage(*msg);
296  continue;
297  } else {
298  continue;
299  }
300 
301  bool first_packet = false;
302  if (!frame_id_to_properties.count(frame_id)) {
303  frame_id_to_properties.emplace(
304  frame_id,
305  FrameProperties{time, message.getTopic(), std::vector<float>(),
306  dump_timing ? CreateTimingFile(frame_id) : nullptr,
307  message.getDataType()});
308  first_packet = true;
309  }
310 
311  auto& entry = frame_id_to_properties.at(frame_id);
312  if (!first_packet) {
313  const double delta_t_sec = (time - entry.last_timestamp).toSec();
314  if (delta_t_sec < 0) {
315  LOG_FIRST_N(ERROR, 3)
316  << "Sensor with frame_id \"" << frame_id
317  << "\" jumps backwards in time. Make sure that the bag "
318  "contains the data for each frame_id sorted by "
319  "header.stamp, i.e. the order in which they were "
320  "acquired from the sensor.";
321  }
322  entry.time_deltas.push_back(delta_t_sec);
323  }
324 
325  if (entry.topic != message.getTopic()) {
326  LOG_FIRST_N(ERROR, 3)
327  << "frame_id \"" << frame_id
328  << "\" is send on multiple topics. It was seen at least on "
329  << entry.topic << " and " << message.getTopic();
330  }
331  entry.last_timestamp = time;
332 
333  if (dump_timing) {
334  CHECK(entry.timing_file != nullptr);
335  (*entry.timing_file) << message_index << "\t"
336  << message.getTime().toNSec() << "\t"
337  << time.toNSec() << std::endl;
338  }
339 
340  double duration_serialization_sensor = (time - message.getTime()).toSec();
341  if (std::abs(duration_serialization_sensor) >
342  kTimeDeltaSerializationSensorWarning) {
343  std::stringstream stream;
344  stream << "frame_id \"" << frame_id << "\" on topic "
345  << message.getTopic() << " has serialization time "
346  << message.getTime() << " but sensor time " << time
347  << " differing by " << duration_serialization_sensor << " s.";
348  if (std::abs(duration_serialization_sensor) >
349  kTimeDeltaSerializationSensorError) {
350  LOG_FIRST_N(ERROR, 3) << stream.str();
351  } else {
352  LOG_FIRST_N(WARNING, 1) << stream.str();
353  }
354  }
355  }
356  bag.close();
357 
358  range_data_checker.PrintReport();
359 
360  if (num_imu_messages > 0) {
361  double average_imu_acceleration = sum_imu_acceleration / num_imu_messages;
362  if (std::isnan(average_imu_acceleration) ||
363  average_imu_acceleration < kMinAverageAcceleration ||
364  average_imu_acceleration > kMaxAverageAcceleration) {
365  LOG(ERROR) << "Average IMU linear acceleration is "
366  << average_imu_acceleration << " m/s^2,"
367  << " expected is [" << kMinAverageAcceleration << ", "
368  << kMaxAverageAcceleration
369  << "] m/s^2. Linear acceleration data "
370  "should include gravity and be given in m/s^2.";
371  }
372  }
373 
374  constexpr int kNumBucketsForHistogram = 10;
375  for (const auto& entry_pair : frame_id_to_properties) {
376  const FrameProperties& frame_properties = entry_pair.second;
377  float max_time_delta =
378  *std::max_element(frame_properties.time_deltas.begin(),
379  frame_properties.time_deltas.end());
380  if (IsPointDataType(frame_properties.data_type) &&
381  max_time_delta > kMaxGapPointsData) {
382  LOG(ERROR) << "Point data (frame_id: \"" << entry_pair.first
383  << "\") has a large gap, largest is " << max_time_delta
384  << " s, recommended is [0.0005, 0.05] s with no jitter.";
385  }
386  if (frame_properties.data_type ==
388  max_time_delta > kMaxGapImuData) {
389  LOG(ERROR) << "IMU data (frame_id: \"" << entry_pair.first
390  << "\") has a large gap, largest is " << max_time_delta
391  << " s, recommended is [0.0005, 0.005] s with no jitter.";
392  }
393 
395  for (float time_delta : frame_properties.time_deltas) {
396  histogram.Add(time_delta);
397  }
398  LOG(INFO) << "Time delta histogram for consecutive messages on topic \""
399  << frame_properties.topic << "\" (frame_id: \""
400  << entry_pair.first << "\"):\n"
401  << histogram.ToString(kNumBucketsForHistogram);
402  }
403 
404  if (dump_timing) {
405  for (const auto& entry_pair : frame_id_to_properties) {
406  entry_pair.second.timing_file->close();
407  CHECK(*entry_pair.second.timing_file)
408  << "Could not write timing information for \"" << entry_pair.first
409  << "\"";
410  }
411  }
412 }
413 
414 } // namespace
415 } // namespace cartographer_ros
416 
417 int main(int argc, char** argv) {
418  FLAGS_alsologtostderr = true;
419  google::InitGoogleLogging(argv[0]);
420  google::ParseCommandLineFlags(&argc, &argv, true);
421 
422  CHECK(!FLAGS_bag_filename.empty()) << "-bag_filename is missing.";
423  ::cartographer_ros::Run(FLAGS_bag_filename, FLAGS_dump_timing);
424 }
std::unique_ptr< std::ofstream > timing_file
void open(std::string const &filename, uint32_t mode=bagmode::Read)
uint64_t toNSec() const
Rigid3d ToRigid3d(const geometry_msgs::TransformStamped &transform)
const common::Time time
std::string data_type
void close()
UniversalTimeScaleClock::time_point Time
Eigen::Vector3d ToEigen(const geometry_msgs::Vector3 &vector3)
std::map< std::string, RangeChecksum > frame_id_to_range_checksum_
Duration FromSeconds(const double seconds)
std::string ToString(int buckets) const
ros::Time last_timestamp
std::map< std::string, double > frame_id_to_max_overlap_duration_
double ToSeconds(const Duration duration)
DEFINE_string(bag_filename, "", "Bag to process.")
DEFINE_bool(dump_timing, false, "Dump per-sensor timing information in files called " "timing_<frame_id>.csv in the current directory.")
std::vector< Eigen::Vector4f > TimedPointCloud
void Run(const std::string &configuration_directory, const std::string &configuration_basename)
std::string topic
std::map< std::string, cartographer::common::Time > frame_id_to_previous_time_to_
transform::Rigid3d pose
std::tuple<::cartographer::sensor::PointCloudWithIntensities, ::cartographer::common::Time > ToPointCloudWithIntensities(const sensor_msgs::LaserScan &msg)
std::vector< float > time_deltas
int main(int argc, char **argv)


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:06:05