diff --git a/cartographer_ros/cartographer_ros/rosbag_validate_main.cc b/cartographer_ros/cartographer_ros/rosbag_validate_main.cc index b05db39..6cc282e 100644 --- a/cartographer_ros/cartographer_ros/rosbag_validate_main.cc +++ b/cartographer_ros/cartographer_ros/rosbag_validate_main.cc @@ -311,13 +311,13 @@ void Run(const std::string& bag_filename, const bool dump_timing) { auto& entry = frame_id_to_properties.at(frame_id); if (!first_packet) { const double delta_t_sec = (time - entry.last_timestamp).toSec(); - if (delta_t_sec < 0) { + if (delta_t_sec <= 0) { LOG_FIRST_N(ERROR, 3) << "Sensor with frame_id \"" << frame_id - << "\" jumps backwards in time. Make sure that the bag " - "contains the data for each frame_id sorted by " - "header.stamp, i.e. the order in which they were " - "acquired from the sensor."; + << "\" jumps backwards in time, i.e. timestamps are not strictly " + "increasing. Make sure that the bag contains the data for each " + "frame_id sorted by header.stamp, i.e. the order in which they " + "were acquired from the sensor."; } entry.time_deltas.push_back(delta_t_sec); }