From 4990d4d5e9237edf85916f5c4f5848f6f680b549 Mon Sep 17 00:00:00 2001 From: Alexander Belyaev <32522095+pifon2a@users.noreply.github.com> Date: Fri, 27 Jul 2018 19:05:45 +0200 Subject: [PATCH] [ABSL] Purge common::optional. (#1339) --- cartographer/BUILD.bazel | 2 +- .../cloud/internal/client/pose_graph_stub.cc | 2 +- ...eceive_global_slam_optimizations_handler.h | 2 +- cartographer/common/optional.h | 69 ------------------- cartographer/common/optional_test.cc | 63 ----------------- cartographer/mapping/2d/tsdf_2d.cc | 2 + .../2d/local_trajectory_builder_2d.cc | 4 +- .../internal/2d/local_trajectory_builder_2d.h | 8 +-- .../mapping/internal/2d/pose_graph_2d.cc | 2 +- .../3d/local_trajectory_builder_3d.cc | 4 +- .../internal/3d/local_trajectory_builder_3d.h | 8 +-- .../mapping/internal/3d/pose_graph_3d.cc | 2 +- .../optimization/optimization_problem_3d.h | 2 +- cartographer/mapping/pose_graph_interface.h | 6 +- cartographer/mapping/trajectory_node.h | 4 +- cartographer/sensor/collator_interface.h | 4 +- cartographer/sensor/fixed_frame_pose_data.cc | 6 +- cartographer/sensor/fixed_frame_pose_data.h | 4 +- cartographer/sensor/internal/collator.cc | 4 +- cartographer/sensor/internal/collator.h | 2 +- .../sensor/internal/trajectory_collator.cc | 4 +- .../sensor/internal/trajectory_collator.h | 2 +- cmake/modules/FindAbseil.cmake | 9 +++ 23 files changed, 47 insertions(+), 168 deletions(-) delete mode 100644 cartographer/common/optional.h delete mode 100644 cartographer/common/optional_test.cc diff --git a/cartographer/BUILD.bazel b/cartographer/BUILD.bazel index 5c98b4b..6ff5cce 100644 --- a/cartographer/BUILD.bazel +++ b/cartographer/BUILD.bazel @@ -95,12 +95,12 @@ cc_library( deps = [ ":cc_protos", "@boost//:iostreams", + "@com_google_absl//absl/types:optional", "@com_google_glog//:glog", "@org_cairographics_cairo//:cairo", "@org_ceres_solver_ceres_solver//:ceres", "@org_lua_lua//:lua", "@org_tuxfamily_eigen//:eigen", - "@com_google_absl//absl/strings", ], ) diff --git a/cartographer/cloud/internal/client/pose_graph_stub.cc b/cartographer/cloud/internal/client/pose_graph_stub.cc index f9de08b..c7ea2ea 100644 --- a/cartographer/cloud/internal/client/pose_graph_stub.cc +++ b/cartographer/cloud/internal/client/pose_graph_stub.cc @@ -93,7 +93,7 @@ PoseGraphStub::GetTrajectoryNodePoses() const { CHECK(client.Write(request)); mapping::MapById node_poses; for (const auto& node_pose : client.response().node_poses()) { - common::optional + absl::optional constant_pose_data; if (node_pose.has_constant_pose_data()) { constant_pose_data = mapping::TrajectoryNodePose::ConstantPoseData{ diff --git a/cartographer/cloud/internal/handlers/receive_global_slam_optimizations_handler.h b/cartographer/cloud/internal/handlers/receive_global_slam_optimizations_handler.h index 8a177b6..725cd30 100644 --- a/cartographer/cloud/internal/handlers/receive_global_slam_optimizations_handler.h +++ b/cartographer/cloud/internal/handlers/receive_global_slam_optimizations_handler.h @@ -39,7 +39,7 @@ class ReceiveGlobalSlamOptimizationsHandler void OnFinish() override; private: - common::optional subscription_index_; + absl::optional subscription_index_; }; } // namespace handlers diff --git a/cartographer/common/optional.h b/cartographer/common/optional.h deleted file mode 100644 index 58e0a92..0000000 --- a/cartographer/common/optional.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright 2017 The Cartographer Authors - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef CARTOGRAPHER_COMMON_OPTIONAL_H_ -#define CARTOGRAPHER_COMMON_OPTIONAL_H_ - -#include - -#include "cartographer/common/make_unique.h" -#include "glog/logging.h" - -namespace cartographer { -namespace common { - -template -class optional { - public: - optional() {} - - optional(const optional& other) { - if (other.has_value()) { - value_ = common::make_unique(other.value()); - } - } - - explicit optional(const T& value) { value_ = common::make_unique(value); } - - bool has_value() const { return value_ != nullptr; } - - const T& value() const { - CHECK(value_ != nullptr); - return *value_; - } - - optional& operator=(const T& other_value) { - this->value_ = common::make_unique(other_value); - return *this; - } - - optional& operator=(const optional& other) { - if (!other.has_value()) { - this->value_ = nullptr; - } else { - this->value_ = common::make_unique(other.value()); - } - return *this; - } - - private: - std::unique_ptr value_; -}; - -} // namespace common -} // namespace cartographer - -#endif // CARTOGRAPHER_COMMON_OPTIONAL_H_ diff --git a/cartographer/common/optional_test.cc b/cartographer/common/optional_test.cc deleted file mode 100644 index fbf96c9..0000000 --- a/cartographer/common/optional_test.cc +++ /dev/null @@ -1,63 +0,0 @@ -/* - * Copyright 2017 The Cartographer Authors - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#include "cartographer/common/optional.h" - -#include "gtest/gtest.h" - -namespace cartographer { -namespace common { -namespace { - -TEST(OptionalTest, CreateDisengagedObject) { - const optional o; - EXPECT_FALSE(o.has_value()); - const optional x; - EXPECT_FALSE(x.has_value()); -} - -TEST(OptionalTest, CreateWithValue) { - const optional a(5); - EXPECT_TRUE(a.has_value()); - EXPECT_EQ(5, a.value()); -} - -TEST(OptionalTest, CreateFromOtherOptional) { - const optional a(5); - const optional b = a; - EXPECT_TRUE(a.has_value()); - EXPECT_TRUE(b.has_value()); - EXPECT_EQ(5, a.value()); - EXPECT_EQ(5, b.value()); -} - -TEST(OptionalTest, AssignmentOperator) { - optional a(5); - optional b(4); - optional c; - a = b; - EXPECT_TRUE(a.has_value()); - EXPECT_EQ(4, a.value()); - a = c; - EXPECT_FALSE(a.has_value()); - a = 3; - EXPECT_TRUE(a.has_value()); - EXPECT_EQ(3, a.value()); -} - -} // namespace -} // namespace common -} // namespace cartographer diff --git a/cartographer/mapping/2d/tsdf_2d.cc b/cartographer/mapping/2d/tsdf_2d.cc index 1264146..12cdf68 100644 --- a/cartographer/mapping/2d/tsdf_2d.cc +++ b/cartographer/mapping/2d/tsdf_2d.cc @@ -16,6 +16,8 @@ #include "cartographer/mapping/2d/tsdf_2d.h" +#include "cartographer/common/make_unique.h" + namespace cartographer { namespace mapping { diff --git a/cartographer/mapping/internal/2d/local_trajectory_builder_2d.cc b/cartographer/mapping/internal/2d/local_trajectory_builder_2d.cc index 83aa9a3..de036a6 100644 --- a/cartographer/mapping/internal/2d/local_trajectory_builder_2d.cc +++ b/cartographer/mapping/internal/2d/local_trajectory_builder_2d.cc @@ -187,7 +187,7 @@ LocalTrajectoryBuilder2D::AddRangeData( if (num_accumulated_ >= options_.num_accumulated_range_data()) { const common::Time current_sensor_time = synchronized_data.time; - common::optional sensor_duration; + absl::optional sensor_duration; if (last_sensor_time_.has_value()) { sensor_duration = current_sensor_time - last_sensor_time_.value(); } @@ -213,7 +213,7 @@ LocalTrajectoryBuilder2D::AddAccumulatedRangeData( const common::Time time, const sensor::RangeData& gravity_aligned_range_data, const transform::Rigid3d& gravity_alignment, - const common::optional& sensor_duration) { + const absl::optional& sensor_duration) { if (gravity_aligned_range_data.returns.empty()) { LOG(WARNING) << "Dropped empty horizontal range data."; return nullptr; diff --git a/cartographer/mapping/internal/2d/local_trajectory_builder_2d.h b/cartographer/mapping/internal/2d/local_trajectory_builder_2d.h index 8f55f5c..1a93463 100644 --- a/cartographer/mapping/internal/2d/local_trajectory_builder_2d.h +++ b/cartographer/mapping/internal/2d/local_trajectory_builder_2d.h @@ -80,7 +80,7 @@ class LocalTrajectoryBuilder2D { std::unique_ptr AddAccumulatedRangeData( common::Time time, const sensor::RangeData& gravity_aligned_range_data, const transform::Rigid3d& gravity_alignment, - const common::optional& sensor_duration); + const absl::optional& sensor_duration); sensor::RangeData TransformToGravityAlignedFrameAndFilter( const transform::Rigid3f& transform_to_gravity_aligned_frame, const sensor::RangeData& range_data) const; @@ -112,9 +112,9 @@ class LocalTrajectoryBuilder2D { int num_accumulated_ = 0; sensor::RangeData accumulated_range_data_; - common::optional last_wall_time_; - common::optional last_thread_cpu_time_seconds_; - common::optional last_sensor_time_; + absl::optional last_wall_time_; + absl::optional last_thread_cpu_time_seconds_; + absl::optional last_sensor_time_; RangeDataCollator range_data_collator_; }; diff --git a/cartographer/mapping/internal/2d/pose_graph_2d.cc b/cartographer/mapping/internal/2d/pose_graph_2d.cc index 8f9cc9e..782ef50 100644 --- a/cartographer/mapping/internal/2d/pose_graph_2d.cc +++ b/cartographer/mapping/internal/2d/pose_graph_2d.cc @@ -845,7 +845,7 @@ MapById PoseGraph2D::GetTrajectoryNodePoses() MapById node_poses; common::MutexLocker locker(&mutex_); for (const auto& node_id_data : data_.trajectory_nodes) { - common::optional constant_pose_data; + absl::optional constant_pose_data; if (node_id_data.data.constant_data != nullptr) { constant_pose_data = TrajectoryNodePose::ConstantPoseData{ node_id_data.data.constant_data->time, diff --git a/cartographer/mapping/internal/3d/local_trajectory_builder_3d.cc b/cartographer/mapping/internal/3d/local_trajectory_builder_3d.cc index 8187a71..820c30f 100644 --- a/cartographer/mapping/internal/3d/local_trajectory_builder_3d.cc +++ b/cartographer/mapping/internal/3d/local_trajectory_builder_3d.cc @@ -198,7 +198,7 @@ LocalTrajectoryBuilder3D::AddRangeData( ++num_accumulated_; if (num_accumulated_ >= options_.num_accumulated_range_data()) { - common::optional sensor_duration; + absl::optional sensor_duration; if (last_sensor_time_.has_value()) { sensor_duration = current_sensor_time - last_sensor_time_.value(); } @@ -237,7 +237,7 @@ std::unique_ptr LocalTrajectoryBuilder3D::AddAccumulatedRangeData( const common::Time time, const sensor::RangeData& filtered_range_data_in_tracking, - const common::optional& sensor_duration) { + const absl::optional& sensor_duration) { if (filtered_range_data_in_tracking.returns.empty()) { LOG(WARNING) << "Dropped empty range data."; return nullptr; diff --git a/cartographer/mapping/internal/3d/local_trajectory_builder_3d.h b/cartographer/mapping/internal/3d/local_trajectory_builder_3d.h index dfc34c9..2abeee8 100644 --- a/cartographer/mapping/internal/3d/local_trajectory_builder_3d.h +++ b/cartographer/mapping/internal/3d/local_trajectory_builder_3d.h @@ -78,7 +78,7 @@ class LocalTrajectoryBuilder3D { std::unique_ptr AddAccumulatedRangeData( common::Time time, const sensor::RangeData& filtered_range_data_in_tracking, - const common::optional& sensor_duration); + const absl::optional& sensor_duration); std::unique_ptr InsertIntoSubmap( common::Time time, const sensor::RangeData& filtered_range_data_in_local, @@ -107,13 +107,13 @@ class LocalTrajectoryBuilder3D { int num_accumulated_ = 0; sensor::RangeData accumulated_range_data_; - common::optional last_wall_time_; + absl::optional last_wall_time_; - common::optional last_thread_cpu_time_seconds_; + absl::optional last_thread_cpu_time_seconds_; RangeDataCollator range_data_collator_; - common::optional last_sensor_time_; + absl::optional last_sensor_time_; }; } // namespace mapping diff --git a/cartographer/mapping/internal/3d/pose_graph_3d.cc b/cartographer/mapping/internal/3d/pose_graph_3d.cc index 1b77c65..cc6726c 100644 --- a/cartographer/mapping/internal/3d/pose_graph_3d.cc +++ b/cartographer/mapping/internal/3d/pose_graph_3d.cc @@ -888,7 +888,7 @@ MapById PoseGraph3D::GetTrajectoryNodePoses() MapById node_poses; common::MutexLocker locker(&mutex_); for (const auto& node_id_data : data_.trajectory_nodes) { - common::optional constant_pose_data; + absl::optional constant_pose_data; if (node_id_data.data.constant_data != nullptr) { constant_pose_data = TrajectoryNodePose::ConstantPoseData{ node_id_data.data.constant_data->time, diff --git a/cartographer/mapping/internal/optimization/optimization_problem_3d.h b/cartographer/mapping/internal/optimization/optimization_problem_3d.h index fceb651..721fde9 100644 --- a/cartographer/mapping/internal/optimization/optimization_problem_3d.h +++ b/cartographer/mapping/internal/optimization/optimization_problem_3d.h @@ -24,7 +24,7 @@ #include "Eigen/Core" #include "Eigen/Geometry" -#include "cartographer/common/optional.h" +#include "absl/types/optional.h" #include "cartographer/common/port.h" #include "cartographer/common/time.h" #include "cartographer/mapping/id.h" diff --git a/cartographer/mapping/pose_graph_interface.h b/cartographer/mapping/pose_graph_interface.h index 5f20dca..22c7256 100644 --- a/cartographer/mapping/pose_graph_interface.h +++ b/cartographer/mapping/pose_graph_interface.h @@ -20,7 +20,7 @@ #include #include -#include "cartographer/common/optional.h" +#include "absl/types/optional.h" #include "cartographer/mapping/id.h" #include "cartographer/mapping/submaps.h" #include "cartographer/transform/rigid_transform.h" @@ -61,7 +61,7 @@ class PoseGraphInterface { double rotation_weight; }; std::vector landmark_observations; - common::optional global_landmark_pose; + absl::optional global_landmark_pose; }; struct SubmapPose { @@ -77,7 +77,7 @@ class PoseGraphInterface { struct TrajectoryData { double gravity_constant = 9.8; std::array imu_calibration{{1., 0., 0., 0.}}; - common::optional fixed_frame_origin_in_map; + absl::optional fixed_frame_origin_in_map; }; enum class TrajectoryState { ACTIVE, FINISHED, FROZEN, DELETED }; diff --git a/cartographer/mapping/trajectory_node.h b/cartographer/mapping/trajectory_node.h index 12c2057..9238cfc 100644 --- a/cartographer/mapping/trajectory_node.h +++ b/cartographer/mapping/trajectory_node.h @@ -21,7 +21,7 @@ #include #include "Eigen/Core" -#include "cartographer/common/optional.h" +#include "absl/types/optional.h" #include "cartographer/common/time.h" #include "cartographer/mapping/proto/trajectory_node_data.pb.h" #include "cartographer/sensor/range_data.h" @@ -38,7 +38,7 @@ struct TrajectoryNodePose { // The node pose in the global SLAM frame. transform::Rigid3d global_pose; - common::optional constant_pose_data; + absl::optional constant_pose_data; }; struct TrajectoryNode { diff --git a/cartographer/sensor/collator_interface.h b/cartographer/sensor/collator_interface.h index eb1d787..6fff62d 100644 --- a/cartographer/sensor/collator_interface.h +++ b/cartographer/sensor/collator_interface.h @@ -22,7 +22,7 @@ #include #include -#include "cartographer/common/optional.h" +#include "absl/types/optional.h" #include "cartographer/sensor/data.h" namespace cartographer { @@ -61,7 +61,7 @@ class CollatorInterface { // the ID of the trajectory that needs more data before CollatorInterface is // unblocked. Returns 'nullopt' for implementations that do not wait for a // particular trajectory. - virtual common::optional GetBlockingTrajectoryId() const = 0; + virtual absl::optional GetBlockingTrajectoryId() const = 0; }; } // namespace sensor diff --git a/cartographer/sensor/fixed_frame_pose_data.cc b/cartographer/sensor/fixed_frame_pose_data.cc index 7bceea3..352f7e9 100644 --- a/cartographer/sensor/fixed_frame_pose_data.cc +++ b/cartographer/sensor/fixed_frame_pose_data.cc @@ -16,7 +16,7 @@ #include "cartographer/sensor/fixed_frame_pose_data.h" -#include "cartographer/common/optional.h" +#include "absl/types/optional.h" #include "cartographer/transform/transform.h" namespace cartographer { @@ -34,9 +34,9 @@ proto::FixedFramePoseData ToProto(const FixedFramePoseData& pose_data) { FixedFramePoseData FromProto(const proto::FixedFramePoseData& proto) { return FixedFramePoseData{common::FromUniversal(proto.timestamp()), proto.has_pose() - ? common::optional( + ? absl::optional( transform::ToRigid3(proto.pose())) - : common::optional()}; + : absl::optional()}; } } // namespace sensor diff --git a/cartographer/sensor/fixed_frame_pose_data.h b/cartographer/sensor/fixed_frame_pose_data.h index 382bd60..1eabb58 100644 --- a/cartographer/sensor/fixed_frame_pose_data.h +++ b/cartographer/sensor/fixed_frame_pose_data.h @@ -19,7 +19,7 @@ #include -#include "cartographer/common/optional.h" +#include "absl/types/optional.h" #include "cartographer/common/time.h" #include "cartographer/sensor/proto/sensor.pb.h" #include "cartographer/transform/rigid_transform.h" @@ -31,7 +31,7 @@ namespace sensor { // optimization. struct FixedFramePoseData { common::Time time; - common::optional pose; + absl::optional pose; }; // Converts 'pose_data' to a proto::FixedFramePoseData. diff --git a/cartographer/sensor/internal/collator.cc b/cartographer/sensor/internal/collator.cc index f303ba5..7db3aa5 100644 --- a/cartographer/sensor/internal/collator.cc +++ b/cartographer/sensor/internal/collator.cc @@ -47,8 +47,8 @@ void Collator::AddSensorData(const int trajectory_id, void Collator::Flush() { queue_.Flush(); } -common::optional Collator::GetBlockingTrajectoryId() const { - return common::optional(queue_.GetBlocker().trajectory_id); +absl::optional Collator::GetBlockingTrajectoryId() const { + return absl::optional(queue_.GetBlocker().trajectory_id); } } // namespace sensor diff --git a/cartographer/sensor/internal/collator.h b/cartographer/sensor/internal/collator.h index 43b7114..38d2b0c 100644 --- a/cartographer/sensor/internal/collator.h +++ b/cartographer/sensor/internal/collator.h @@ -47,7 +47,7 @@ class Collator : public CollatorInterface { void Flush() override; - common::optional GetBlockingTrajectoryId() const override; + absl::optional GetBlockingTrajectoryId() const override; private: // Queue keys are a pair of trajectory ID and sensor identifier. diff --git a/cartographer/sensor/internal/trajectory_collator.cc b/cartographer/sensor/internal/trajectory_collator.cc index 5aec1ce..78204e7 100644 --- a/cartographer/sensor/internal/trajectory_collator.cc +++ b/cartographer/sensor/internal/trajectory_collator.cc @@ -53,8 +53,8 @@ void TrajectoryCollator::Flush() { } } -common::optional TrajectoryCollator::GetBlockingTrajectoryId() const { - return common::optional(); +absl::optional TrajectoryCollator::GetBlockingTrajectoryId() const { + return absl::optional(); } } // namespace sensor diff --git a/cartographer/sensor/internal/trajectory_collator.h b/cartographer/sensor/internal/trajectory_collator.h index 1ebfe33..6707acd 100644 --- a/cartographer/sensor/internal/trajectory_collator.h +++ b/cartographer/sensor/internal/trajectory_collator.h @@ -50,7 +50,7 @@ class TrajectoryCollator : public CollatorInterface { void Flush() override; - common::optional GetBlockingTrajectoryId() const override; + absl::optional GetBlockingTrajectoryId() const override; private: std::unordered_map trajectory_to_queue_; diff --git a/cmake/modules/FindAbseil.cmake b/cmake/modules/FindAbseil.cmake index d8af0bd..4dc3a79 100644 --- a/cmake/modules/FindAbseil.cmake +++ b/cmake/modules/FindAbseil.cmake @@ -54,11 +54,20 @@ if(NOT TARGET standalone_absl) "${ABSEIL_PROJECT_BUILD_DIR}/absl/types/libabsl_variant.a" "${ABSEIL_PROJECT_BUILD_DIR}/absl/utility/libabsl_utility.a" ) + + if(CMAKE_GENERATOR MATCHES "Ninja") + set (ABSL_BUILD_COMMAND "ninja") + else() + set (ABSL_BUILD_COMMAND "make") + endif() + ExternalProject_Add(${ABSEIL_PROJECT_NAME} PREFIX ${ABSEIL_PROJECT_NAME} GIT_REPOSITORY https://github.com/abseil/abseil-cpp.git GIT_TAG 44aa275286baf97fc13529aca547a88b180beb08 INSTALL_COMMAND "" + BUILD_ALWAYS TRUE + BUILD_COMMAND ${ABSEIL_BUILD_COMMAND} CMAKE_CACHE_ARGS "-DCMAKE_POSITION_INDEPENDENT_CODE:BOOL=ON;-DBUILD_TESTING:BOOL=OFF;-DCMAKE_BUILD_TYPE:STRING=Release" BUILD_BYPRODUCTS "${ABSEIL_LIBRARY_PATH};${ABSEIL_DEPENDENT_LIBRARIES}" )