range_data_collator.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2018 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 "cartographer/mapping/internal/range_data_collator.h"
00018 
00019 #include <memory>
00020 
00021 #include "absl/memory/memory.h"
00022 #include "cartographer/mapping/local_slam_result_data.h"
00023 #include "glog/logging.h"
00024 
00025 namespace cartographer {
00026 namespace mapping {
00027 
00028 sensor::TimedPointCloudOriginData RangeDataCollator::AddRangeData(
00029     const std::string& sensor_id,
00030     const sensor::TimedPointCloudData& timed_point_cloud_data) {
00031   CHECK_NE(expected_sensor_ids_.count(sensor_id), 0);
00032   // TODO(gaschler): These two cases can probably be one.
00033   if (id_to_pending_data_.count(sensor_id) != 0) {
00034     current_start_ = current_end_;
00035     // When we have two messages of the same sensor, move forward the older of
00036     // the two (do not send out current).
00037     current_end_ = id_to_pending_data_.at(sensor_id).time;
00038     auto result = CropAndMerge();
00039     id_to_pending_data_.emplace(sensor_id, timed_point_cloud_data);
00040     return result;
00041   }
00042   id_to_pending_data_.emplace(sensor_id, timed_point_cloud_data);
00043   if (expected_sensor_ids_.size() != id_to_pending_data_.size()) {
00044     return {};
00045   }
00046   current_start_ = current_end_;
00047   // We have messages from all sensors, move forward to oldest.
00048   common::Time oldest_timestamp = common::Time::max();
00049   for (const auto& pair : id_to_pending_data_) {
00050     oldest_timestamp = std::min(oldest_timestamp, pair.second.time);
00051   }
00052   current_end_ = oldest_timestamp;
00053   return CropAndMerge();
00054 }
00055 
00056 sensor::TimedPointCloudOriginData RangeDataCollator::CropAndMerge() {
00057   sensor::TimedPointCloudOriginData result{current_end_, {}, {}};
00058   bool warned_for_dropped_points = false;
00059   for (auto it = id_to_pending_data_.begin();
00060        it != id_to_pending_data_.end();) {
00061     sensor::TimedPointCloudData& data = it->second;
00062     sensor::TimedPointCloud& ranges = it->second.ranges;
00063 
00064     auto overlap_begin = ranges.begin();
00065     while (overlap_begin < ranges.end() &&
00066            data.time + common::FromSeconds((*overlap_begin).time) <
00067                current_start_) {
00068       ++overlap_begin;
00069     }
00070     auto overlap_end = overlap_begin;
00071     while (overlap_end < ranges.end() &&
00072            data.time + common::FromSeconds((*overlap_end).time) <=
00073                current_end_) {
00074       ++overlap_end;
00075     }
00076     if (ranges.begin() < overlap_begin && !warned_for_dropped_points) {
00077       LOG(WARNING) << "Dropped " << std::distance(ranges.begin(), overlap_begin)
00078                    << " earlier points.";
00079       warned_for_dropped_points = true;
00080     }
00081 
00082     // Copy overlapping range.
00083     if (overlap_begin < overlap_end) {
00084       std::size_t origin_index = result.origins.size();
00085       result.origins.push_back(data.origin);
00086       const float time_correction =
00087           static_cast<float>(common::ToSeconds(data.time - current_end_));
00088       for (auto overlap_it = overlap_begin; overlap_it != overlap_end;
00089            ++overlap_it) {
00090         sensor::TimedPointCloudOriginData::RangeMeasurement point{*overlap_it,
00091                                                                   origin_index};
00092         // current_end_ + point_time[3]_after == in_timestamp +
00093         // point_time[3]_before
00094         point.point_time.time += time_correction;
00095         result.ranges.push_back(point);
00096       }
00097     }
00098 
00099     // Drop buffered points until overlap_end.
00100     if (overlap_end == ranges.end()) {
00101       it = id_to_pending_data_.erase(it);
00102     } else if (overlap_end == ranges.begin()) {
00103       ++it;
00104     } else {
00105       data = sensor::TimedPointCloudData{
00106           data.time, data.origin,
00107           sensor::TimedPointCloud(overlap_end, ranges.end())};
00108       ++it;
00109     }
00110   }
00111 
00112   std::sort(result.ranges.begin(), result.ranges.end(),
00113             [](const sensor::TimedPointCloudOriginData::RangeMeasurement& a,
00114                const sensor::TimedPointCloudOriginData::RangeMeasurement& b) {
00115               return a.point_time.time < b.point_time.time;
00116             });
00117   return result;
00118 }
00119 
00120 }  // namespace mapping
00121 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35