rosbag_validate_main.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include <fstream>
00018 #include <iostream>
00019 #include <map>
00020 #include <set>
00021 #include <string>
00022 
00023 #include "absl/memory/memory.h"
00024 #include "cartographer/common/histogram.h"
00025 #include "cartographer_ros/msg_conversion.h"
00026 #include "gflags/gflags.h"
00027 #include "glog/logging.h"
00028 #include "nav_msgs/Odometry.h"
00029 #include "ros/ros.h"
00030 #include "ros/time.h"
00031 #include "rosbag/bag.h"
00032 #include "rosbag/view.h"
00033 #include "sensor_msgs/Imu.h"
00034 #include "sensor_msgs/LaserScan.h"
00035 #include "sensor_msgs/MultiEchoLaserScan.h"
00036 #include "sensor_msgs/PointCloud2.h"
00037 #include "tf2_eigen/tf2_eigen.h"
00038 #include "tf2_msgs/TFMessage.h"
00039 #include "tf2_ros/buffer.h"
00040 #include "urdf/model.h"
00041 
00042 DEFINE_string(bag_filename, "", "Bag to process.");
00043 DEFINE_bool(dump_timing, false,
00044             "Dump per-sensor timing information in files called "
00045             "timing_<frame_id>.csv in the current directory.");
00046 
00047 namespace cartographer_ros {
00048 namespace {
00049 
00050 struct FrameProperties {
00051   ros::Time last_timestamp;
00052   std::string topic;
00053   std::vector<float> time_deltas;
00054   std::unique_ptr<std::ofstream> timing_file;
00055   std::string data_type;
00056 };
00057 
00058 const double kMinLinearAcceleration = 3.;
00059 const double kMaxLinearAcceleration = 30.;
00060 const double kTimeDeltaSerializationSensorWarning = 0.1;
00061 const double kTimeDeltaSerializationSensorError = 0.5;
00062 const double kMinAverageAcceleration = 9.5;
00063 const double kMaxAverageAcceleration = 10.5;
00064 const double kMaxGapPointsData = 0.1;
00065 const double kMaxGapImuData = 0.05;
00066 const std::set<std::string> kPointDataTypes = {
00067     std::string(
00068         ros::message_traits::DataType<sensor_msgs::PointCloud2>::value()),
00069     std::string(ros::message_traits::DataType<
00070                 sensor_msgs::MultiEchoLaserScan>::value()),
00071     std::string(
00072         ros::message_traits::DataType<sensor_msgs::LaserScan>::value())};
00073 
00074 std::unique_ptr<std::ofstream> CreateTimingFile(const std::string& frame_id) {
00075   auto timing_file = absl::make_unique<std::ofstream>(
00076       std::string("timing_") + frame_id + ".csv", std::ios_base::out);
00077 
00078   (*timing_file)
00079       << "# Timing information for sensor with frame id: " << frame_id
00080       << std::endl
00081       << "# Columns are in order" << std::endl
00082       << "# - packet index of the packet in the bag, first packet is 1"
00083       << std::endl
00084       << "# - timestamp when rosbag wrote the packet, i.e. "
00085          "rosbag::MessageInstance::getTime().toNSec()"
00086       << std::endl
00087       << "# - timestamp when data was acquired, i.e. "
00088          "message.header.stamp.toNSec()"
00089       << std::endl
00090       << "#" << std::endl
00091       << "# The data can be read in python using" << std::endl
00092       << "# import numpy" << std::endl
00093       << "# np.loadtxt(<filename>, dtype='uint64')" << std::endl;
00094 
00095   return timing_file;
00096 }
00097 
00098 void CheckImuMessage(const sensor_msgs::Imu& imu_message) {
00099   auto linear_acceleration = ToEigen(imu_message.linear_acceleration);
00100   if (std::isnan(linear_acceleration.norm()) ||
00101       linear_acceleration.norm() < kMinLinearAcceleration ||
00102       linear_acceleration.norm() > kMaxLinearAcceleration) {
00103     LOG_FIRST_N(WARNING, 3)
00104         << "frame_id " << imu_message.header.frame_id << " time "
00105         << imu_message.header.stamp.toNSec() << ": IMU linear acceleration is "
00106         << linear_acceleration.norm() << " m/s^2,"
00107         << " expected is [" << kMinLinearAcceleration << ", "
00108         << kMaxLinearAcceleration << "] m/s^2."
00109         << " (It should include gravity and be given in m/s^2.)"
00110         << " linear_acceleration " << linear_acceleration.transpose();
00111   }
00112 }
00113 
00114 bool IsValidPose(const geometry_msgs::Pose& pose) {
00115   return ToRigid3d(pose).IsValid();
00116 }
00117 
00118 void CheckOdometryMessage(const nav_msgs::Odometry& message) {
00119   const auto& pose = message.pose.pose;
00120   if (!IsValidPose(pose)) {
00121     LOG_FIRST_N(ERROR, 3) << "frame_id " << message.header.frame_id << " time "
00122                           << message.header.stamp.toNSec()
00123                           << ": Odometry pose is invalid."
00124                           << " pose " << pose;
00125   }
00126 }
00127 
00128 void CheckTfMessage(const tf2_msgs::TFMessage& message) {
00129   for (const auto& transform : message.transforms) {
00130     if (transform.header.frame_id == "map") {
00131       LOG_FIRST_N(ERROR, 1)
00132           << "Input contains transform message from frame_id \""
00133           << transform.header.frame_id << "\" to child_frame_id \""
00134           << transform.child_frame_id
00135           << "\". This is almost always output published by cartographer and "
00136              "should not appear as input. (Unless you have some complex "
00137              "remove_frames configuration, this is will not work. Simplest "
00138              "solution is to record input without cartographer running.)";
00139     }
00140   }
00141 }
00142 
00143 bool IsPointDataType(const std::string& data_type) {
00144   return (kPointDataTypes.count(data_type) != 0);
00145 }
00146 
00147 class RangeDataChecker {
00148  public:
00149   template <typename MessageType>
00150   void CheckMessage(const MessageType& message) {
00151     const std::string& frame_id = message.header.frame_id;
00152     ros::Time current_time_stamp = message.header.stamp;
00153     RangeChecksum current_checksum;
00154     cartographer::common::Time time_from, time_to;
00155     ReadRangeMessage(message, &current_checksum, &time_from, &time_to);
00156     auto previous_time_to_it = frame_id_to_previous_time_to_.find(frame_id);
00157     if (previous_time_to_it != frame_id_to_previous_time_to_.end() &&
00158         previous_time_to_it->second >= time_from) {
00159       if (previous_time_to_it->second >= time_to) {
00160         LOG_FIRST_N(ERROR, 3) << "Sensor with frame_id \"" << frame_id
00161                               << "\" is not sequential in time."
00162                               << "Previous range message ends at time "
00163                               << previous_time_to_it->second
00164                               << ", current one at time " << time_to;
00165       } else {
00166         LOG_FIRST_N(WARNING, 3)
00167             << "Sensor with frame_id \"" << frame_id
00168             << "\" measurements overlap in time. "
00169             << "Previous range message, ending at time stamp "
00170             << previous_time_to_it->second
00171             << ", must finish before current range message, "
00172             << "which ranges from " << time_from << " to " << time_to;
00173       }
00174       double overlap = cartographer::common::ToSeconds(
00175           previous_time_to_it->second - time_from);
00176       auto it = frame_id_to_max_overlap_duration_.find(frame_id);
00177       if (it == frame_id_to_max_overlap_duration_.end() ||
00178           overlap > frame_id_to_max_overlap_duration_.at(frame_id)) {
00179         frame_id_to_max_overlap_duration_[frame_id] = overlap;
00180       }
00181     }
00182     frame_id_to_previous_time_to_[frame_id] = time_to;
00183     if (current_checksum.first == 0) {
00184       return;
00185     }
00186     auto it = frame_id_to_range_checksum_.find(frame_id);
00187     if (it != frame_id_to_range_checksum_.end()) {
00188       RangeChecksum previous_checksum = it->second;
00189       if (previous_checksum == current_checksum) {
00190         LOG_FIRST_N(ERROR, 3)
00191             << "Sensor with frame_id \"" << frame_id
00192             << "\" sends exactly the same range measurements multiple times. "
00193             << "Range data at time " << current_time_stamp
00194             << " equals preceding data with " << current_checksum.first
00195             << " points.";
00196       }
00197     }
00198     frame_id_to_range_checksum_[frame_id] = current_checksum;
00199   }
00200 
00201   void PrintReport() {
00202     for (auto& it : frame_id_to_max_overlap_duration_) {
00203       LOG(WARNING) << "Sensor with frame_id \"" << it.first
00204                    << "\" range measurements have longest overlap of "
00205                    << it.second << " s";
00206     }
00207   }
00208 
00209  private:
00210   typedef std::pair<size_t /* num_points */, Eigen::Vector4f /* points_sum */>
00211       RangeChecksum;
00212 
00213   template <typename MessageType>
00214   static void ReadRangeMessage(const MessageType& message,
00215                                RangeChecksum* range_checksum,
00216                                cartographer::common::Time* from,
00217                                cartographer::common::Time* to) {
00218     auto point_cloud_time = ToPointCloudWithIntensities(message);
00219     const cartographer::sensor::TimedPointCloud& point_cloud =
00220         std::get<0>(point_cloud_time).points;
00221     *to = std::get<1>(point_cloud_time);
00222     *from = *to + cartographer::common::FromSeconds(point_cloud[0].time);
00223     Eigen::Vector4f points_sum = Eigen::Vector4f::Zero();
00224     for (const auto& point : point_cloud) {
00225       points_sum.head<3>() += point.position;
00226       points_sum[3] += point.time;
00227     }
00228     if (point_cloud.size() > 0) {
00229       double first_point_relative_time = point_cloud[0].time;
00230       double last_point_relative_time = (*point_cloud.rbegin()).time;
00231       if (first_point_relative_time > 0) {
00232         LOG_FIRST_N(ERROR, 1)
00233             << "Sensor with frame_id \"" << message.header.frame_id
00234             << "\" has range data that has positive relative time "
00235             << first_point_relative_time << " s, must negative or zero.";
00236       }
00237       if (last_point_relative_time != 0) {
00238         LOG_FIRST_N(INFO, 1)
00239             << "Sensor with frame_id \"" << message.header.frame_id
00240             << "\" has range data whose last point has relative time "
00241             << last_point_relative_time << " s, should be zero.";
00242       }
00243     }
00244     *range_checksum = {point_cloud.size(), points_sum};
00245   }
00246 
00247   std::map<std::string, RangeChecksum> frame_id_to_range_checksum_;
00248   std::map<std::string, cartographer::common::Time>
00249       frame_id_to_previous_time_to_;
00250   std::map<std::string, double> frame_id_to_max_overlap_duration_;
00251 };
00252 
00253 void Run(const std::string& bag_filename, const bool dump_timing) {
00254   rosbag::Bag bag;
00255   bag.open(bag_filename, rosbag::bagmode::Read);
00256   rosbag::View view(bag);
00257 
00258   std::map<std::string, FrameProperties> frame_id_to_properties;
00259   size_t message_index = 0;
00260   int num_imu_messages = 0;
00261   double sum_imu_acceleration = 0.;
00262   RangeDataChecker range_data_checker;
00263   for (const rosbag::MessageInstance& message : view) {
00264     ++message_index;
00265     std::string frame_id;
00266     ros::Time time;
00267     if (message.isType<sensor_msgs::PointCloud2>()) {
00268       auto msg = message.instantiate<sensor_msgs::PointCloud2>();
00269       time = msg->header.stamp;
00270       frame_id = msg->header.frame_id;
00271       range_data_checker.CheckMessage(*msg);
00272     } else if (message.isType<sensor_msgs::MultiEchoLaserScan>()) {
00273       auto msg = message.instantiate<sensor_msgs::MultiEchoLaserScan>();
00274       time = msg->header.stamp;
00275       frame_id = msg->header.frame_id;
00276       range_data_checker.CheckMessage(*msg);
00277     } else if (message.isType<sensor_msgs::LaserScan>()) {
00278       auto msg = message.instantiate<sensor_msgs::LaserScan>();
00279       time = msg->header.stamp;
00280       frame_id = msg->header.frame_id;
00281       range_data_checker.CheckMessage(*msg);
00282     } else if (message.isType<sensor_msgs::Imu>()) {
00283       auto msg = message.instantiate<sensor_msgs::Imu>();
00284       time = msg->header.stamp;
00285       frame_id = msg->header.frame_id;
00286       CheckImuMessage(*msg);
00287       num_imu_messages++;
00288       sum_imu_acceleration += ToEigen(msg->linear_acceleration).norm();
00289     } else if (message.isType<nav_msgs::Odometry>()) {
00290       auto msg = message.instantiate<nav_msgs::Odometry>();
00291       time = msg->header.stamp;
00292       frame_id = msg->header.frame_id;
00293       CheckOdometryMessage(*msg);
00294     } else if (message.isType<tf2_msgs::TFMessage>()) {
00295       auto msg = message.instantiate<tf2_msgs::TFMessage>();
00296       CheckTfMessage(*msg);
00297       continue;
00298     } else {
00299       continue;
00300     }
00301 
00302     bool first_packet = false;
00303     if (!frame_id_to_properties.count(frame_id)) {
00304       frame_id_to_properties.emplace(
00305           frame_id,
00306           FrameProperties{time, message.getTopic(), std::vector<float>(),
00307                           dump_timing ? CreateTimingFile(frame_id) : nullptr,
00308                           message.getDataType()});
00309       first_packet = true;
00310     }
00311 
00312     auto& entry = frame_id_to_properties.at(frame_id);
00313     if (!first_packet) {
00314       const double delta_t_sec = (time - entry.last_timestamp).toSec();
00315       if (delta_t_sec <= 0) {
00316         LOG_FIRST_N(ERROR, 3)
00317             << "Sensor with frame_id \"" << frame_id
00318             << "\" jumps backwards in time, i.e. timestamps are not strictly "
00319                "increasing. Make sure that the bag contains the data for each "
00320                "frame_id sorted by header.stamp, i.e. the order in which they "
00321                "were acquired from the sensor.";
00322       }
00323       entry.time_deltas.push_back(delta_t_sec);
00324     }
00325 
00326     if (entry.topic != message.getTopic()) {
00327       LOG_FIRST_N(ERROR, 3)
00328           << "frame_id \"" << frame_id
00329           << "\" is send on multiple topics. It was seen at least on "
00330           << entry.topic << " and " << message.getTopic();
00331     }
00332     entry.last_timestamp = time;
00333 
00334     if (dump_timing) {
00335       CHECK(entry.timing_file != nullptr);
00336       (*entry.timing_file) << message_index << "\t"
00337                            << message.getTime().toNSec() << "\t"
00338                            << time.toNSec() << std::endl;
00339     }
00340 
00341     double duration_serialization_sensor = (time - message.getTime()).toSec();
00342     if (std::abs(duration_serialization_sensor) >
00343         kTimeDeltaSerializationSensorWarning) {
00344       std::stringstream stream;
00345       stream << "frame_id \"" << frame_id << "\" on topic "
00346              << message.getTopic() << " has serialization time "
00347              << message.getTime() << " but sensor time " << time
00348              << " differing by " << duration_serialization_sensor << " s.";
00349       if (std::abs(duration_serialization_sensor) >
00350           kTimeDeltaSerializationSensorError) {
00351         LOG_FIRST_N(ERROR, 3) << stream.str();
00352       } else {
00353         LOG_FIRST_N(WARNING, 1) << stream.str();
00354       }
00355     }
00356   }
00357   bag.close();
00358 
00359   range_data_checker.PrintReport();
00360 
00361   if (num_imu_messages > 0) {
00362     double average_imu_acceleration = sum_imu_acceleration / num_imu_messages;
00363     if (std::isnan(average_imu_acceleration) ||
00364         average_imu_acceleration < kMinAverageAcceleration ||
00365         average_imu_acceleration > kMaxAverageAcceleration) {
00366       LOG(ERROR) << "Average IMU linear acceleration is "
00367                  << average_imu_acceleration << " m/s^2,"
00368                  << " expected is [" << kMinAverageAcceleration << ", "
00369                  << kMaxAverageAcceleration
00370                  << "] m/s^2. Linear acceleration data "
00371                     "should include gravity and be given in m/s^2.";
00372     }
00373   }
00374 
00375   constexpr int kNumBucketsForHistogram = 10;
00376   for (const auto& entry_pair : frame_id_to_properties) {
00377     const FrameProperties& frame_properties = entry_pair.second;
00378     float max_time_delta =
00379         *std::max_element(frame_properties.time_deltas.begin(),
00380                           frame_properties.time_deltas.end());
00381     if (IsPointDataType(frame_properties.data_type) &&
00382         max_time_delta > kMaxGapPointsData) {
00383       LOG(ERROR) << "Point data (frame_id: \"" << entry_pair.first
00384                  << "\") has a large gap, largest is " << max_time_delta
00385                  << " s, recommended is [0.0005, 0.05] s with no jitter.";
00386     }
00387     if (frame_properties.data_type ==
00388             ros::message_traits::DataType<sensor_msgs::Imu>::value() &&
00389         max_time_delta > kMaxGapImuData) {
00390       LOG(ERROR) << "IMU data (frame_id: \"" << entry_pair.first
00391                  << "\") has a large gap, largest is " << max_time_delta
00392                  << " s, recommended is [0.0005, 0.005] s with no jitter.";
00393     }
00394 
00395     cartographer::common::Histogram histogram;
00396     for (float time_delta : frame_properties.time_deltas) {
00397       histogram.Add(time_delta);
00398     }
00399     LOG(INFO) << "Time delta histogram for consecutive messages on topic \""
00400               << frame_properties.topic << "\" (frame_id: \""
00401               << entry_pair.first << "\"):\n"
00402               << histogram.ToString(kNumBucketsForHistogram);
00403   }
00404 
00405   if (dump_timing) {
00406     for (const auto& entry_pair : frame_id_to_properties) {
00407       entry_pair.second.timing_file->close();
00408       CHECK(*entry_pair.second.timing_file)
00409           << "Could not write timing information for \"" << entry_pair.first
00410           << "\"";
00411     }
00412   }
00413 }
00414 
00415 }  // namespace
00416 }  // namespace cartographer_ros
00417 
00418 int main(int argc, char** argv) {
00419   FLAGS_alsologtostderr = true;
00420   google::InitGoogleLogging(argv[0]);
00421   google::ParseCommandLineFlags(&argc, &argv, true);
00422 
00423   CHECK(!FLAGS_bag_filename.empty()) << "-bag_filename is missing.";
00424   ::cartographer_ros::Run(FLAGS_bag_filename, FLAGS_dump_timing);
00425 }


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Wed Jul 10 2019 04:10:28