id.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 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 #ifndef CARTOGRAPHER_MAPPING_ID_H_
00018 #define CARTOGRAPHER_MAPPING_ID_H_
00019 
00020 #include <algorithm>
00021 #include <iostream>
00022 #include <iterator>
00023 #include <limits>
00024 #include <map>
00025 #include <memory>
00026 #include <ostream>
00027 #include <tuple>
00028 #include <vector>
00029 
00030 #include "absl/memory/memory.h"
00031 #include "cartographer/common/port.h"
00032 #include "cartographer/common/time.h"
00033 #include "cartographer/mapping/proto/pose_graph.pb.h"
00034 #include "glog/logging.h"
00035 
00036 namespace cartographer {
00037 namespace mapping {
00038 namespace internal {
00039 
00040 template <class T>
00041 auto GetTimeImpl(const T& t, int) -> decltype(t.time()) {
00042   return t.time();
00043 }
00044 template <class T>
00045 auto GetTimeImpl(const T& t, unsigned) -> decltype(t.time) {
00046   return t.time;
00047 }
00048 template <class T>
00049 common::Time GetTime(const T& t) {
00050   return GetTimeImpl(t, 0);
00051 }
00052 
00053 }  // namespace internal
00054 
00055 // Uniquely identifies a trajectory node using a combination of a unique
00056 // trajectory ID and a zero-based index of the node inside that trajectory.
00057 struct NodeId {
00058   NodeId(int trajectory_id, int node_index)
00059       : trajectory_id(trajectory_id), node_index(node_index) {}
00060 
00061   int trajectory_id;
00062   int node_index;
00063 
00064   bool operator==(const NodeId& other) const {
00065     return std::forward_as_tuple(trajectory_id, node_index) ==
00066            std::forward_as_tuple(other.trajectory_id, other.node_index);
00067   }
00068 
00069   bool operator!=(const NodeId& other) const { return !operator==(other); }
00070 
00071   bool operator<(const NodeId& other) const {
00072     return std::forward_as_tuple(trajectory_id, node_index) <
00073            std::forward_as_tuple(other.trajectory_id, other.node_index);
00074   }
00075 
00076   void ToProto(proto::NodeId* proto) const {
00077     proto->set_trajectory_id(trajectory_id);
00078     proto->set_node_index(node_index);
00079   }
00080 };
00081 
00082 inline std::ostream& operator<<(std::ostream& os, const NodeId& v) {
00083   return os << "(" << v.trajectory_id << ", " << v.node_index << ")";
00084 }
00085 
00086 // Uniquely identifies a submap using a combination of a unique trajectory ID
00087 // and a zero-based index of the submap inside that trajectory.
00088 struct SubmapId {
00089   SubmapId(int trajectory_id, int submap_index)
00090       : trajectory_id(trajectory_id), submap_index(submap_index) {}
00091 
00092   int trajectory_id;
00093   int submap_index;
00094 
00095   bool operator==(const SubmapId& other) const {
00096     return std::forward_as_tuple(trajectory_id, submap_index) ==
00097            std::forward_as_tuple(other.trajectory_id, other.submap_index);
00098   }
00099 
00100   bool operator!=(const SubmapId& other) const { return !operator==(other); }
00101 
00102   bool operator<(const SubmapId& other) const {
00103     return std::forward_as_tuple(trajectory_id, submap_index) <
00104            std::forward_as_tuple(other.trajectory_id, other.submap_index);
00105   }
00106 
00107   void ToProto(proto::SubmapId* proto) const {
00108     proto->set_trajectory_id(trajectory_id);
00109     proto->set_submap_index(submap_index);
00110   }
00111 };
00112 
00113 inline std::ostream& operator<<(std::ostream& os, const SubmapId& v) {
00114   return os << "(" << v.trajectory_id << ", " << v.submap_index << ")";
00115 }
00116 
00117 template <typename IteratorType>
00118 class Range {
00119  public:
00120   Range(const IteratorType& begin, const IteratorType& end)
00121       : begin_(begin), end_(end) {}
00122 
00123   IteratorType begin() const { return begin_; }
00124   IteratorType end() const { return end_; }
00125 
00126  private:
00127   IteratorType begin_;
00128   IteratorType end_;
00129 };
00130 
00131 // Reminiscent of std::map, but indexed by 'IdType' which can be 'NodeId' or
00132 // 'SubmapId'.
00133 // Note: This container will only ever contain non-empty trajectories. Trimming
00134 // the last remaining node of a trajectory drops the trajectory.
00135 template <typename IdType, typename DataType>
00136 class MapById {
00137  private:
00138   struct MapByIndex;
00139 
00140  public:
00141   struct IdDataReference {
00142     IdType id;
00143     const DataType& data;
00144   };
00145 
00146   class ConstIterator {
00147    public:
00148     using iterator_category = std::bidirectional_iterator_tag;
00149     using value_type = IdDataReference;
00150     using difference_type = int64;
00151     using pointer = std::unique_ptr<const IdDataReference>;
00152     using reference = const IdDataReference&;
00153 
00154     explicit ConstIterator(const MapById& map_by_id, const int trajectory_id)
00155         : current_trajectory_(
00156               map_by_id.trajectories_.lower_bound(trajectory_id)),
00157           end_trajectory_(map_by_id.trajectories_.end()) {
00158       if (current_trajectory_ != end_trajectory_) {
00159         current_data_ = current_trajectory_->second.data_.begin();
00160         AdvanceToValidDataIterator();
00161       }
00162     }
00163 
00164     explicit ConstIterator(const MapById& map_by_id, const IdType& id)
00165         : current_trajectory_(map_by_id.trajectories_.find(id.trajectory_id)),
00166           end_trajectory_(map_by_id.trajectories_.end()) {
00167       if (current_trajectory_ != end_trajectory_) {
00168         current_data_ =
00169             current_trajectory_->second.data_.find(MapById::GetIndex(id));
00170         if (current_data_ == current_trajectory_->second.data_.end()) {
00171           current_trajectory_ = end_trajectory_;
00172         }
00173       }
00174     }
00175 
00176     IdDataReference operator*() const {
00177       CHECK(current_trajectory_ != end_trajectory_);
00178       return IdDataReference{
00179           IdType{current_trajectory_->first, current_data_->first},
00180           current_data_->second};
00181     }
00182 
00183     std::unique_ptr<const IdDataReference> operator->() const {
00184       return absl::make_unique<const IdDataReference>(this->operator*());
00185     }
00186 
00187     ConstIterator& operator++() {
00188       CHECK(current_trajectory_ != end_trajectory_);
00189       ++current_data_;
00190       AdvanceToValidDataIterator();
00191       return *this;
00192     }
00193 
00194     ConstIterator& operator--() {
00195       while (current_trajectory_ == end_trajectory_ ||
00196              current_data_ == current_trajectory_->second.data_.begin()) {
00197         --current_trajectory_;
00198         current_data_ = current_trajectory_->second.data_.end();
00199       }
00200       --current_data_;
00201       return *this;
00202     }
00203 
00204     bool operator==(const ConstIterator& it) const {
00205       if (current_trajectory_ == end_trajectory_ ||
00206           it.current_trajectory_ == it.end_trajectory_) {
00207         return current_trajectory_ == it.current_trajectory_;
00208       }
00209       return current_trajectory_ == it.current_trajectory_ &&
00210              current_data_ == it.current_data_;
00211     }
00212 
00213     bool operator!=(const ConstIterator& it) const { return !operator==(it); }
00214 
00215    private:
00216     void AdvanceToValidDataIterator() {
00217       CHECK(current_trajectory_ != end_trajectory_);
00218       while (current_data_ == current_trajectory_->second.data_.end()) {
00219         ++current_trajectory_;
00220         if (current_trajectory_ == end_trajectory_) {
00221           return;
00222         }
00223         current_data_ = current_trajectory_->second.data_.begin();
00224       }
00225     }
00226 
00227     typename std::map<int, MapByIndex>::const_iterator current_trajectory_;
00228     typename std::map<int, MapByIndex>::const_iterator end_trajectory_;
00229     typename std::map<int, DataType>::const_iterator current_data_;
00230   };
00231 
00232   class ConstTrajectoryIterator {
00233    public:
00234     using iterator_category = std::bidirectional_iterator_tag;
00235     using value_type = int;
00236     using difference_type = int64;
00237     using pointer = const int*;
00238     using reference = const int&;
00239 
00240     explicit ConstTrajectoryIterator(
00241         typename std::map<int, MapByIndex>::const_iterator current_trajectory)
00242         : current_trajectory_(current_trajectory) {}
00243 
00244     int operator*() const { return current_trajectory_->first; }
00245 
00246     ConstTrajectoryIterator& operator++() {
00247       ++current_trajectory_;
00248       return *this;
00249     }
00250 
00251     ConstTrajectoryIterator& operator--() {
00252       --current_trajectory_;
00253       return *this;
00254     }
00255 
00256     bool operator==(const ConstTrajectoryIterator& it) const {
00257       return current_trajectory_ == it.current_trajectory_;
00258     }
00259 
00260     bool operator!=(const ConstTrajectoryIterator& it) const {
00261       return !operator==(it);
00262     }
00263 
00264    private:
00265     typename std::map<int, MapByIndex>::const_iterator current_trajectory_;
00266   };
00267 
00268   // Appends data to a 'trajectory_id', creating trajectories as needed.
00269   IdType Append(const int trajectory_id, const DataType& data) {
00270     CHECK_GE(trajectory_id, 0);
00271     auto& trajectory = trajectories_[trajectory_id];
00272     CHECK(trajectory.can_append_);
00273     const int index =
00274         trajectory.data_.empty() ? 0 : trajectory.data_.rbegin()->first + 1;
00275     trajectory.data_.emplace(index, data);
00276     return IdType{trajectory_id, index};
00277   }
00278 
00279   // Returns an iterator to the element at 'id' or the end iterator if it does
00280   // not exist.
00281   ConstIterator find(const IdType& id) const {
00282     return ConstIterator(*this, id);
00283   }
00284 
00285   // Inserts data (which must not exist already) into a trajectory.
00286   void Insert(const IdType& id, const DataType& data) {
00287     CHECK_GE(id.trajectory_id, 0);
00288     CHECK_GE(GetIndex(id), 0);
00289     auto& trajectory = trajectories_[id.trajectory_id];
00290     trajectory.can_append_ = false;
00291     CHECK(trajectory.data_.emplace(GetIndex(id), data).second);
00292   }
00293 
00294   // Removes the data for 'id' which must exist.
00295   void Trim(const IdType& id) {
00296     auto& trajectory = trajectories_.at(id.trajectory_id);
00297     const auto it = trajectory.data_.find(GetIndex(id));
00298     CHECK(it != trajectory.data_.end()) << id;
00299     if (std::next(it) == trajectory.data_.end()) {
00300       // We are removing the data with the highest index from this trajectory.
00301       // We assume that we will never append to it anymore. If we did, we would
00302       // have to make sure that gaps in indices are properly chosen to maintain
00303       // correct connectivity.
00304       trajectory.can_append_ = false;
00305     }
00306     trajectory.data_.erase(it);
00307     if (trajectory.data_.empty()) {
00308       trajectories_.erase(id.trajectory_id);
00309     }
00310   }
00311 
00312   bool Contains(const IdType& id) const {
00313     return trajectories_.count(id.trajectory_id) != 0 &&
00314            trajectories_.at(id.trajectory_id).data_.count(GetIndex(id)) != 0;
00315   }
00316 
00317   const DataType& at(const IdType& id) const {
00318     return trajectories_.at(id.trajectory_id).data_.at(GetIndex(id));
00319   }
00320 
00321   DataType& at(const IdType& id) {
00322     return trajectories_.at(id.trajectory_id).data_.at(GetIndex(id));
00323   }
00324 
00325   // Support querying by trajectory.
00326   ConstIterator BeginOfTrajectory(const int trajectory_id) const {
00327     return ConstIterator(*this, trajectory_id);
00328   }
00329   ConstIterator EndOfTrajectory(const int trajectory_id) const {
00330     return BeginOfTrajectory(trajectory_id + 1);
00331   }
00332 
00333   // Returns 0 if 'trajectory_id' does not exist.
00334   size_t SizeOfTrajectoryOrZero(const int trajectory_id) const {
00335     return trajectories_.count(trajectory_id)
00336                ? trajectories_.at(trajectory_id).data_.size()
00337                : 0;
00338   }
00339 
00340   // Returns count of all elements.
00341   size_t size() const {
00342     size_t size = 0;
00343     for (const auto& item : trajectories_) {
00344       size += item.second.data_.size();
00345     }
00346     return size;
00347   }
00348 
00349   // Returns Range object for range-based loops over the nodes of a trajectory.
00350   Range<ConstIterator> trajectory(const int trajectory_id) const {
00351     return Range<ConstIterator>(BeginOfTrajectory(trajectory_id),
00352                                 EndOfTrajectory(trajectory_id));
00353   }
00354 
00355   // Returns Range object for range-based loops over the trajectory IDs.
00356   Range<ConstTrajectoryIterator> trajectory_ids() const {
00357     return Range<ConstTrajectoryIterator>(
00358         ConstTrajectoryIterator(trajectories_.begin()),
00359         ConstTrajectoryIterator(trajectories_.end()));
00360   }
00361 
00362   ConstIterator begin() const { return BeginOfTrajectory(0); }
00363   ConstIterator end() const {
00364     return BeginOfTrajectory(std::numeric_limits<int>::max());
00365   }
00366 
00367   bool empty() const { return begin() == end(); }
00368 
00369   // Returns an iterator to the first element in the container belonging to
00370   // trajectory 'trajectory_id' whose time is not considered to go before
00371   // 'time', or EndOfTrajectory(trajectory_id) if all keys are considered to go
00372   // before 'time'.
00373   ConstIterator lower_bound(const int trajectory_id,
00374                             const common::Time time) const {
00375     if (SizeOfTrajectoryOrZero(trajectory_id) == 0) {
00376       return EndOfTrajectory(trajectory_id);
00377     }
00378 
00379     const std::map<int, DataType>& trajectory =
00380         trajectories_.at(trajectory_id).data_;
00381     if (internal::GetTime(std::prev(trajectory.end())->second) < time) {
00382       return EndOfTrajectory(trajectory_id);
00383     }
00384     auto left = trajectory.begin();
00385     auto right = std::prev(trajectory.end());
00386     while (left != right) {
00387       const int middle = left->first + (right->first - left->first) / 2;
00388       const auto lower_bound_middle = trajectory.lower_bound(middle);
00389       if (internal::GetTime(lower_bound_middle->second) < time) {
00390         left = std::next(lower_bound_middle);
00391       } else {
00392         right = lower_bound_middle;
00393       }
00394     }
00395 
00396     return ConstIterator(*this, IdType{trajectory_id, left->first});
00397   }
00398 
00399  private:
00400   struct MapByIndex {
00401     bool can_append_ = true;
00402     std::map<int, DataType> data_;
00403   };
00404 
00405   static int GetIndex(const NodeId& id) { return id.node_index; }
00406   static int GetIndex(const SubmapId& id) { return id.submap_index; }
00407 
00408   std::map<int, MapByIndex> trajectories_;
00409 };
00410 
00411 }  // namespace mapping
00412 }  // namespace cartographer
00413 
00414 #endif  // CARTOGRAPHER_MAPPING_ID_H_


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