From 5b44305ea30e6af0d1b1edb50e758881f3330c07 Mon Sep 17 00:00:00 2001 From: Alexander Belyaev <32522095+pifon2a@users.noreply.github.com> Date: Fri, 27 Jul 2018 19:43:35 +0200 Subject: [PATCH] [ABSL] Purge common::make_unique. (#1340) --- cartographer/BUILD.bazel | 1 + cartographer/cloud/client/map_builder_stub.cc | 2 +- .../client/trajectory_builder_stub.cc | 14 ++-- .../cloud/internal/client_server_test.cc | 24 +++---- .../add_fixed_frame_pose_data_handler.cc | 4 +- .../internal/handlers/add_imu_data_handler.cc | 4 +- .../handlers/add_landmark_data_handler.cc | 4 +- .../handlers/add_odometry_data_handler.cc | 4 +- .../handlers/add_rangefinder_data_handler.cc | 2 +- .../handlers/add_sensor_data_batch_handler.cc | 4 +- .../handlers/add_sensor_data_handler_base.h | 2 +- .../handlers/add_trajectory_handler.cc | 4 +- .../handlers/add_trajectory_handler_test.cc | 2 +- .../handlers/delete_trajectory_handler.cc | 4 +- .../handlers/finish_trajectory_handler.cc | 4 +- .../internal/handlers/get_all_submap_poses.cc | 4 +- .../handlers/get_constraints_handler.cc | 4 +- .../handlers/get_landmark_poses_handler.cc | 4 +- .../get_local_to_global_transform_handler.cc | 3 +- .../internal/handlers/get_submap_handler.cc | 4 +- .../get_trajectory_node_poses_handler.cc | 4 +- .../handlers/get_trajectory_states_handler.cc | 4 +- .../is_trajectory_finished_handler.cc | 4 +- .../handlers/is_trajectory_frozen_handler.cc | 4 +- .../handlers/load_state_from_file_handler.cc | 4 +- .../internal/handlers/load_state_handler.cc | 4 +- ...ceive_global_slam_optimizations_handler.cc | 4 +- .../receive_local_slam_results_handler.cc | 6 +- .../run_final_optimization_handler.cc | 4 +- .../handlers/set_landmark_pose_handler.cc | 2 +- .../internal/handlers/write_state_handler.cc | 2 +- .../internal/local_trajectory_uploader.cc | 4 +- .../internal/map_builder_context_impl.cc | 8 +-- .../cloud/internal/map_builder_context_impl.h | 2 +- .../cloud/internal/map_builder_server.cc | 12 ++-- .../cloud/internal/testing/handler_test.h | 12 ++-- .../cloud/map_builder_server_interface.cc | 6 +- cartographer/cloud/map_builder_server_main.cc | 2 +- .../cloud/map_builder_server_options.cc | 4 +- .../metrics/prometheus/family_factory.cc | 14 ++-- cartographer/common/blocking_queue_test.cc | 18 ++--- .../common/configuration_files_test.cc | 20 +++--- .../testing/thread_pool_for_testing.cc | 2 +- cartographer/common/lockless_queue.h | 2 +- cartographer/common/lockless_queue_test.cc | 10 +-- .../common/lua_parameter_dictionary_test.cc | 4 +- .../lua_parameter_dictionary_test_helpers.h | 6 +- cartographer/common/make_unique.h | 62 ----------------- cartographer/common/optional.h | 69 +++++++++++++++++++ cartographer/common/task_test.cc | 20 +++--- cartographer/common/thread_pool.cc | 2 +- cartographer/common/thread_pool_test.cc | 34 ++++----- cartographer/io/coloring_points_processor.cc | 6 +- cartographer/io/counting_points_processor.cc | 4 +- .../fixed_ratio_sampling_points_processor.cc | 9 ++- .../io/frame_id_filtering_points_processor.cc | 4 +- .../io/hybrid_grid_points_processor.cc | 4 +- .../io/intensity_to_color_points_processor.cc | 4 +- .../io/internal/in_memory_proto_stream.h | 4 +- .../internal/in_memory_proto_stream_test.cc | 2 +- ...in_max_range_filtering_points_processor.cc | 4 +- .../io/outlier_removing_points_processor.cc | 4 +- .../io/pcd_writing_points_processor.cc | 4 +- .../io/ply_writing_points_processor.cc | 4 +- .../io/points_processor_pipeline_builder.cc | 4 +- .../io/probability_grid_points_processor.cc | 8 +-- .../probability_grid_points_processor_test.cc | 13 ++-- .../io/proto_stream_deserializer_test.cc | 3 +- cartographer/io/testing/test_helpers.cc | 6 +- cartographer/io/xray_points_processor.cc | 4 +- .../io/xyz_writing_points_processor.cc | 4 +- cartographer/mapping/2d/probability_grid.cc | 4 +- .../mapping/2d/range_data_inserter_2d_test.cc | 4 +- cartographer/mapping/2d/submap_2d.cc | 14 ++-- cartographer/mapping/2d/submap_2d_test.cc | 4 +- cartographer/mapping/2d/tsdf_2d.cc | 8 +-- .../2d/tsdf_range_data_inserter_2d_test.cc | 15 ++-- cartographer/mapping/3d/hybrid_grid.h | 6 +- cartographer/mapping/3d/submap_3d.cc | 10 +-- cartographer/mapping/id.h | 4 +- cartographer/mapping/imu_tracker_test.cc | 4 +- .../internal/2d/local_slam_result_2d.cc | 2 +- .../2d/local_trajectory_builder_2d.cc | 12 ++-- .../mapping/internal/2d/pose_graph_2d.cc | 8 +-- .../mapping/internal/2d/pose_graph_2d_test.cc | 8 +-- .../ceres_scan_matcher_2d_test.cc | 4 +- .../fast_correlative_scan_matcher_2d.cc | 4 +- ...l_time_correlative_scan_matcher_2d_test.cc | 6 +- .../internal/3d/local_slam_result_3d.cc | 2 +- .../3d/local_trajectory_builder_3d.cc | 19 +++-- .../mapping/internal/3d/pose_graph_3d.cc | 8 +-- .../mapping/internal/3d/pose_graph_3d_test.cc | 17 ++--- .../3d/scan_matching/ceres_scan_matcher_3d.cc | 6 +- .../fast_correlative_scan_matcher_3d.cc | 6 +- .../fast_correlative_scan_matcher_3d_test.cc | 6 +- .../constraints/constraint_builder_2d.cc | 21 +++--- .../constraints/constraint_builder_2d_test.cc | 4 +- .../constraints/constraint_builder_3d.cc | 21 +++--- .../constraints/constraint_builder_3d_test.cc | 2 +- .../internal/global_trajectory_builder.cc | 8 +-- .../optimization/optimization_problem_2d.cc | 8 +-- .../optimization/optimization_problem_3d.cc | 24 +++---- .../mapping/internal/range_data_collator.cc | 2 +- .../mapping/internal/range_data_collator.h | 2 +- .../mapping/internal/testing/test_helpers.cc | 14 ++-- cartographer/mapping/map_builder.cc | 54 +++++++-------- cartographer/mapping/map_builder_test.cc | 2 +- cartographer/mapping/pose_extrapolator.cc | 12 ++-- .../mapping/pose_extrapolator_test.cc | 2 +- cartographer/mapping/probability_values.cc | 4 +- .../mapping/trajectory_builder_interface.h | 2 +- .../mapping/value_conversion_tables.cc | 4 +- .../constraint/acceleration_constraint_3d.cc | 4 +- .../relative_pose_cost_2d_test.cc | 4 +- ...nterpolated_relative_pose_constraint_2d.cc | 4 +- ...nterpolated_relative_pose_constraint_3d.cc | 4 +- .../constraint/loss_function/loss_function.cc | 4 +- .../constraint/relative_pose_constraint_2d.cc | 5 +- .../constraint/relative_pose_constraint_3d.cc | 4 +- .../constraint/rotation_constraint_3d.cc | 4 +- .../optimizer/ceres_optimizer_test.cc | 4 +- cartographer/sensor/data.h | 2 +- cartographer/sensor/internal/collator_test.cc | 2 +- cartographer/sensor/internal/dispatchable.h | 2 +- .../sensor/internal/ordered_multi_queue.cc | 2 +- .../internal/ordered_multi_queue_test.cc | 2 +- cartographer/sensor/internal/test_helpers.h | 2 +- .../internal/trajectory_collator_test.cc | 2 +- 128 files changed, 480 insertions(+), 486 deletions(-) delete mode 100644 cartographer/common/make_unique.h create mode 100644 cartographer/common/optional.h diff --git a/cartographer/BUILD.bazel b/cartographer/BUILD.bazel index 6ff5cce..69cb934 100644 --- a/cartographer/BUILD.bazel +++ b/cartographer/BUILD.bazel @@ -112,6 +112,7 @@ cc_library( ":cartographer", ":cartographer_test_library", "@com_google_googletest//:gtest_main", + "@com_google_absl//absl/memory", ], ) for src in glob( ["**/*_test.cc"], diff --git a/cartographer/cloud/client/map_builder_stub.cc b/cartographer/cloud/client/map_builder_stub.cc index e99521e..841eab5 100644 --- a/cartographer/cloud/client/map_builder_stub.cc +++ b/cartographer/cloud/client/map_builder_stub.cc @@ -34,7 +34,7 @@ namespace cartographer { namespace cloud { namespace { -using common::make_unique; +using absl::make_unique; constexpr int kConnectionTimeoutInSeconds = 10; } // namespace diff --git a/cartographer/cloud/internal/client/trajectory_builder_stub.cc b/cartographer/cloud/internal/client/trajectory_builder_stub.cc index 4c81ae9..104d92c 100644 --- a/cartographer/cloud/internal/client/trajectory_builder_stub.cc +++ b/cartographer/cloud/internal/client/trajectory_builder_stub.cc @@ -39,7 +39,7 @@ TrajectoryBuilderStub::TrajectoryBuilderStub( receive_local_slam_results_client_.Write(request); auto* receive_local_slam_results_client_ptr = &receive_local_slam_results_client_; - receive_local_slam_results_thread_ = common::make_unique( + receive_local_slam_results_thread_ = absl::make_unique( [receive_local_slam_results_client_ptr, local_slam_result_callback]() { RunLocalSlamResultsReader(receive_local_slam_results_client_ptr, local_slam_result_callback); @@ -77,7 +77,7 @@ void TrajectoryBuilderStub::AddSensorData( const std::string& sensor_id, const sensor::TimedPointCloudData& timed_point_cloud_data) { if (!add_rangefinder_client_) { - add_rangefinder_client_ = common::make_unique< + add_rangefinder_client_ = absl::make_unique< async_grpc::Client>( client_channel_); } @@ -92,7 +92,7 @@ void TrajectoryBuilderStub::AddSensorData(const std::string& sensor_id, const sensor::ImuData& imu_data) { if (!add_imu_client_) { add_imu_client_ = - common::make_unique>( + absl::make_unique>( client_channel_); } proto::AddImuDataRequest request; @@ -104,7 +104,7 @@ void TrajectoryBuilderStub::AddSensorData(const std::string& sensor_id, void TrajectoryBuilderStub::AddSensorData( const std::string& sensor_id, const sensor::OdometryData& odometry_data) { if (!add_odometry_client_) { - add_odometry_client_ = common::make_unique< + add_odometry_client_ = absl::make_unique< async_grpc::Client>( client_channel_); } @@ -118,7 +118,7 @@ void TrajectoryBuilderStub::AddSensorData( const std::string& sensor_id, const sensor::FixedFramePoseData& fixed_frame_pose) { if (!add_fixed_frame_pose_client_) { - add_fixed_frame_pose_client_ = common::make_unique< + add_fixed_frame_pose_client_ = absl::make_unique< async_grpc::Client>( client_channel_); } @@ -132,7 +132,7 @@ void TrajectoryBuilderStub::AddSensorData( void TrajectoryBuilderStub::AddSensorData( const std::string& sensor_id, const sensor::LandmarkData& landmark_data) { if (!add_landmark_client_) { - add_landmark_client_ = common::make_unique< + add_landmark_client_ = absl::make_unique< async_grpc::Client>( client_channel_); } @@ -158,7 +158,7 @@ void TrajectoryBuilderStub::RunLocalSlamResultsReader( sensor::RangeData range_data = sensor::FromProto(response.range_data()); auto insertion_result = response.has_insertion_result() - ? common::make_unique( + ? absl::make_unique( InsertionResult{mapping::NodeId{ response.insertion_result().node_id().trajectory_id(), response.insertion_result().node_id().node_index()}}) diff --git a/cartographer/cloud/internal/client_server_test.cc b/cartographer/cloud/internal/client_server_test.cc index 3592b5a..bc7d85e 100644 --- a/cartographer/cloud/internal/client_server_test.cc +++ b/cartographer/cloud/internal/client_server_test.cc @@ -138,42 +138,42 @@ class ClientServerTest : public ::testing::Test { } void InitializeRealServer() { - auto map_builder = common::make_unique( + auto map_builder = absl::make_unique( map_builder_server_options_.map_builder_options()); - server_ = common::make_unique(map_builder_server_options_, - std::move(map_builder)); + server_ = absl::make_unique(map_builder_server_options_, + std::move(map_builder)); EXPECT_TRUE(server_ != nullptr); } void InitializeRealUploadingServer() { - auto map_builder = common::make_unique( + auto map_builder = absl::make_unique( uploading_map_builder_server_options_.map_builder_options()); - uploading_server_ = common::make_unique( + uploading_server_ = absl::make_unique( uploading_map_builder_server_options_, std::move(map_builder)); EXPECT_TRUE(uploading_server_ != nullptr); } void InitializeServerWithMockMapBuilder() { - auto mock_map_builder = common::make_unique(); + auto mock_map_builder = absl::make_unique(); mock_map_builder_ = mock_map_builder.get(); - mock_pose_graph_ = common::make_unique(); + mock_pose_graph_ = absl::make_unique(); EXPECT_CALL(*mock_map_builder_, pose_graph()) .WillOnce(::testing::Return(mock_pose_graph_.get())); EXPECT_CALL(*mock_pose_graph_, SetGlobalSlamOptimizationCallback(_)); - server_ = common::make_unique( - map_builder_server_options_, std::move(mock_map_builder)); + server_ = absl::make_unique(map_builder_server_options_, + std::move(mock_map_builder)); EXPECT_TRUE(server_ != nullptr); - mock_trajectory_builder_ = common::make_unique(); + mock_trajectory_builder_ = absl::make_unique(); } void InitializeStub() { - stub_ = common::make_unique( + stub_ = absl::make_unique( map_builder_server_options_.server_address(), kClientId); EXPECT_TRUE(stub_ != nullptr); } void InitializeStubForUploadingServer() { - stub_for_uploading_server_ = common::make_unique( + stub_for_uploading_server_ = absl::make_unique( uploading_map_builder_server_options_.server_address(), kClientId); EXPECT_TRUE(stub_for_uploading_server_ != nullptr); } diff --git a/cartographer/cloud/internal/handlers/add_fixed_frame_pose_data_handler.cc b/cartographer/cloud/internal/handlers/add_fixed_frame_pose_data_handler.cc index 1508f32..b705300 100644 --- a/cartographer/cloud/internal/handlers/add_fixed_frame_pose_data_handler.cc +++ b/cartographer/cloud/internal/handlers/add_fixed_frame_pose_data_handler.cc @@ -16,11 +16,11 @@ #include "cartographer/cloud/internal/handlers/add_fixed_frame_pose_data_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/internal/sensor/serialization.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "cartographer/sensor/fixed_frame_pose_data.h" #include "cartographer/sensor/internal/dispatchable.h" #include "google/protobuf/empty.pb.h" @@ -45,7 +45,7 @@ void AddFixedFramePoseDataHandler::OnSensorData( // 'MapBuilderContext'. if (GetUnsynchronizedContext() ->local_trajectory_uploader()) { - auto sensor_data = common::make_unique(); + auto sensor_data = absl::make_unique(); *sensor_data->mutable_sensor_metadata() = request.sensor_metadata(); *sensor_data->mutable_fixed_frame_pose_data() = request.fixed_frame_pose_data(); diff --git a/cartographer/cloud/internal/handlers/add_imu_data_handler.cc b/cartographer/cloud/internal/handlers/add_imu_data_handler.cc index 29b709e..99e51d1 100644 --- a/cartographer/cloud/internal/handlers/add_imu_data_handler.cc +++ b/cartographer/cloud/internal/handlers/add_imu_data_handler.cc @@ -16,11 +16,11 @@ #include "cartographer/cloud/internal/handlers/add_imu_data_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/internal/sensor/serialization.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "cartographer/sensor/imu_data.h" #include "cartographer/sensor/internal/dispatchable.h" #include "google/protobuf/empty.pb.h" @@ -43,7 +43,7 @@ void AddImuDataHandler::OnSensorData(const proto::AddImuDataRequest& request) { // 'MapBuilderContext'. if (GetUnsynchronizedContext() ->local_trajectory_uploader()) { - auto sensor_data = common::make_unique(); + auto sensor_data = absl::make_unique(); *sensor_data->mutable_sensor_metadata() = request.sensor_metadata(); *sensor_data->mutable_imu_data() = request.imu_data(); GetUnsynchronizedContext() diff --git a/cartographer/cloud/internal/handlers/add_landmark_data_handler.cc b/cartographer/cloud/internal/handlers/add_landmark_data_handler.cc index 2dfbbc1..a820002 100644 --- a/cartographer/cloud/internal/handlers/add_landmark_data_handler.cc +++ b/cartographer/cloud/internal/handlers/add_landmark_data_handler.cc @@ -16,11 +16,11 @@ #include "cartographer/cloud/internal/handlers/add_landmark_data_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/internal/sensor/serialization.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "cartographer/sensor/internal/dispatchable.h" #include "cartographer/sensor/landmark_data.h" #include "google/protobuf/empty.pb.h" @@ -44,7 +44,7 @@ void AddLandmarkDataHandler::OnSensorData( // 'MapBuilderContext'. if (GetUnsynchronizedContext() ->local_trajectory_uploader()) { - auto sensor_data = common::make_unique(); + auto sensor_data = absl::make_unique(); *sensor_data->mutable_sensor_metadata() = request.sensor_metadata(); *sensor_data->mutable_landmark_data() = request.landmark_data(); GetUnsynchronizedContext() diff --git a/cartographer/cloud/internal/handlers/add_odometry_data_handler.cc b/cartographer/cloud/internal/handlers/add_odometry_data_handler.cc index 7793839..0cc1670 100644 --- a/cartographer/cloud/internal/handlers/add_odometry_data_handler.cc +++ b/cartographer/cloud/internal/handlers/add_odometry_data_handler.cc @@ -16,11 +16,11 @@ #include "cartographer/cloud/internal/handlers/add_odometry_data_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/internal/sensor/serialization.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "cartographer/sensor/internal/dispatchable.h" #include "cartographer/sensor/odometry_data.h" #include "google/protobuf/empty.pb.h" @@ -44,7 +44,7 @@ void AddOdometryDataHandler::OnSensorData( // 'MapBuilderContext'. if (GetUnsynchronizedContext() ->local_trajectory_uploader()) { - auto sensor_data = common::make_unique(); + auto sensor_data = absl::make_unique(); *sensor_data->mutable_sensor_metadata() = request.sensor_metadata(); *sensor_data->mutable_odometry_data() = request.odometry_data(); GetUnsynchronizedContext() diff --git a/cartographer/cloud/internal/handlers/add_rangefinder_data_handler.cc b/cartographer/cloud/internal/handlers/add_rangefinder_data_handler.cc index 6b3f992..4ef584b 100644 --- a/cartographer/cloud/internal/handlers/add_rangefinder_data_handler.cc +++ b/cartographer/cloud/internal/handlers/add_rangefinder_data_handler.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/add_rangefinder_data_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "cartographer/sensor/internal/dispatchable.h" #include "cartographer/sensor/timed_point_cloud_data.h" #include "google/protobuf/empty.pb.h" diff --git a/cartographer/cloud/internal/handlers/add_sensor_data_batch_handler.cc b/cartographer/cloud/internal/handlers/add_sensor_data_batch_handler.cc index 94de5e5..a88578e 100644 --- a/cartographer/cloud/internal/handlers/add_sensor_data_batch_handler.cc +++ b/cartographer/cloud/internal/handlers/add_sensor_data_batch_handler.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/add_sensor_data_batch_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "cartographer/mapping/local_slam_result_data.h" #include "cartographer/sensor/internal/dispatchable.h" #include "cartographer/sensor/timed_point_cloud_data.h" @@ -93,7 +93,7 @@ void AddSensorDataBatchHandler::OnRequest( << sensor_data.sensor_data_case(); } } - Send(common::make_unique()); + Send(absl::make_unique()); } } // namespace handlers diff --git a/cartographer/cloud/internal/handlers/add_sensor_data_handler_base.h b/cartographer/cloud/internal/handlers/add_sensor_data_handler_base.h index 20dc75d..2c0afba 100644 --- a/cartographer/cloud/internal/handlers/add_sensor_data_handler_base.h +++ b/cartographer/cloud/internal/handlers/add_sensor_data_handler_base.h @@ -50,7 +50,7 @@ class AddSensorDataHandlerBase virtual void OnSensorData(const SensorDataType& request) = 0; void OnReadsDone() override { - this->template Send(common::make_unique()); + this->template Send(absl::make_unique()); } }; diff --git a/cartographer/cloud/internal/handlers/add_trajectory_handler.cc b/cartographer/cloud/internal/handlers/add_trajectory_handler.cc index af072af..b0b9e04 100644 --- a/cartographer/cloud/internal/handlers/add_trajectory_handler.cc +++ b/cartographer/cloud/internal/handlers/add_trajectory_handler.cc @@ -16,11 +16,11 @@ #include "cartographer/cloud/internal/handlers/add_trajectory_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/internal/sensor/serialization.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" namespace cartographer { namespace cloud { @@ -71,7 +71,7 @@ void AddTrajectoryHandler::OnRequest( } } - auto response = common::make_unique(); + auto response = absl::make_unique(); response->set_trajectory_id(trajectory_id); Send(std::move(response)); } diff --git a/cartographer/cloud/internal/handlers/add_trajectory_handler_test.cc b/cartographer/cloud/internal/handlers/add_trajectory_handler_test.cc index c6d785e..4612e49 100644 --- a/cartographer/cloud/internal/handlers/add_trajectory_handler_test.cc +++ b/cartographer/cloud/internal/handlers/add_trajectory_handler_test.cc @@ -74,7 +74,7 @@ class AddTrajectoryHandlerTest public: void SetUp() override { testing::HandlerTest::SetUp(); - mock_map_builder_ = common::make_unique(); + mock_map_builder_ = absl::make_unique(); EXPECT_CALL(*mock_map_builder_context_, GetLocalSlamResultCallbackForSubscriptions()) .WillOnce(Return(nullptr)); diff --git a/cartographer/cloud/internal/handlers/delete_trajectory_handler.cc b/cartographer/cloud/internal/handlers/delete_trajectory_handler.cc index fb6ff51..84f6e53 100644 --- a/cartographer/cloud/internal/handlers/delete_trajectory_handler.cc +++ b/cartographer/cloud/internal/handlers/delete_trajectory_handler.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/delete_trajectory_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "google/protobuf/empty.pb.h" namespace cartographer { @@ -40,7 +40,7 @@ void DeleteTrajectoryHandler::OnRequest( .pose_graph() ->DeleteTrajectory(request.trajectory_id()); // TODO(gaschler): Think if LocalSlamUploader needs to be notified. - Send(common::make_unique()); + Send(absl::make_unique()); } } // namespace handlers diff --git a/cartographer/cloud/internal/handlers/finish_trajectory_handler.cc b/cartographer/cloud/internal/handlers/finish_trajectory_handler.cc index fab7cb7..d6b881d 100644 --- a/cartographer/cloud/internal/handlers/finish_trajectory_handler.cc +++ b/cartographer/cloud/internal/handlers/finish_trajectory_handler.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/finish_trajectory_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "google/protobuf/empty.pb.h" namespace cartographer { @@ -45,7 +45,7 @@ void FinishTrajectoryHandler::OnRequest( ->local_trajectory_uploader() ->FinishTrajectory(request.client_id(), request.trajectory_id()); } - Send(common::make_unique()); + Send(absl::make_unique()); } } // namespace handlers diff --git a/cartographer/cloud/internal/handlers/get_all_submap_poses.cc b/cartographer/cloud/internal/handlers/get_all_submap_poses.cc index 7847f69..0f101b2 100644 --- a/cartographer/cloud/internal/handlers/get_all_submap_poses.cc +++ b/cartographer/cloud/internal/handlers/get_all_submap_poses.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/get_all_submap_poses.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "cartographer/transform/transform.h" #include "google/protobuf/empty.pb.h" @@ -33,7 +33,7 @@ void GetAllSubmapPosesHandler::OnRequest( ->map_builder() .pose_graph() ->GetAllSubmapPoses(); - auto response = common::make_unique(); + auto response = absl::make_unique(); for (const auto& submap_id_pose : submap_poses) { auto* submap_pose = response->add_submap_poses(); submap_id_pose.id.ToProto(submap_pose->mutable_submap_id()); diff --git a/cartographer/cloud/internal/handlers/get_constraints_handler.cc b/cartographer/cloud/internal/handlers/get_constraints_handler.cc index 12ef849..126217f 100644 --- a/cartographer/cloud/internal/handlers/get_constraints_handler.cc +++ b/cartographer/cloud/internal/handlers/get_constraints_handler.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/get_constraints_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "cartographer/mapping/pose_graph.h" #include "google/protobuf/empty.pb.h" @@ -32,7 +32,7 @@ void GetConstraintsHandler::OnRequest(const google::protobuf::Empty& request) { ->map_builder() .pose_graph() ->constraints(); - auto response = common::make_unique(); + auto response = absl::make_unique(); response->mutable_constraints()->Reserve(constraints.size()); for (const auto& constraint : constraints) { *response->add_constraints() = mapping::ToProto(constraint); diff --git a/cartographer/cloud/internal/handlers/get_landmark_poses_handler.cc b/cartographer/cloud/internal/handlers/get_landmark_poses_handler.cc index 24731f4..a60ce71 100644 --- a/cartographer/cloud/internal/handlers/get_landmark_poses_handler.cc +++ b/cartographer/cloud/internal/handlers/get_landmark_poses_handler.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/get_landmark_poses_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "cartographer/transform/transform.h" #include "google/protobuf/empty.pb.h" @@ -33,7 +33,7 @@ void GetLandmarkPosesHandler::OnRequest( ->map_builder() .pose_graph() ->GetLandmarkPoses(); - auto response = common::make_unique(); + auto response = absl::make_unique(); for (const auto& landmark_pose : landmark_poses) { auto* landmark = response->add_landmark_poses(); landmark->set_landmark_id(landmark_pose.first); diff --git a/cartographer/cloud/internal/handlers/get_local_to_global_transform_handler.cc b/cartographer/cloud/internal/handlers/get_local_to_global_transform_handler.cc index 7fc0095..4b62e4e 100644 --- a/cartographer/cloud/internal/handlers/get_local_to_global_transform_handler.cc +++ b/cartographer/cloud/internal/handlers/get_local_to_global_transform_handler.cc @@ -28,8 +28,7 @@ namespace handlers { void GetLocalToGlobalTransformHandler::OnRequest( const proto::GetLocalToGlobalTransformRequest& request) { - auto response = - common::make_unique(); + auto response = absl::make_unique(); auto local_to_global = GetContext() ->map_builder() diff --git a/cartographer/cloud/internal/handlers/get_submap_handler.cc b/cartographer/cloud/internal/handlers/get_submap_handler.cc index 13bf8b7..554d932 100644 --- a/cartographer/cloud/internal/handlers/get_submap_handler.cc +++ b/cartographer/cloud/internal/handlers/get_submap_handler.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/get_submap_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "google/protobuf/empty.pb.h" namespace cartographer { @@ -27,7 +27,7 @@ namespace cloud { namespace handlers { void GetSubmapHandler::OnRequest(const proto::GetSubmapRequest &request) { - auto response = common::make_unique(); + auto response = absl::make_unique(); response->set_error_msg( GetContext()->map_builder().SubmapToProto( mapping::SubmapId{request.submap_id().trajectory_id(), diff --git a/cartographer/cloud/internal/handlers/get_trajectory_node_poses_handler.cc b/cartographer/cloud/internal/handlers/get_trajectory_node_poses_handler.cc index 8880fec..5c4da10 100644 --- a/cartographer/cloud/internal/handlers/get_trajectory_node_poses_handler.cc +++ b/cartographer/cloud/internal/handlers/get_trajectory_node_poses_handler.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/get_trajectory_node_poses_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "cartographer/transform/transform.h" #include "google/protobuf/empty.pb.h" @@ -33,7 +33,7 @@ void GetTrajectoryNodePosesHandler::OnRequest( ->map_builder() .pose_graph() ->GetTrajectoryNodePoses(); - auto response = common::make_unique(); + auto response = absl::make_unique(); for (const auto& node_id_pose : node_poses) { auto* node_pose = response->add_node_poses(); node_id_pose.id.ToProto(node_pose->mutable_node_id()); diff --git a/cartographer/cloud/internal/handlers/get_trajectory_states_handler.cc b/cartographer/cloud/internal/handlers/get_trajectory_states_handler.cc index 8b29388..7f303c1 100644 --- a/cartographer/cloud/internal/handlers/get_trajectory_states_handler.cc +++ b/cartographer/cloud/internal/handlers/get_trajectory_states_handler.cc @@ -16,11 +16,11 @@ #include "cartographer/cloud/internal/handlers/get_trajectory_states_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/internal/mapping/serialization.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "google/protobuf/empty.pb.h" namespace cartographer { @@ -33,7 +33,7 @@ void GetTrajectoryStatesHandler::OnRequest( ->map_builder() .pose_graph() ->GetTrajectoryStates(); - auto response = common::make_unique(); + auto response = absl::make_unique(); for (const auto& entry : trajectories_state) { (*response->mutable_trajectories_state())[entry.first] = ToProto(entry.second); diff --git a/cartographer/cloud/internal/handlers/is_trajectory_finished_handler.cc b/cartographer/cloud/internal/handlers/is_trajectory_finished_handler.cc index 8537b9b..8278ee5 100644 --- a/cartographer/cloud/internal/handlers/is_trajectory_finished_handler.cc +++ b/cartographer/cloud/internal/handlers/is_trajectory_finished_handler.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/is_trajectory_finished_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" namespace cartographer { namespace cloud { @@ -27,7 +27,7 @@ namespace handlers { void IsTrajectoryFinishedHandler::OnRequest( const proto::IsTrajectoryFinishedRequest& request) { - auto response = common::make_unique(); + auto response = absl::make_unique(); response->set_is_finished( GetContext() ->map_builder() diff --git a/cartographer/cloud/internal/handlers/is_trajectory_frozen_handler.cc b/cartographer/cloud/internal/handlers/is_trajectory_frozen_handler.cc index ede3175..4d22425 100644 --- a/cartographer/cloud/internal/handlers/is_trajectory_frozen_handler.cc +++ b/cartographer/cloud/internal/handlers/is_trajectory_frozen_handler.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/is_trajectory_frozen_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" namespace cartographer { namespace cloud { @@ -27,7 +27,7 @@ namespace handlers { void IsTrajectoryFrozenHandler::OnRequest( const proto::IsTrajectoryFrozenRequest& request) { - auto response = common::make_unique(); + auto response = absl::make_unique(); response->set_is_frozen(GetContext() ->map_builder() .pose_graph() diff --git a/cartographer/cloud/internal/handlers/load_state_from_file_handler.cc b/cartographer/cloud/internal/handlers/load_state_from_file_handler.cc index 863ceed..f0c81d5 100644 --- a/cartographer/cloud/internal/handlers/load_state_from_file_handler.cc +++ b/cartographer/cloud/internal/handlers/load_state_from_file_handler.cc @@ -16,11 +16,11 @@ #include "cartographer/cloud/internal/handlers/load_state_from_file_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/internal/mapping/serialization.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" namespace cartographer { namespace cloud { @@ -37,7 +37,7 @@ void LoadStateFromFileHandler::OnRequest( GetContext()->RegisterClientIdForTrajectory( request.client_id(), entry.second); } - auto response = common::make_unique(); + auto response = absl::make_unique(); *response->mutable_trajectory_remapping() = ToProto(trajectory_remapping); Send(std::move(response)); } diff --git a/cartographer/cloud/internal/handlers/load_state_handler.cc b/cartographer/cloud/internal/handlers/load_state_handler.cc index 9b925fe..562856b 100644 --- a/cartographer/cloud/internal/handlers/load_state_handler.cc +++ b/cartographer/cloud/internal/handlers/load_state_handler.cc @@ -16,11 +16,11 @@ #include "cartographer/cloud/internal/handlers/load_state_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/internal/mapping/serialization.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" namespace cartographer { namespace cloud { @@ -50,7 +50,7 @@ void LoadStateHandler::OnReadsDone() { GetContext()->RegisterClientIdForTrajectory( client_id_, entry.second); } - auto response = common::make_unique(); + auto response = absl::make_unique(); *response->mutable_trajectory_remapping() = ToProto(trajectory_remapping); Send(std::move(response)); } diff --git a/cartographer/cloud/internal/handlers/receive_global_slam_optimizations_handler.cc b/cartographer/cloud/internal/handlers/receive_global_slam_optimizations_handler.cc index 5c902b7..acf8199 100644 --- a/cartographer/cloud/internal/handlers/receive_global_slam_optimizations_handler.cc +++ b/cartographer/cloud/internal/handlers/receive_global_slam_optimizations_handler.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/receive_global_slam_optimizations_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "cartographer/transform/transform.h" namespace cartographer { @@ -31,7 +31,7 @@ std::unique_ptr GenerateResponse( const std::map &last_optimized_submap_ids, const std::map &last_optimized_node_ids) { auto response = - common::make_unique(); + absl::make_unique(); for (const auto &entry : last_optimized_submap_ids) { entry.second.ToProto( &(*response->mutable_last_optimized_submap_ids())[entry.first]); diff --git a/cartographer/cloud/internal/handlers/receive_local_slam_results_handler.cc b/cartographer/cloud/internal/handlers/receive_local_slam_results_handler.cc index 94956f7..af6b7cb 100644 --- a/cartographer/cloud/internal/handlers/receive_local_slam_results_handler.cc +++ b/cartographer/cloud/internal/handlers/receive_local_slam_results_handler.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/receive_local_slam_results_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "cartographer/transform/transform.h" namespace cartographer { @@ -30,7 +30,7 @@ namespace { std::unique_ptr GenerateResponse( std::unique_ptr local_slam_result) { - auto response = common::make_unique(); + auto response = absl::make_unique(); response->set_trajectory_id(local_slam_result->trajectory_id); response->set_timestamp(common::ToUniversal(local_slam_result->time)); *response->mutable_local_pose() = @@ -74,7 +74,7 @@ void ReceiveLocalSlamResultsHandler::OnRequest( }); subscription_id_ = - common::make_unique( + absl::make_unique( subscription_id); } diff --git a/cartographer/cloud/internal/handlers/run_final_optimization_handler.cc b/cartographer/cloud/internal/handlers/run_final_optimization_handler.cc index 472b09b..ac5b0dc 100644 --- a/cartographer/cloud/internal/handlers/run_final_optimization_handler.cc +++ b/cartographer/cloud/internal/handlers/run_final_optimization_handler.cc @@ -16,10 +16,10 @@ #include "cartographer/cloud/internal/handlers/run_final_optimization_handler.h" +#include "absl/memory/memory.h" #include "async_grpc/rpc_handler.h" #include "cartographer/cloud/internal/map_builder_context_interface.h" #include "cartographer/cloud/proto/map_builder_service.pb.h" -#include "cartographer/common/make_unique.h" #include "cartographer/mapping/map_builder_interface.h" #include "cartographer/mapping/pose_graph.h" #include "google/protobuf/empty.pb.h" @@ -34,7 +34,7 @@ void RunFinalOptimizationHandler::OnRequest( ->map_builder() .pose_graph() ->RunFinalOptimization(); - Send(common::make_unique()); + Send(absl::make_unique()); } } // namespace handlers diff --git a/cartographer/cloud/internal/handlers/set_landmark_pose_handler.cc b/cartographer/cloud/internal/handlers/set_landmark_pose_handler.cc index ad457d3..b012c04 100644 --- a/cartographer/cloud/internal/handlers/set_landmark_pose_handler.cc +++ b/cartographer/cloud/internal/handlers/set_landmark_pose_handler.cc @@ -34,7 +34,7 @@ void SetLandmarkPoseHandler::OnRequest( ->SetLandmarkPose( request.landmark_pose().landmark_id(), transform::ToRigid3(request.landmark_pose().global_pose())); - Send(common::make_unique()); + Send(absl::make_unique()); } } // namespace handlers diff --git a/cartographer/cloud/internal/handlers/write_state_handler.cc b/cartographer/cloud/internal/handlers/write_state_handler.cc index 1b480ff..379723c 100644 --- a/cartographer/cloud/internal/handlers/write_state_handler.cc +++ b/cartographer/cloud/internal/handlers/write_state_handler.cc @@ -35,7 +35,7 @@ void WriteStateHandler::OnRequest(const google::protobuf::Empty& request) { return true; } - auto response = common::make_unique(); + auto response = absl::make_unique(); if (proto->GetTypeName() == "cartographer.mapping.proto.SerializationHeader") { response->mutable_header()->CopyFrom(*proto); diff --git a/cartographer/cloud/internal/local_trajectory_uploader.cc b/cartographer/cloud/internal/local_trajectory_uploader.cc index 7fbec27..5608d1e 100644 --- a/cartographer/cloud/internal/local_trajectory_uploader.cc +++ b/cartographer/cloud/internal/local_trajectory_uploader.cc @@ -19,6 +19,7 @@ #include #include +#include "absl/memory/memory.h" #include "async_grpc/client.h" #include "async_grpc/token_file_credentials.h" #include "cartographer/cloud/internal/handlers/add_sensor_data_batch_handler.h" @@ -26,7 +27,6 @@ #include "cartographer/cloud/internal/handlers/finish_trajectory_handler.h" #include "cartographer/cloud/internal/sensor/serialization.h" #include "cartographer/common/blocking_queue.h" -#include "cartographer/common/make_unique.h" #include "glog/logging.h" #include "grpc++/grpc++.h" @@ -34,7 +34,7 @@ namespace cartographer { namespace cloud { namespace { -using common::make_unique; +using absl::make_unique; constexpr int kConnectionTimeoutInSeconds = 10; constexpr int kTokenRefreshIntervalInSeconds = 60; diff --git a/cartographer/cloud/internal/map_builder_context_impl.cc b/cartographer/cloud/internal/map_builder_context_impl.cc index 54fc4cb..4606046 100644 --- a/cartographer/cloud/internal/map_builder_context_impl.cc +++ b/cartographer/cloud/internal/map_builder_context_impl.cc @@ -27,9 +27,9 @@ template <> void MapBuilderContext::EnqueueLocalSlamResultData( int trajectory_id, const std::string& sensor_id, const mapping::proto::LocalSlamResultData& local_slam_result_data) { - map_builder_server_->incoming_data_queue_.Push(common::make_unique( + map_builder_server_->incoming_data_queue_.Push(absl::make_unique( Data{trajectory_id, - common::make_unique( + absl::make_unique( sensor_id, local_slam_result_data, &submap_controller_)})); } @@ -37,9 +37,9 @@ template <> void MapBuilderContext::EnqueueLocalSlamResultData( int trajectory_id, const std::string& sensor_id, const mapping::proto::LocalSlamResultData& local_slam_result_data) { - map_builder_server_->incoming_data_queue_.Push(common::make_unique( + map_builder_server_->incoming_data_queue_.Push(absl::make_unique( Data{trajectory_id, - common::make_unique( + absl::make_unique( sensor_id, local_slam_result_data, &submap_controller_)})); } diff --git a/cartographer/cloud/internal/map_builder_context_impl.h b/cartographer/cloud/internal/map_builder_context_impl.h index d3f1a9b..186e1e7 100644 --- a/cartographer/cloud/internal/map_builder_context_impl.h +++ b/cartographer/cloud/internal/map_builder_context_impl.h @@ -104,7 +104,7 @@ template void MapBuilderContext::EnqueueSensorData( int trajectory_id, std::unique_ptr data) { map_builder_server_->incoming_data_queue_.Push( - common::make_unique(Data{trajectory_id, std::move(data)})); + absl::make_unique(Data{trajectory_id, std::move(data)})); } template diff --git a/cartographer/cloud/internal/map_builder_server.cc b/cartographer/cloud/internal/map_builder_server.cc index f0a04f4..8d592f3 100644 --- a/cartographer/cloud/internal/map_builder_server.cc +++ b/cartographer/cloud/internal/map_builder_server.cc @@ -100,11 +100,11 @@ MapBuilderServer::MapBuilderServer( if (map_builder_server_options.map_builder_options() .use_trajectory_builder_2d()) { grpc_server_->SetExecutionContext( - common::make_unique>(this)); + absl::make_unique>(this)); } else if (map_builder_server_options.map_builder_options() .use_trajectory_builder_3d()) { grpc_server_->SetExecutionContext( - common::make_unique>(this)); + absl::make_unique>(this)); } else { LOG(FATAL) << "Set either use_trajectory_builder_2d or use_trajectory_builder_3d"; @@ -166,7 +166,7 @@ void MapBuilderServer::StartSlamThread() { CHECK(!slam_thread_); // Start the SLAM processing thread. - slam_thread_ = common::make_unique( + slam_thread_ = absl::make_unique( [this]() { this->ProcessSensorDataQueue(); }); } @@ -183,7 +183,7 @@ void MapBuilderServer::OnLocalSlamResult( if (insertion_result && grpc_server_->GetUnsynchronizedContext() ->local_trajectory_uploader()) { - auto sensor_data = common::make_unique(); + auto sensor_data = absl::make_unique(); auto sensor_id = grpc_server_->GetUnsynchronizedContext() ->local_trajectory_uploader() @@ -204,14 +204,14 @@ void MapBuilderServer::OnLocalSlamResult( for (auto& entry : local_slam_subscriptions_[trajectory_id]) { auto copy_of_insertion_result = insertion_result - ? common::make_unique< + ? absl::make_unique< const mapping::TrajectoryBuilderInterface::InsertionResult>( *insertion_result) : nullptr; MapBuilderContextInterface::LocalSlamSubscriptionCallback callback = entry.second; if (!callback( - common::make_unique( + absl::make_unique( MapBuilderContextInterface::LocalSlamResult{ trajectory_id, time, local_pose, shared_range_data, std::move(copy_of_insertion_result)}))) { diff --git a/cartographer/cloud/internal/testing/handler_test.h b/cartographer/cloud/internal/testing/handler_test.h index 96c525f..189a70d 100644 --- a/cartographer/cloud/internal/testing/handler_test.h +++ b/cartographer/cloud/internal/testing/handler_test.h @@ -17,8 +17,8 @@ #ifndef CARTOGRAPHER_CLOUD_INTERNAL_TESTING_HANDLER_TEST_H #define CARTOGRAPHER_CLOUD_INTERNAL_TESTING_HANDLER_TEST_H +#include "absl/memory/memory.h" #include "async_grpc/testing/rpc_handler_test_server.h" -#include "cartographer/common/make_unique.h" #include "cartographer/mapping/internal/testing/mock_map_builder.h" #include "cartographer/mapping/internal/testing/mock_pose_graph.h" #include "gtest/gtest.h" @@ -36,16 +36,16 @@ template class HandlerTest : public Test { public: void SetUp() override { - test_server_ = common::make_unique< + test_server_ = absl::make_unique< async_grpc::testing::RpcHandlerTestServer>( - common::make_unique()); + absl::make_unique()); mock_map_builder_context_ = test_server_ ->template GetUnsynchronizedContext(); mock_local_trajectory_uploader_ = - common::make_unique(); - mock_map_builder_ = common::make_unique(); - mock_pose_graph_ = common::make_unique(); + absl::make_unique(); + mock_map_builder_ = absl::make_unique(); + mock_pose_graph_ = absl::make_unique(); EXPECT_CALL(*mock_map_builder_context_, map_builder()) .Times(::testing::AnyNumber()) diff --git a/cartographer/cloud/map_builder_server_interface.cc b/cartographer/cloud/map_builder_server_interface.cc index e983c89..07e204b 100644 --- a/cartographer/cloud/map_builder_server_interface.cc +++ b/cartographer/cloud/map_builder_server_interface.cc @@ -1,7 +1,7 @@ #include "cartographer/cloud/map_builder_server_interface.h" +#include "absl/memory/memory.h" #include "cartographer/cloud/internal/map_builder_server.h" -#include "cartographer/common/make_unique.h" namespace cartographer { namespace cloud { @@ -13,8 +13,8 @@ void RegisterMapBuilderServerMetrics(metrics::FamilyFactory* factory) { std::unique_ptr CreateMapBuilderServer( const proto::MapBuilderServerOptions& map_builder_server_options, std::unique_ptr map_builder) { - return common::make_unique(map_builder_server_options, - std::move(map_builder)); + return absl::make_unique(map_builder_server_options, + std::move(map_builder)); } } // namespace cloud diff --git a/cartographer/cloud/map_builder_server_main.cc b/cartographer/cloud/map_builder_server_main.cc index 4bb0456..b07a99a 100644 --- a/cartographer/cloud/map_builder_server_main.cc +++ b/cartographer/cloud/map_builder_server_main.cc @@ -54,7 +54,7 @@ void Run(const std::string& configuration_directory, // config. map_builder_server_options.mutable_map_builder_options() ->set_collate_by_trajectory(true); - auto map_builder = common::make_unique( + auto map_builder = absl::make_unique( map_builder_server_options.map_builder_options()); std::unique_ptr map_builder_server = CreateMapBuilderServer(map_builder_server_options, diff --git a/cartographer/cloud/map_builder_server_options.cc b/cartographer/cloud/map_builder_server_options.cc index 563d4d1..560478c 100644 --- a/cartographer/cloud/map_builder_server_options.cc +++ b/cartographer/cloud/map_builder_server_options.cc @@ -16,8 +16,8 @@ #include "cartographer/cloud/map_builder_server_options.h" +#include "absl/memory/memory.h" #include "cartographer/common/configuration_file_resolver.h" -#include "cartographer/common/make_unique.h" #include "cartographer/mapping/map_builder.h" namespace cartographer { @@ -49,7 +49,7 @@ proto::MapBuilderServerOptions CreateMapBuilderServerOptions( proto::MapBuilderServerOptions LoadMapBuilderServerOptions( const std::string& configuration_directory, const std::string& configuration_basename) { - auto file_resolver = common::make_unique( + auto file_resolver = absl::make_unique( std::vector{configuration_directory}); const std::string code = file_resolver->GetFileContentOrDie(configuration_basename); diff --git a/cartographer/cloud/metrics/prometheus/family_factory.cc b/cartographer/cloud/metrics/prometheus/family_factory.cc index 1c02199..75757f9 100644 --- a/cartographer/cloud/metrics/prometheus/family_factory.cc +++ b/cartographer/cloud/metrics/prometheus/family_factory.cc @@ -16,7 +16,7 @@ #include "cartographer/cloud/metrics/prometheus/family_factory.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "prometheus/counter.h" #include "prometheus/family.h" #include "prometheus/gauge.h" @@ -51,7 +51,7 @@ class CounterFamily Counter* Add(const std::map& labels) override { ::prometheus::Counter* counter = &prometheus_->Add(labels); - auto wrapper = common::make_unique(counter); + auto wrapper = absl::make_unique(counter); auto* ptr = wrapper.get(); wrappers_.emplace_back(std::move(wrapper)); return ptr; @@ -84,7 +84,7 @@ class GaugeFamily Gauge* Add(const std::map& labels) override { ::prometheus::Gauge* gauge = &prometheus_->Add(labels); - auto wrapper = common::make_unique(gauge); + auto wrapper = absl::make_unique(gauge); auto* ptr = wrapper.get(); wrappers_.emplace_back(std::move(wrapper)); return ptr; @@ -115,7 +115,7 @@ class HistogramFamily : public ::cartographer::metrics::Family< Histogram* Add(const std::map& labels) override { ::prometheus::Histogram* histogram = &prometheus_->Add(labels, boundaries_); - auto wrapper = common::make_unique(histogram); + auto wrapper = absl::make_unique(histogram); auto* ptr = wrapper.get(); wrappers_.emplace_back(std::move(wrapper)); return ptr; @@ -139,7 +139,7 @@ FamilyFactory::NewCounterFamily(const std::string& name, .Name(name) .Help(description) .Register(*registry_); - auto wrapper = common::make_unique(&family); + auto wrapper = absl::make_unique(&family); auto* ptr = wrapper.get(); counters_.emplace_back(std::move(wrapper)); return ptr; @@ -152,7 +152,7 @@ FamilyFactory::NewGaugeFamily(const std::string& name, .Name(name) .Help(description) .Register(*registry_); - auto wrapper = common::make_unique(&family); + auto wrapper = absl::make_unique(&family); auto* ptr = wrapper.get(); gauges_.emplace_back(std::move(wrapper)); return ptr; @@ -166,7 +166,7 @@ FamilyFactory::NewHistogramFamily(const std::string& name, .Name(name) .Help(description) .Register(*registry_); - auto wrapper = common::make_unique(&family, boundaries); + auto wrapper = absl::make_unique(&family, boundaries); auto* ptr = wrapper.get(); histograms_.emplace_back(std::move(wrapper)); return ptr; diff --git a/cartographer/common/blocking_queue_test.cc b/cartographer/common/blocking_queue_test.cc index 92bdc0c..b6f019f 100644 --- a/cartographer/common/blocking_queue_test.cc +++ b/cartographer/common/blocking_queue_test.cc @@ -19,7 +19,7 @@ #include #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/time.h" #include "gtest/gtest.h" @@ -29,9 +29,9 @@ namespace { TEST(BlockingQueueTest, testPushPeekPop) { BlockingQueue> blocking_queue; - blocking_queue.Push(common::make_unique(42)); + blocking_queue.Push(absl::make_unique(42)); ASSERT_EQ(1, blocking_queue.Size()); - blocking_queue.Push(common::make_unique(24)); + blocking_queue.Push(absl::make_unique(24)); ASSERT_EQ(2, blocking_queue.Size()); EXPECT_EQ(42, *blocking_queue.Peek()); ASSERT_EQ(2, blocking_queue.Size()); @@ -60,10 +60,10 @@ TEST(BlockingQueueTest, testPopWithTimeout) { TEST(BlockingQueueTest, testPushWithTimeout) { BlockingQueue> blocking_queue(1); EXPECT_EQ(true, - blocking_queue.PushWithTimeout(common::make_unique(42), + blocking_queue.PushWithTimeout(absl::make_unique(42), common::FromMilliseconds(150))); EXPECT_EQ(false, - blocking_queue.PushWithTimeout(common::make_unique(15), + blocking_queue.PushWithTimeout(absl::make_unique(15), common::FromMilliseconds(150))); EXPECT_EQ(42, *blocking_queue.Pop()); EXPECT_EQ(0, blocking_queue.Size()); @@ -72,10 +72,10 @@ TEST(BlockingQueueTest, testPushWithTimeout) { TEST(BlockingQueueTest, testPushWithTimeoutInfinteQueue) { BlockingQueue> blocking_queue; EXPECT_EQ(true, - blocking_queue.PushWithTimeout(common::make_unique(42), + blocking_queue.PushWithTimeout(absl::make_unique(42), common::FromMilliseconds(150))); EXPECT_EQ(true, - blocking_queue.PushWithTimeout(common::make_unique(45), + blocking_queue.PushWithTimeout(absl::make_unique(45), common::FromMilliseconds(150))); EXPECT_EQ(42, *blocking_queue.Pop()); EXPECT_EQ(45, *blocking_queue.Pop()); @@ -91,7 +91,7 @@ TEST(BlockingQueueTest, testBlockingPop) { std::thread thread([&blocking_queue, &pop] { pop = *blocking_queue.Pop(); }); std::this_thread::sleep_for(common::FromMilliseconds(100)); - blocking_queue.Push(common::make_unique(42)); + blocking_queue.Push(absl::make_unique(42)); thread.join(); ASSERT_EQ(0, blocking_queue.Size()); EXPECT_EQ(42, pop); @@ -108,7 +108,7 @@ TEST(BlockingQueueTest, testBlockingPopWithTimeout) { }); std::this_thread::sleep_for(common::FromMilliseconds(100)); - blocking_queue.Push(common::make_unique(42)); + blocking_queue.Push(absl::make_unique(42)); thread.join(); ASSERT_EQ(0, blocking_queue.Size()); EXPECT_EQ(42, pop); diff --git a/cartographer/common/configuration_files_test.cc b/cartographer/common/configuration_files_test.cc index 1104737..62db6d8 100644 --- a/cartographer/common/configuration_files_test.cc +++ b/cartographer/common/configuration_files_test.cc @@ -32,11 +32,11 @@ TEST(ConfigurationFilesTest, ValidateMapBuilderOptions) { MAP_BUILDER.use_trajectory_builder_2d = true return MAP_BUILDER)text"; EXPECT_NO_FATAL_FAILURE({ - auto file_resolver = ::cartographer::common::make_unique< - ::cartographer::common::ConfigurationFileResolver>( - std::vector{ - std::string(::cartographer::common::kSourceDirectory) + - "/configuration_files"}); + auto file_resolver = + ::absl::make_unique< ::cartographer::common::ConfigurationFileResolver>( + std::vector{ + std::string(::cartographer::common::kSourceDirectory) + + "/configuration_files"}); ::cartographer::common::LuaParameterDictionary lua_parameter_dictionary( kCode, std::move(file_resolver)); ::cartographer::mapping::CreateMapBuilderOptions(&lua_parameter_dictionary); @@ -49,11 +49,11 @@ TEST(ConfigurationFilesTest, ValidateTrajectoryBuilderOptions) { TRAJECTORY_BUILDER.trajectory_builder_2d.use_imu_data = false return TRAJECTORY_BUILDER)text"; EXPECT_NO_FATAL_FAILURE({ - auto file_resolver = ::cartographer::common::make_unique< - ::cartographer::common::ConfigurationFileResolver>( - std::vector{ - std::string(::cartographer::common::kSourceDirectory) + - "/configuration_files"}); + auto file_resolver = + ::absl::make_unique< ::cartographer::common::ConfigurationFileResolver>( + std::vector{ + std::string(::cartographer::common::kSourceDirectory) + + "/configuration_files"}); ::cartographer::common::LuaParameterDictionary lua_parameter_dictionary( kCode, std::move(file_resolver)); ::cartographer::mapping::CreateTrajectoryBuilderOptions( diff --git a/cartographer/common/internal/testing/thread_pool_for_testing.cc b/cartographer/common/internal/testing/thread_pool_for_testing.cc index f804e13..771c44a 100644 --- a/cartographer/common/internal/testing/thread_pool_for_testing.cc +++ b/cartographer/common/internal/testing/thread_pool_for_testing.cc @@ -21,7 +21,7 @@ #include #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/task.h" #include "cartographer/common/time.h" #include "glog/logging.h" diff --git a/cartographer/common/lockless_queue.h b/cartographer/common/lockless_queue.h index 4c5250e..2517439 100644 --- a/cartographer/common/lockless_queue.h +++ b/cartographer/common/lockless_queue.h @@ -20,7 +20,7 @@ #include #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "glog/logging.h" namespace cartographer { diff --git a/cartographer/common/lockless_queue_test.cc b/cartographer/common/lockless_queue_test.cc index 5c9b565..f1f247c 100644 --- a/cartographer/common/lockless_queue_test.cc +++ b/cartographer/common/lockless_queue_test.cc @@ -7,13 +7,13 @@ namespace { TEST(LocklessQueueTest, PushAndPop) { LocklessQueue queue; - queue.Push(common::make_unique(1)); - queue.Push(common::make_unique(2)); + queue.Push(absl::make_unique(1)); + queue.Push(absl::make_unique(2)); EXPECT_EQ(*queue.Pop(), 1); - queue.Push(common::make_unique(3)); - queue.Push(common::make_unique(4)); + queue.Push(absl::make_unique(3)); + queue.Push(absl::make_unique(4)); EXPECT_EQ(*queue.Pop(), 2); - queue.Push(common::make_unique(5)); + queue.Push(absl::make_unique(5)); EXPECT_EQ(*queue.Pop(), 3); EXPECT_EQ(*queue.Pop(), 4); EXPECT_EQ(*queue.Pop(), 5); diff --git a/cartographer/common/lua_parameter_dictionary_test.cc b/cartographer/common/lua_parameter_dictionary_test.cc index 1862ae6..d794e02 100644 --- a/cartographer/common/lua_parameter_dictionary_test.cc +++ b/cartographer/common/lua_parameter_dictionary_test.cc @@ -20,8 +20,8 @@ #include #include +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary_test_helpers.h" -#include "cartographer/common/make_unique.h" #include "gtest/gtest.h" namespace cartographer { @@ -31,7 +31,7 @@ namespace { std::unique_ptr MakeNonReferenceCounted( const std::string& code) { return LuaParameterDictionary::NonReferenceCounted( - code, common::make_unique()); + code, absl::make_unique()); } class LuaParameterDictionaryTest : public ::testing::Test { diff --git a/cartographer/common/lua_parameter_dictionary_test_helpers.h b/cartographer/common/lua_parameter_dictionary_test_helpers.h index f395f25..4326029 100644 --- a/cartographer/common/lua_parameter_dictionary_test_helpers.h +++ b/cartographer/common/lua_parameter_dictionary_test_helpers.h @@ -20,8 +20,8 @@ #include #include +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary.h" -#include "cartographer/common/make_unique.h" #include "cartographer/common/port.h" #include "glog/logging.h" @@ -48,8 +48,8 @@ class DummyFileResolver : public FileResolver { std::unique_ptr MakeDictionary( const std::string& code) { - return common::make_unique( - code, common::make_unique()); + return absl::make_unique( + code, absl::make_unique()); } } // namespace common diff --git a/cartographer/common/make_unique.h b/cartographer/common/make_unique.h deleted file mode 100644 index a31baa9..0000000 --- a/cartographer/common/make_unique.h +++ /dev/null @@ -1,62 +0,0 @@ -/* - * Copyright 2016 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_MAKE_UNIQUE_H_ -#define CARTOGRAPHER_COMMON_MAKE_UNIQUE_H_ - -#include -#include -#include -#include - -namespace cartographer { -namespace common { - -// Implementation of c++14's std::make_unique, taken from -// https://isocpp.org/files/papers/N3656.txt -template -struct _Unique_if { - typedef std::unique_ptr _Single_object; -}; - -template -struct _Unique_if { - typedef std::unique_ptr _Unknown_bound; -}; - -template -struct _Unique_if { - typedef void _Known_bound; -}; - -template -typename _Unique_if::_Single_object make_unique(Args&&... args) { - return std::unique_ptr(new T(std::forward(args)...)); -} - -template -typename _Unique_if::_Unknown_bound make_unique(size_t n) { - typedef typename std::remove_extent::type U; - return std::unique_ptr(new U[n]()); -} - -template -typename _Unique_if::_Known_bound make_unique(Args&&...) = delete; - -} // namespace common -} // namespace cartographer - -#endif // CARTOGRAPHER_COMMON_MAKE_UNIQUE_H_ diff --git a/cartographer/common/optional.h b/cartographer/common/optional.h new file mode 100644 index 0000000..929ffde --- /dev/null +++ b/cartographer/common/optional.h @@ -0,0 +1,69 @@ +/* + * 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 "absl/memory/memory.h" +#include "glog/logging.h" + +namespace cartographer { +namespace common { + +template +class optional { + public: + optional() {} + + optional(const optional& other) { + if (other.has_value()) { + value_ = absl::make_unique(other.value()); + } + } + + explicit optional(const T& value) { value_ = absl::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_ = absl::make_unique(other_value); + return *this; + } + + optional& operator=(const optional& other) { + if (!other.has_value()) { + this->value_ = nullptr; + } else { + this->value_ = absl::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/task_test.cc b/cartographer/common/task_test.cc index 249bc08..896dbb1 100644 --- a/cartographer/common/task_test.cc +++ b/cartographer/common/task_test.cc @@ -19,7 +19,7 @@ #include #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "gmock/gmock.h" #include "gtest/gtest.h" @@ -71,7 +71,7 @@ class TaskTest : public ::testing::Test { }; TEST_F(TaskTest, RunTask) { - auto a = make_unique(); + auto a = absl::make_unique(); MockCallback callback; a->SetWorkItem([&callback]() { callback.Run(); }); EXPECT_EQ(a->GetState(), Task::NEW); @@ -85,8 +85,8 @@ TEST_F(TaskTest, RunTask) { } TEST_F(TaskTest, RunTaskWithDependency) { - auto a = make_unique(); - auto b = make_unique(); + auto a = absl::make_unique(); + auto b = absl::make_unique(); MockCallback callback_a; a->SetWorkItem([&callback_a]() { callback_a.Run(); }); MockCallback callback_b; @@ -116,10 +116,10 @@ TEST_F(TaskTest, RunTaskWithTwoDependency) { /* c \ * a --> b --> d */ - auto a = make_unique(); - auto b = make_unique(); - auto c = make_unique(); - auto d = make_unique(); + auto a = absl::make_unique(); + auto b = absl::make_unique(); + auto c = absl::make_unique(); + auto d = absl::make_unique(); MockCallback callback_a; a->SetWorkItem([&callback_a]() { callback_a.Run(); }); MockCallback callback_b; @@ -159,7 +159,7 @@ TEST_F(TaskTest, RunTaskWithTwoDependency) { } TEST_F(TaskTest, RunWithCompletedDependency) { - auto a = make_unique(); + auto a = absl::make_unique(); MockCallback callback_a; a->SetWorkItem([&callback_a]() { callback_a.Run(); }); auto shared_a = thread_pool()->Schedule(std::move(a)).lock(); @@ -168,7 +168,7 @@ TEST_F(TaskTest, RunWithCompletedDependency) { EXPECT_CALL(callback_a, Run()).Times(1); thread_pool()->RunNext(); EXPECT_EQ(shared_a->GetState(), Task::COMPLETED); - auto b = make_unique(); + auto b = absl::make_unique(); MockCallback callback_b; b->SetWorkItem([&callback_b]() { callback_b.Run(); }); b->AddDependency(shared_a); diff --git a/cartographer/common/thread_pool.cc b/cartographer/common/thread_pool.cc index 258231e..21ad1a1 100644 --- a/cartographer/common/thread_pool.cc +++ b/cartographer/common/thread_pool.cc @@ -21,7 +21,7 @@ #include #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/task.h" #include "glog/logging.h" diff --git a/cartographer/common/thread_pool_test.cc b/cartographer/common/thread_pool_test.cc index 8cf0264..6251de1 100644 --- a/cartographer/common/thread_pool_test.cc +++ b/cartographer/common/thread_pool_test.cc @@ -18,7 +18,7 @@ #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "gtest/gtest.h" namespace cartographer { @@ -47,7 +47,7 @@ class Receiver { TEST(ThreadPoolTest, RunTask) { ThreadPool pool(1); Receiver receiver; - auto task = common::make_unique(); + auto task = absl::make_unique(); task->SetWorkItem([&receiver]() { receiver.Receive(1); }); pool.Schedule(std::move(task)); receiver.WaitForNumberSequence({1}); @@ -59,7 +59,7 @@ TEST(ThreadPoolTest, ManyTasks) { Receiver receiver; int kNumTasks = 10; for (int i = 0; i < kNumTasks; ++i) { - auto task = common::make_unique(); + auto task = absl::make_unique(); task->SetWorkItem([&receiver]() { receiver.Receive(1); }); pool.Schedule(std::move(task)); } @@ -70,9 +70,9 @@ TEST(ThreadPoolTest, ManyTasks) { TEST(ThreadPoolTest, RunWithDependency) { ThreadPool pool(2); Receiver receiver; - auto task_2 = common::make_unique(); + auto task_2 = absl::make_unique(); task_2->SetWorkItem([&receiver]() { receiver.Receive(2); }); - auto task_1 = common::make_unique(); + auto task_1 = absl::make_unique(); task_1->SetWorkItem([&receiver]() { receiver.Receive(1); }); auto weak_task_1 = pool.Schedule(std::move(task_1)); task_2->AddDependency(weak_task_1); @@ -83,10 +83,10 @@ TEST(ThreadPoolTest, RunWithDependency) { TEST(ThreadPoolTest, RunWithOutOfScopeDependency) { ThreadPool pool(2); Receiver receiver; - auto task_2 = common::make_unique(); + auto task_2 = absl::make_unique(); task_2->SetWorkItem([&receiver]() { receiver.Receive(2); }); { - auto task_1 = common::make_unique(); + auto task_1 = absl::make_unique(); task_1->SetWorkItem([&receiver]() { receiver.Receive(1); }); auto weak_task_1 = pool.Schedule(std::move(task_1)); task_2->AddDependency(weak_task_1); @@ -100,10 +100,10 @@ TEST(ThreadPoolTest, ManyDependencies) { ThreadPool pool(5); Receiver receiver; int kNumDependencies = 10; - auto task = common::make_unique(); + auto task = absl::make_unique(); task->SetWorkItem([&receiver]() { receiver.Receive(1); }); for (int i = 0; i < kNumDependencies; ++i) { - auto dependency_task = common::make_unique(); + auto dependency_task = absl::make_unique(); dependency_task->SetWorkItem([]() {}); task->AddDependency(pool.Schedule(std::move(dependency_task))); } @@ -117,11 +117,11 @@ TEST(ThreadPoolTest, ManyDependants) { ThreadPool pool(5); Receiver receiver; int kNumDependants = 10; - auto dependency_task = common::make_unique(); + auto dependency_task = absl::make_unique(); dependency_task->SetWorkItem([]() {}); auto dependency_handle = pool.Schedule(std::move(dependency_task)); for (int i = 0; i < kNumDependants; ++i) { - auto task = common::make_unique(); + auto task = absl::make_unique(); task->AddDependency(dependency_handle); task->SetWorkItem([&receiver]() { receiver.Receive(1); }); pool.Schedule(std::move(task)); @@ -133,13 +133,13 @@ TEST(ThreadPoolTest, ManyDependants) { TEST(ThreadPoolTest, RunWithMultipleDependencies) { ThreadPool pool(2); Receiver receiver; - auto task_1 = common::make_unique(); + auto task_1 = absl::make_unique(); task_1->SetWorkItem([&receiver]() { receiver.Receive(1); }); - auto task_2a = common::make_unique(); + auto task_2a = absl::make_unique(); task_2a->SetWorkItem([&receiver]() { receiver.Receive(2); }); - auto task_2b = common::make_unique(); + auto task_2b = absl::make_unique(); task_2b->SetWorkItem([&receiver]() { receiver.Receive(2); }); - auto task_3 = common::make_unique(); + auto task_3 = absl::make_unique(); task_3->SetWorkItem([&receiver]() { receiver.Receive(3); }); /* -> task_2a \ * task_1 /-> task_2b --> task_3 @@ -159,9 +159,9 @@ TEST(ThreadPoolTest, RunWithMultipleDependencies) { TEST(ThreadPoolTest, RunWithFinishedDependency) { ThreadPool pool(2); Receiver receiver; - auto task_1 = common::make_unique(); + auto task_1 = absl::make_unique(); task_1->SetWorkItem([&receiver]() { receiver.Receive(1); }); - auto task_2 = common::make_unique(); + auto task_2 = absl::make_unique(); task_2->SetWorkItem([&receiver]() { receiver.Receive(2); }); auto weak_task_1 = pool.Schedule(std::move(task_1)); task_2->AddDependency(weak_task_1); diff --git a/cartographer/io/coloring_points_processor.cc b/cartographer/io/coloring_points_processor.cc index a11e6b9..9375071 100644 --- a/cartographer/io/coloring_points_processor.cc +++ b/cartographer/io/coloring_points_processor.cc @@ -17,7 +17,7 @@ #include "cartographer/io/coloring_points_processor.h" #include "Eigen/Core" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "glog/logging.h" namespace cartographer { @@ -33,8 +33,8 @@ ColoringPointsProcessor::FromDictionary( const Uint8Color color = {{static_cast(color_values[0]), static_cast(color_values[1]), static_cast(color_values[2])}}; - return common::make_unique(ToFloatColor(color), - frame_id, next); + return absl::make_unique(ToFloatColor(color), + frame_id, next); } ColoringPointsProcessor::ColoringPointsProcessor(const FloatColor& color, diff --git a/cartographer/io/counting_points_processor.cc b/cartographer/io/counting_points_processor.cc index 000340d..995461d 100644 --- a/cartographer/io/counting_points_processor.cc +++ b/cartographer/io/counting_points_processor.cc @@ -16,7 +16,7 @@ #include "cartographer/io/counting_points_processor.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "glog/logging.h" namespace cartographer { @@ -29,7 +29,7 @@ std::unique_ptr CountingPointsProcessor::FromDictionary( common::LuaParameterDictionary* const dictionary, PointsProcessor* const next) { - return common::make_unique(next); + return absl::make_unique(next); } void CountingPointsProcessor::Process(std::unique_ptr batch) { diff --git a/cartographer/io/fixed_ratio_sampling_points_processor.cc b/cartographer/io/fixed_ratio_sampling_points_processor.cc index e517a1d..8ac14de 100644 --- a/cartographer/io/fixed_ratio_sampling_points_processor.cc +++ b/cartographer/io/fixed_ratio_sampling_points_processor.cc @@ -17,7 +17,7 @@ #include "cartographer/io/fixed_ratio_sampling_points_processor.h" #include "Eigen/Core" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "glog/logging.h" namespace cartographer { @@ -30,8 +30,8 @@ FixedRatioSamplingPointsProcessor::FromDictionary( const double sampling_ratio(dictionary->GetDouble("sampling_ratio")); CHECK_LT(0., sampling_ratio) << "Sampling ratio <= 0 makes no sense."; CHECK_LT(sampling_ratio, 1.) << "Sampling ratio >= 1 makes no sense."; - return common::make_unique(sampling_ratio, - next); + return absl::make_unique(sampling_ratio, + next); } FixedRatioSamplingPointsProcessor::FixedRatioSamplingPointsProcessor( @@ -58,8 +58,7 @@ PointsProcessor::FlushResult FixedRatioSamplingPointsProcessor::Flush() { return PointsProcessor::FlushResult::kFinished; case PointsProcessor::FlushResult::kRestartStream: - sampler_ = - common::make_unique(sampling_ratio_); + sampler_ = absl::make_unique(sampling_ratio_); return PointsProcessor::FlushResult::kRestartStream; } LOG(FATAL); diff --git a/cartographer/io/frame_id_filtering_points_processor.cc b/cartographer/io/frame_id_filtering_points_processor.cc index 2b2ae47..f9b9f42 100644 --- a/cartographer/io/frame_id_filtering_points_processor.cc +++ b/cartographer/io/frame_id_filtering_points_processor.cc @@ -16,8 +16,8 @@ #include "cartographer/io/frame_id_filtering_points_processor.h" +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary.h" -#include "cartographer/common/make_unique.h" #include "cartographer/io/points_batch.h" #include "glog/logging.h" @@ -36,7 +36,7 @@ FrameIdFilteringPointsProcessor::FromDictionary( drop_frames = dictionary->GetDictionary("drop_frames")->GetArrayValuesAsStrings(); } - return common::make_unique( + return absl::make_unique( std::unordered_set(keep_frames.begin(), keep_frames.end()), std::unordered_set(drop_frames.begin(), drop_frames.end()), next); diff --git a/cartographer/io/hybrid_grid_points_processor.cc b/cartographer/io/hybrid_grid_points_processor.cc index e998e23..32525fb 100644 --- a/cartographer/io/hybrid_grid_points_processor.cc +++ b/cartographer/io/hybrid_grid_points_processor.cc @@ -4,7 +4,7 @@ #include #include "Eigen/Core" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/io/file_writer.h" #include "cartographer/io/points_batch.h" #include "cartographer/io/points_processor.h" @@ -31,7 +31,7 @@ HybridGridPointsProcessor::FromDictionary( const FileWriterFactory& file_writer_factory, common::LuaParameterDictionary* const dictionary, PointsProcessor* const next) { - return common::make_unique( + return absl::make_unique( dictionary->GetDouble("voxel_size"), mapping::CreateRangeDataInserterOptions3D( dictionary->GetDictionary("range_data_inserter").get()), diff --git a/cartographer/io/intensity_to_color_points_processor.cc b/cartographer/io/intensity_to_color_points_processor.cc index 0bceb64..c1a2c08 100644 --- a/cartographer/io/intensity_to_color_points_processor.cc +++ b/cartographer/io/intensity_to_color_points_processor.cc @@ -17,7 +17,7 @@ #include "cartographer/io/intensity_to_color_points_processor.h" #include "Eigen/Core" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/math.h" #include "glog/logging.h" @@ -32,7 +32,7 @@ IntensityToColorPointsProcessor::FromDictionary( dictionary->HasKey("frame_id") ? dictionary->GetString("frame_id") : ""; const float min_intensity = dictionary->GetDouble("min_intensity"); const float max_intensity = dictionary->GetDouble("max_intensity"); - return common::make_unique( + return absl::make_unique( min_intensity, max_intensity, frame_id, next); } diff --git a/cartographer/io/internal/in_memory_proto_stream.h b/cartographer/io/internal/in_memory_proto_stream.h index 14da01a..c628d73 100644 --- a/cartographer/io/internal/in_memory_proto_stream.h +++ b/cartographer/io/internal/in_memory_proto_stream.h @@ -19,7 +19,7 @@ #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/port.h" #include "cartographer/io/proto_stream_interface.h" #include "google/protobuf/message.h" @@ -62,7 +62,7 @@ class InMemoryProtoStreamReader template void AddProto(const MessageType& proto) { - state_chunks_.push(common::make_unique(proto)); + state_chunks_.push(absl::make_unique(proto)); } bool ReadProto(google::protobuf::Message* proto) override; diff --git a/cartographer/io/internal/in_memory_proto_stream_test.cc b/cartographer/io/internal/in_memory_proto_stream_test.cc index b033385..9dd3a1e 100644 --- a/cartographer/io/internal/in_memory_proto_stream_test.cc +++ b/cartographer/io/internal/in_memory_proto_stream_test.cc @@ -24,7 +24,7 @@ namespace cartographer { namespace io { namespace { -using common::make_unique; +using absl::make_unique; using google::protobuf::Message; using mapping::proto::PoseGraph; using mapping::proto::SerializedData; diff --git a/cartographer/io/min_max_range_filtering_points_processor.cc b/cartographer/io/min_max_range_filtering_points_processor.cc index eb17090..392c638 100644 --- a/cartographer/io/min_max_range_filtering_points_processor.cc +++ b/cartographer/io/min_max_range_filtering_points_processor.cc @@ -16,8 +16,8 @@ #include "cartographer/io/min_max_range_filtering_points_processor.h" +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary.h" -#include "cartographer/common/make_unique.h" #include "cartographer/io/points_batch.h" namespace cartographer { @@ -27,7 +27,7 @@ std::unique_ptr MinMaxRangeFiteringPointsProcessor::FromDictionary( common::LuaParameterDictionary* const dictionary, PointsProcessor* const next) { - return common::make_unique( + return absl::make_unique( dictionary->GetDouble("min_range"), dictionary->GetDouble("max_range"), next); } diff --git a/cartographer/io/outlier_removing_points_processor.cc b/cartographer/io/outlier_removing_points_processor.cc index 5cf3619..c33d25e 100644 --- a/cartographer/io/outlier_removing_points_processor.cc +++ b/cartographer/io/outlier_removing_points_processor.cc @@ -16,8 +16,8 @@ #include "cartographer/io/outlier_removing_points_processor.h" +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary.h" -#include "cartographer/common/make_unique.h" #include "glog/logging.h" namespace cartographer { @@ -27,7 +27,7 @@ std::unique_ptr OutlierRemovingPointsProcessor::FromDictionary( common::LuaParameterDictionary* const dictionary, PointsProcessor* const next) { - return common::make_unique( + return absl::make_unique( dictionary->GetDouble("voxel_size"), next); } diff --git a/cartographer/io/pcd_writing_points_processor.cc b/cartographer/io/pcd_writing_points_processor.cc index bbfb618..a424931 100644 --- a/cartographer/io/pcd_writing_points_processor.cc +++ b/cartographer/io/pcd_writing_points_processor.cc @@ -20,8 +20,8 @@ #include #include +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary.h" -#include "cartographer/common/make_unique.h" #include "cartographer/io/points_batch.h" #include "glog/logging.h" @@ -82,7 +82,7 @@ PcdWritingPointsProcessor::FromDictionary( FileWriterFactory file_writer_factory, common::LuaParameterDictionary* const dictionary, PointsProcessor* const next) { - return common::make_unique( + return absl::make_unique( file_writer_factory(dictionary->GetString("filename")), next); } diff --git a/cartographer/io/ply_writing_points_processor.cc b/cartographer/io/ply_writing_points_processor.cc index 6e68865..d564518 100644 --- a/cartographer/io/ply_writing_points_processor.cc +++ b/cartographer/io/ply_writing_points_processor.cc @@ -20,8 +20,8 @@ #include #include +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary.h" -#include "cartographer/common/make_unique.h" #include "cartographer/io/points_batch.h" #include "glog/logging.h" @@ -85,7 +85,7 @@ PlyWritingPointsProcessor::FromDictionary( const FileWriterFactory& file_writer_factory, common::LuaParameterDictionary* const dictionary, PointsProcessor* const next) { - return common::make_unique( + return absl::make_unique( file_writer_factory(dictionary->GetString("filename")), next); } diff --git a/cartographer/io/points_processor_pipeline_builder.cc b/cartographer/io/points_processor_pipeline_builder.cc index f348f84..23c9232 100644 --- a/cartographer/io/points_processor_pipeline_builder.cc +++ b/cartographer/io/points_processor_pipeline_builder.cc @@ -16,7 +16,7 @@ #include "cartographer/io/points_processor_pipeline_builder.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/io/coloring_points_processor.h" #include "cartographer/io/counting_points_processor.h" #include "cartographer/io/fixed_ratio_sampling_points_processor.h" @@ -118,7 +118,7 @@ PointsProcessorPipelineBuilder::CreatePipeline( // The last consumer in the pipeline must exist, so that the one created after // it (and being before it in the pipeline) has a valid 'next' to point to. // The last consumer will just drop all points. - pipeline.emplace_back(common::make_unique()); + pipeline.emplace_back(absl::make_unique()); std::vector> configurations = dictionary->GetArrayValuesAsDictionaries(); diff --git a/cartographer/io/probability_grid_points_processor.cc b/cartographer/io/probability_grid_points_processor.cc index f404fe1..0796907 100644 --- a/cartographer/io/probability_grid_points_processor.cc +++ b/cartographer/io/probability_grid_points_processor.cc @@ -17,8 +17,8 @@ #include "cartographer/io/probability_grid_points_processor.h" #include "Eigen/Core" +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary.h" -#include "cartographer/common/make_unique.h" #include "cartographer/common/math.h" #include "cartographer/io/draw_trajectories.h" #include "cartographer/io/image.h" @@ -113,7 +113,7 @@ ProbabilityGridPointsProcessor::FromDictionary( dictionary->HasKey("output_type") ? OutputTypeFromString(dictionary->GetString("output_type")) : OutputType::kPng; - return common::make_unique( + return absl::make_unique( dictionary->GetDouble("resolution"), mapping::CreateProbabilityGridRangeDataInserterOptions2D( dictionary->GetDictionary("range_data_inserter").get()), @@ -178,8 +178,8 @@ std::unique_ptr DrawProbabilityGrid( LOG(WARNING) << "Not writing output: empty probability grid"; return nullptr; } - auto image = common::make_unique(cell_limits.num_x_cells, - cell_limits.num_y_cells); + auto image = absl::make_unique(cell_limits.num_x_cells, + cell_limits.num_y_cells); for (const Eigen::Array2i& xy_index : mapping::XYIndexRangeIterator(cell_limits)) { const Eigen::Array2i index = xy_index + *offset; diff --git a/cartographer/io/probability_grid_points_processor_test.cc b/cartographer/io/probability_grid_points_processor_test.cc index 0b01977..31a35a2 100644 --- a/cartographer/io/probability_grid_points_processor_test.cc +++ b/cartographer/io/probability_grid_points_processor_test.cc @@ -32,7 +32,7 @@ namespace io { namespace { std::unique_ptr CreatePointsBatch() { - auto points_batch = cartographer::common::make_unique(); + auto points_batch = ::absl::make_unique(); points_batch->origin = Eigen::Vector3f(0, 0, 0); points_batch->points.emplace_back(0.0f, 0.0f, 0.0f); points_batch->points.emplace_back(0.0f, 1.0f, 2.0f); @@ -48,9 +48,8 @@ std::unique_ptr CreatePointsBatch() { return [&fake_file_writer_output, &expected_filename](const std::string& full_filename) { EXPECT_EQ(expected_filename, full_filename); - return ::cartographer::common::make_unique< - ::cartographer::io::FakeFileWriter>(full_filename, - fake_file_writer_output); + return ::absl::make_unique<::cartographer::io::FakeFileWriter>( + full_filename, fake_file_writer_output); }; } @@ -59,8 +58,8 @@ CreatePipelineFromDictionary( common::LuaParameterDictionary* const pipeline_dictionary, const std::vector& trajectories, ::cartographer::io::FileWriterFactory file_writer_factory) { - auto builder = ::cartographer::common::make_unique< - ::cartographer::io::PointsProcessorPipelineBuilder>(); + auto builder = + ::absl::make_unique<::cartographer::io::PointsProcessorPipelineBuilder>(); builder->Register( ProbabilityGridPointsProcessor::kConfigurationFileActionName, [&trajectories, file_writer_factory]( @@ -115,7 +114,7 @@ std::unique_ptr CreateParameterDictionary() { } return pipeline )text", - common::make_unique()); + absl::make_unique()); return parameter_dictionary; } diff --git a/cartographer/io/proto_stream_deserializer_test.cc b/cartographer/io/proto_stream_deserializer_test.cc index d8416ae..44e5a0b 100644 --- a/cartographer/io/proto_stream_deserializer_test.cc +++ b/cartographer/io/proto_stream_deserializer_test.cc @@ -29,7 +29,6 @@ namespace cartographer { namespace io { namespace { -using ::cartographer::common::make_unique; using ::cartographer::io::testing::ProtoFromStringOrDie; using ::cartographer::io::testing::ProtoReaderFromStrings; using ::cartographer::mapping::proto::SerializationHeader; @@ -134,7 +133,7 @@ TEST_F(ProtoStreamDeserializerTest, WorksOnGoldenTextStream) { TEST_F(ProtoStreamDeserializerTest, FailsIfVersionNotSupported) { reader_ = ProtoReaderFromStrings(kUnsupportedSerializationHeaderProtoString, {}); - EXPECT_DEATH(common::make_unique(reader_.get()), + EXPECT_DEATH(absl::make_unique(reader_.get()), "Unsupported serialization format"); } diff --git a/cartographer/io/testing/test_helpers.cc b/cartographer/io/testing/test_helpers.cc index d2b5544..1e9fbab 100644 --- a/cartographer/io/testing/test_helpers.cc +++ b/cartographer/io/testing/test_helpers.cc @@ -25,17 +25,17 @@ std::unique_ptr ProtoReaderFromStrings( const std::string &header_textpb, const std::initializer_list &data_textpbs) { std::queue> proto_queue; - proto_queue.emplace(common::make_unique< + proto_queue.emplace(absl::make_unique< ::cartographer::mapping::proto::SerializationHeader>( ProtoFromStringOrDie<::cartographer::mapping::proto::SerializationHeader>( header_textpb))); for (const std::string &data_textpb : data_textpbs) { proto_queue.emplace( - common::make_unique<::cartographer::mapping::proto::SerializedData>( + absl::make_unique<::cartographer::mapping::proto::SerializedData>( ProtoFromStringOrDie< ::cartographer::mapping::proto::SerializedData>(data_textpb))); } - return common::make_unique(std::move(proto_queue)); + return absl::make_unique(std::move(proto_queue)); } } // namespace testing diff --git a/cartographer/io/xray_points_processor.cc b/cartographer/io/xray_points_processor.cc index 6c9b090..31856af 100644 --- a/cartographer/io/xray_points_processor.cc +++ b/cartographer/io/xray_points_processor.cc @@ -20,8 +20,8 @@ #include #include "Eigen/Core" +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary.h" -#include "cartographer/common/make_unique.h" #include "cartographer/common/math.h" #include "cartographer/io/draw_trajectories.h" #include "cartographer/io/image.h" @@ -133,7 +133,7 @@ std::unique_ptr XRayPointsProcessor::FromDictionary( floors = mapping::DetectFloors(trajectories.at(0)); } - return common::make_unique( + return absl::make_unique( dictionary->GetDouble("voxel_size"), transform::FromDictionary(dictionary->GetDictionary("transform").get()) .cast(), diff --git a/cartographer/io/xyz_writing_points_processor.cc b/cartographer/io/xyz_writing_points_processor.cc index f89ac32..6a25c8e 100644 --- a/cartographer/io/xyz_writing_points_processor.cc +++ b/cartographer/io/xyz_writing_points_processor.cc @@ -2,7 +2,7 @@ #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "glog/logging.h" namespace cartographer { @@ -30,7 +30,7 @@ XyzWriterPointsProcessor::FromDictionary( const FileWriterFactory& file_writer_factory, common::LuaParameterDictionary* const dictionary, PointsProcessor* const next) { - return common::make_unique( + return absl::make_unique( file_writer_factory(dictionary->GetString("filename")), next); } diff --git a/cartographer/mapping/2d/probability_grid.cc b/cartographer/mapping/2d/probability_grid.cc index 10a62bc..5c954e9 100644 --- a/cartographer/mapping/2d/probability_grid.cc +++ b/cartographer/mapping/2d/probability_grid.cc @@ -17,7 +17,7 @@ #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/mapping/probability_values.h" #include "cartographer/mapping/submaps.h" @@ -92,7 +92,7 @@ std::unique_ptr ProbabilityGrid::ComputeCroppedGrid() const { const Eigen::Vector2d max = limits().max() - resolution * Eigen::Vector2d(offset.y(), offset.x()); std::unique_ptr cropped_grid = - common::make_unique( + absl::make_unique( MapLimits(resolution, max, cell_limits), conversion_tables_); for (const Eigen::Array2i& xy_index : XYIndexRangeIterator(cell_limits)) { if (!IsKnown(xy_index + offset)) continue; diff --git a/cartographer/mapping/2d/range_data_inserter_2d_test.cc b/cartographer/mapping/2d/range_data_inserter_2d_test.cc index 5a72022..433f8a7 100644 --- a/cartographer/mapping/2d/range_data_inserter_2d_test.cc +++ b/cartographer/mapping/2d/range_data_inserter_2d_test.cc @@ -18,9 +18,9 @@ #include +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary.h" #include "cartographer/common/lua_parameter_dictionary_test_helpers.h" -#include "cartographer/common/make_unique.h" #include "cartographer/mapping/2d/probability_grid.h" #include "cartographer/mapping/probability_values.h" #include "gmock/gmock.h" @@ -44,7 +44,7 @@ class RangeDataInserterTest2D : public ::testing::Test { options_ = CreateProbabilityGridRangeDataInserterOptions2D( parameter_dictionary.get()); range_data_inserter_ = - common::make_unique(options_); + absl::make_unique(options_); } void InsertPointCloud() { diff --git a/cartographer/mapping/2d/submap_2d.cc b/cartographer/mapping/2d/submap_2d.cc index dee0368..5ac0827 100644 --- a/cartographer/mapping/2d/submap_2d.cc +++ b/cartographer/mapping/2d/submap_2d.cc @@ -23,7 +23,7 @@ #include #include "Eigen/Geometry" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/port.h" #include "cartographer/mapping/2d/probability_grid_range_data_inserter_2d.h" #include "cartographer/mapping/range_data_inserter_interface.h" @@ -76,7 +76,7 @@ Submap2D::Submap2D(const proto::Submap2D& proto, if (proto.has_grid()) { CHECK(proto.grid().has_probability_grid_2d()); grid_ = - common::make_unique(proto.grid(), conversion_tables_); + absl::make_unique(proto.grid(), conversion_tables_); } set_num_range_data(proto.num_range_data()); set_finished(proto.finished()); @@ -103,8 +103,8 @@ void Submap2D::UpdateFromProto(const proto::Submap& proto) { set_finished(submap_2d.finished()); if (proto.submap_2d().has_grid()) { CHECK(proto.submap_2d().grid().has_probability_grid_2d()); - grid_ = common::make_unique(submap_2d.grid(), - conversion_tables_); + grid_ = absl::make_unique(submap_2d.grid(), + conversion_tables_); } } @@ -159,7 +159,7 @@ std::vector> ActiveSubmaps2D::InsertRangeData( std::unique_ptr ActiveSubmaps2D::CreateRangeDataInserter() { - return common::make_unique( + return absl::make_unique( options_.range_data_inserter_options() .probability_grid_range_data_inserter_options_2d()); } @@ -168,7 +168,7 @@ std::unique_ptr ActiveSubmaps2D::CreateGrid( const Eigen::Vector2f& origin) { constexpr int kInitialSubmapSize = 100; float resolution = options_.grid_options_2d().resolution(); - return common::make_unique( + return absl::make_unique( MapLimits(resolution, origin.cast() + 0.5 * kInitialSubmapSize * resolution * Eigen::Vector2d::Ones(), @@ -183,7 +183,7 @@ void ActiveSubmaps2D::AddSubmap(const Eigen::Vector2f& origin) { CHECK(submaps_.front()->finished()); submaps_.erase(submaps_.begin()); } - submaps_.push_back(common::make_unique( + submaps_.push_back(absl::make_unique( origin, std::unique_ptr( static_cast(CreateGrid(origin).release())), diff --git a/cartographer/mapping/2d/submap_2d_test.cc b/cartographer/mapping/2d/submap_2d_test.cc index 0f01763..6f773dc 100644 --- a/cartographer/mapping/2d/submap_2d_test.cc +++ b/cartographer/mapping/2d/submap_2d_test.cc @@ -100,8 +100,8 @@ TEST(Submap2DTest, ToFromProto) { CellLimits(100, 110)); ValueConversionTables conversion_tables; Submap2D expected(Eigen::Vector2f(4.f, 5.f), - common::make_unique(expected_map_limits, - &conversion_tables), + absl::make_unique(expected_map_limits, + &conversion_tables), &conversion_tables); const proto::Submap proto = expected.ToProto(true /* include_probability_grid_data */); diff --git a/cartographer/mapping/2d/tsdf_2d.cc b/cartographer/mapping/2d/tsdf_2d.cc index 12cdf68..c465ec7 100644 --- a/cartographer/mapping/2d/tsdf_2d.cc +++ b/cartographer/mapping/2d/tsdf_2d.cc @@ -16,7 +16,7 @@ #include "cartographer/mapping/2d/tsdf_2d.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" namespace cartographer { namespace mapping { @@ -26,7 +26,7 @@ TSDF2D::TSDF2D(const MapLimits& limits, float truncation_distance, : Grid2D(limits, -truncation_distance, truncation_distance, conversion_tables), conversion_tables_(conversion_tables), - value_converter_(common::make_unique( + value_converter_(absl::make_unique( truncation_distance, max_weight, conversion_tables_)), weight_cells_( limits.cell_limits().num_x_cells * limits.cell_limits().num_y_cells, @@ -36,7 +36,7 @@ TSDF2D::TSDF2D(const proto::Grid2D& proto, ValueConversionTables* conversion_tables) : Grid2D(proto, conversion_tables), conversion_tables_(conversion_tables) { CHECK(proto.has_tsdf_2d()); - value_converter_ = common::make_unique( + value_converter_ = absl::make_unique( proto.tsdf_2d().truncation_distance(), proto.tsdf_2d().max_weight(), conversion_tables_); weight_cells_.reserve(proto.tsdf_2d().weight_cells_size()); @@ -120,7 +120,7 @@ std::unique_ptr TSDF2D::ComputeCroppedGrid() const { const double resolution = limits().resolution(); const Eigen::Vector2d max = limits().max() - resolution * Eigen::Vector2d(offset.y(), offset.x()); - std::unique_ptr cropped_grid = common::make_unique( + std::unique_ptr cropped_grid = absl::make_unique( MapLimits(resolution, max, cell_limits), value_converter_->getMaxTSD(), value_converter_->getMaxWeight(), conversion_tables_); for (const Eigen::Array2i& xy_index : XYIndexRangeIterator(cell_limits)) { diff --git a/cartographer/mapping/2d/tsdf_range_data_inserter_2d_test.cc b/cartographer/mapping/2d/tsdf_range_data_inserter_2d_test.cc index 7334b2d..b665143 100644 --- a/cartographer/mapping/2d/tsdf_range_data_inserter_2d_test.cc +++ b/cartographer/mapping/2d/tsdf_range_data_inserter_2d_test.cc @@ -44,8 +44,7 @@ class RangeDataInserterTest2DTSDF : public ::testing::Test { "update_weight_distance_cell_to_hit_kernel_bandwith = 0," "}"); options_ = CreateTSDFRangeDataInserterOptions2D(parameter_dictionary.get()); - range_data_inserter_ = - common::make_unique(options_); + range_data_inserter_ = absl::make_unique(options_); } void InsertPoint() { @@ -145,7 +144,7 @@ TEST_F(RangeDataInserterTest2DTSDF, InsertPoint) { TEST_F(RangeDataInserterTest2DTSDF, InsertPointWithFreeSpaceUpdate) { options_.set_update_free_space(true); - range_data_inserter_ = common::make_unique(options_); + range_data_inserter_ = absl::make_unique(options_); InsertPoint(); const float truncation_distance = static_cast(options_.truncation_distance()); @@ -199,7 +198,7 @@ TEST_F(RangeDataInserterTest2DTSDF, InsertPointWithFreeSpaceUpdate) { TEST_F(RangeDataInserterTest2DTSDF, InsertPointLinearWeight) { options_.set_update_weight_range_exponent(1); - range_data_inserter_ = common::make_unique(options_); + range_data_inserter_ = absl::make_unique(options_); InsertPoint(); const float truncation_distance = static_cast(options_.truncation_distance()); @@ -218,7 +217,7 @@ TEST_F(RangeDataInserterTest2DTSDF, InsertPointLinearWeight) { TEST_F(RangeDataInserterTest2DTSDF, InsertPointQuadraticWeight) { options_.set_update_weight_range_exponent(2); - range_data_inserter_ = common::make_unique(options_); + range_data_inserter_ = absl::make_unique(options_); InsertPoint(); const float truncation_distance = static_cast(options_.truncation_distance()); @@ -263,7 +262,7 @@ TEST_F(RangeDataInserterTest2DTSDF, TEST_F(RangeDataInserterTest2DTSDF, InsertSmallAnglePointWitNormalProjection) { options_.set_project_sdf_distance_to_scan_normal(true); - range_data_inserter_ = common::make_unique(options_); + range_data_inserter_ = absl::make_unique(options_); sensor::RangeData range_data; range_data.returns.emplace_back(-0.5f, 3.5f, 0.f); range_data.returns.emplace_back(5.5f, 3.5f, 0.f); @@ -292,7 +291,7 @@ TEST_F(RangeDataInserterTest2DTSDF, InsertPointsWithAngleScanNormalToRayWeight) { float bandwith = 10.f; options_.set_update_weight_angle_scan_normal_to_ray_kernel_bandwith(bandwith); - range_data_inserter_ = common::make_unique(options_); + range_data_inserter_ = absl::make_unique(options_); sensor::RangeData range_data; range_data.returns.emplace_back(-0.5f, 3.5f, 0.f); range_data.returns.emplace_back(5.5f, 3.5f, 0.f); @@ -326,7 +325,7 @@ TEST_F(RangeDataInserterTest2DTSDF, TEST_F(RangeDataInserterTest2DTSDF, InsertPointsWithDistanceCellToHit) { float bandwith = 10.f; options_.set_update_weight_distance_cell_to_hit_kernel_bandwith(bandwith); - range_data_inserter_ = common::make_unique(options_); + range_data_inserter_ = absl::make_unique(options_); InsertPoint(); const float truncation_distance = static_cast(options_.truncation_distance()); diff --git a/cartographer/mapping/3d/hybrid_grid.h b/cartographer/mapping/3d/hybrid_grid.h index 423f9c9..10d2a59 100644 --- a/cartographer/mapping/3d/hybrid_grid.h +++ b/cartographer/mapping/3d/hybrid_grid.h @@ -24,7 +24,7 @@ #include #include "Eigen/Core" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/math.h" #include "cartographer/common/port.h" #include "cartographer/mapping/probability_values.h" @@ -169,7 +169,7 @@ class NestedGrid { std::unique_ptr& meta_cell = meta_cells_[ToFlatIndex(meta_index, kBits)]; if (meta_cell == nullptr) { - meta_cell = common::make_unique(); + meta_cell = absl::make_unique(); } const Eigen::Array3i inner_index = index - meta_index * WrappedGrid::grid_size(); @@ -292,7 +292,7 @@ class DynamicGrid { std::unique_ptr& meta_cell = meta_cells_[ToFlatIndex(meta_index, bits_)]; if (meta_cell == nullptr) { - meta_cell = common::make_unique(); + meta_cell = absl::make_unique(); } const Eigen::Array3i inner_index = shifted_index - meta_index * WrappedGrid::grid_size(); diff --git a/cartographer/mapping/3d/submap_3d.cc b/cartographer/mapping/3d/submap_3d.cc index 7768b1f..00bc26e 100644 --- a/cartographer/mapping/3d/submap_3d.cc +++ b/cartographer/mapping/3d/submap_3d.cc @@ -199,9 +199,9 @@ Submap3D::Submap3D(const float high_resolution, const float low_resolution, const transform::Rigid3d& local_submap_pose) : Submap(local_submap_pose), high_resolution_hybrid_grid_( - common::make_unique(high_resolution)), + absl::make_unique(high_resolution)), low_resolution_hybrid_grid_( - common::make_unique(low_resolution)) {} + absl::make_unique(low_resolution)) {} Submap3D::Submap3D(const proto::Submap3D& proto) : Submap(transform::ToRigid3(proto.local_pose())) { @@ -233,12 +233,12 @@ void Submap3D::UpdateFromProto(const proto::Submap3D& submap_3d) { set_num_range_data(submap_3d.num_range_data()); set_finished(submap_3d.finished()); if (submap_3d.has_high_resolution_hybrid_grid()) { - high_resolution_hybrid_grid_ = common::make_unique( - submap_3d.high_resolution_hybrid_grid()); + high_resolution_hybrid_grid_ = + absl::make_unique(submap_3d.high_resolution_hybrid_grid()); } if (submap_3d.has_low_resolution_hybrid_grid()) { low_resolution_hybrid_grid_ = - common::make_unique(submap_3d.low_resolution_hybrid_grid()); + absl::make_unique(submap_3d.low_resolution_hybrid_grid()); } } diff --git a/cartographer/mapping/id.h b/cartographer/mapping/id.h index 6cf427a..8e8cadc 100644 --- a/cartographer/mapping/id.h +++ b/cartographer/mapping/id.h @@ -27,7 +27,7 @@ #include #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/port.h" #include "cartographer/common/time.h" #include "cartographer/mapping/proto/pose_graph.pb.h" @@ -181,7 +181,7 @@ class MapById { } std::unique_ptr operator->() const { - return common::make_unique(this->operator*()); + return absl::make_unique(this->operator*()); } ConstIterator& operator++() { diff --git a/cartographer/mapping/imu_tracker_test.cc b/cartographer/mapping/imu_tracker_test.cc index 8cccc19..8f3b452 100644 --- a/cartographer/mapping/imu_tracker_test.cc +++ b/cartographer/mapping/imu_tracker_test.cc @@ -16,7 +16,7 @@ #include "cartographer/mapping/imu_tracker.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "gtest/gtest.h" namespace cartographer { @@ -31,7 +31,7 @@ constexpr int kSteps = 10; class ImuTrackerTest : public ::testing::Test { protected: void SetUp() override { - imu_tracker_ = common::make_unique(kGravityTimeConstant, time_); + imu_tracker_ = absl::make_unique(kGravityTimeConstant, time_); angular_velocity_ = Eigen::Vector3d(0, 0, 0); linear_acceleration_ = Eigen::Vector3d(0, 0, 9.9); EXPECT_NEAR(0., diff --git a/cartographer/mapping/internal/2d/local_slam_result_2d.cc b/cartographer/mapping/internal/2d/local_slam_result_2d.cc index 2acd48f..05b078c 100644 --- a/cartographer/mapping/internal/2d/local_slam_result_2d.cc +++ b/cartographer/mapping/internal/2d/local_slam_result_2d.cc @@ -23,7 +23,7 @@ namespace mapping { void LocalSlamResult2D::AddToTrajectoryBuilder( TrajectoryBuilderInterface* const trajectory_builder) { trajectory_builder->AddLocalSlamResultData( - common::make_unique(*this)); + absl::make_unique(*this)); } void LocalSlamResult2D::AddToPoseGraph(int trajectory_id, diff --git a/cartographer/mapping/internal/2d/local_trajectory_builder_2d.cc b/cartographer/mapping/internal/2d/local_trajectory_builder_2d.cc index de036a6..9df3d93 100644 --- a/cartographer/mapping/internal/2d/local_trajectory_builder_2d.cc +++ b/cartographer/mapping/internal/2d/local_trajectory_builder_2d.cc @@ -19,7 +19,7 @@ #include #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/metrics/family_factory.h" #include "cartographer/sensor/range_data.h" @@ -66,7 +66,7 @@ std::unique_ptr LocalTrajectoryBuilder2D::ScanMatch( const common::Time time, const transform::Rigid2d& pose_prediction, const sensor::PointCloud& filtered_gravity_aligned_point_cloud) { if (active_submaps_.submaps().empty()) { - return common::make_unique(pose_prediction); + return absl::make_unique(pose_prediction); } std::shared_ptr matching_submap = active_submaps_.submaps().front(); @@ -84,7 +84,7 @@ std::unique_ptr LocalTrajectoryBuilder2D::ScanMatch( kRealTimeCorrelativeScanMatcherScoreMetric->Observe(score); } - auto pose_observation = common::make_unique(); + auto pose_observation = absl::make_unique(); ceres::Solver::Summary summary; ceres_scan_matcher_.Match(pose_prediction.translation(), initial_ceres_pose, filtered_gravity_aligned_point_cloud, @@ -271,7 +271,7 @@ LocalTrajectoryBuilder2D::AddAccumulatedRangeData( } last_wall_time_ = wall_time; last_thread_cpu_time_seconds_ = thread_cpu_time_seconds; - return common::make_unique( + return absl::make_unique( MatchingResult{time, pose_estimate, std::move(range_data_in_local), std::move(insertion_result)}); } @@ -287,7 +287,7 @@ LocalTrajectoryBuilder2D::InsertIntoSubmap( } std::vector> insertion_submaps = active_submaps_.InsertRangeData(range_data_in_local); - return common::make_unique(InsertionResult{ + return absl::make_unique(InsertionResult{ std::make_shared(TrajectoryNode::Data{ time, gravity_alignment, @@ -324,7 +324,7 @@ void LocalTrajectoryBuilder2D::InitializeExtrapolator(const common::Time time) { // in time and thus the last two are used. constexpr double kExtrapolationEstimationTimeSec = 0.001; // TODO(gaschler): Consider using InitializeWithImu as 3D does. - extrapolator_ = common::make_unique( + extrapolator_ = absl::make_unique( ::cartographer::common::FromSeconds(kExtrapolationEstimationTimeSec), options_.imu_gravity_time_constant()); extrapolator_->AddPose(time, transform::Rigid3d::Identity()); diff --git a/cartographer/mapping/internal/2d/pose_graph_2d.cc b/cartographer/mapping/internal/2d/pose_graph_2d.cc index 782ef50..2b958b1 100644 --- a/cartographer/mapping/internal/2d/pose_graph_2d.cc +++ b/cartographer/mapping/internal/2d/pose_graph_2d.cc @@ -29,7 +29,7 @@ #include #include "Eigen/Eigenvalues" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/math.h" #include "cartographer/mapping/proto/pose_graph/constraint_builder_options.pb.h" #include "cartographer/sensor/compressed_point_cloud.h" @@ -158,8 +158,8 @@ void PoseGraph2D::AddWorkItem( const std::function& work_item) { common::MutexLocker locker(&work_queue_mutex_); if (work_queue_ == nullptr) { - work_queue_ = common::make_unique(); - auto task = common::make_unique(); + work_queue_ = absl::make_unique(); + auto task = absl::make_unique(); task->SetWorkItem([this]() { DrainWorkQueue(); }); thread_pool_->Schedule(std::move(task)); } @@ -183,7 +183,7 @@ void PoseGraph2D::AddTrajectoryIfNeeded(const int trajectory_id) { // Make sure we have a sampler for this trajectory. if (!global_localization_samplers_[trajectory_id]) { global_localization_samplers_[trajectory_id] = - common::make_unique( + absl::make_unique( options_.global_sampling_ratio()); } } diff --git a/cartographer/mapping/internal/2d/pose_graph_2d_test.cc b/cartographer/mapping/internal/2d/pose_graph_2d_test.cc index 73ba849..2789238 100644 --- a/cartographer/mapping/internal/2d/pose_graph_2d_test.cc +++ b/cartographer/mapping/internal/2d/pose_graph_2d_test.cc @@ -20,8 +20,8 @@ #include #include +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary_test_helpers.h" -#include "cartographer/common/make_unique.h" #include "cartographer/common/thread_pool.h" #include "cartographer/common/time.h" #include "cartographer/mapping/2d/probability_grid_range_data_inserter_2d.h" @@ -77,7 +77,7 @@ class PoseGraph2DTest : public ::testing::Test { }, }, })text"); - active_submaps_ = common::make_unique( + active_submaps_ = absl::make_unique( mapping::CreateSubmapsOptions2D(parameter_dictionary.get())); } @@ -155,9 +155,9 @@ class PoseGraph2DTest : public ::testing::Test { global_constraint_search_after_n_seconds = 10.0, })text"); auto options = CreatePoseGraphOptions(parameter_dictionary.get()); - pose_graph_ = common::make_unique( + pose_graph_ = absl::make_unique( options, - common::make_unique( + absl::make_unique( options.optimization_problem_options()), &thread_pool_); } diff --git a/cartographer/mapping/internal/2d/scan_matching/ceres_scan_matcher_2d_test.cc b/cartographer/mapping/internal/2d/scan_matching/ceres_scan_matcher_2d_test.cc index 7503aa8..162565b 100644 --- a/cartographer/mapping/internal/2d/scan_matching/ceres_scan_matcher_2d_test.cc +++ b/cartographer/mapping/internal/2d/scan_matching/ceres_scan_matcher_2d_test.cc @@ -18,9 +18,9 @@ #include +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary.h" #include "cartographer/common/lua_parameter_dictionary_test_helpers.h" -#include "cartographer/common/make_unique.h" #include "cartographer/mapping/2d/probability_grid.h" #include "cartographer/mapping/probability_values.h" #include "cartographer/sensor/point_cloud.h" @@ -57,7 +57,7 @@ class CeresScanMatcherTest : public ::testing::Test { })text"); const proto::CeresScanMatcherOptions2D options = CreateCeresScanMatcherOptions2D(parameter_dictionary.get()); - ceres_scan_matcher_ = common::make_unique(options); + ceres_scan_matcher_ = absl::make_unique(options); } void TestFromInitialPose(const transform::Rigid2d& initial_pose) { diff --git a/cartographer/mapping/internal/2d/scan_matching/fast_correlative_scan_matcher_2d.cc b/cartographer/mapping/internal/2d/scan_matching/fast_correlative_scan_matcher_2d.cc index d0075a0..726aa0a 100644 --- a/cartographer/mapping/internal/2d/scan_matching/fast_correlative_scan_matcher_2d.cc +++ b/cartographer/mapping/internal/2d/scan_matching/fast_correlative_scan_matcher_2d.cc @@ -23,7 +23,7 @@ #include #include "Eigen/Geometry" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/math.h" #include "cartographer/mapping/2d/grid_2d.h" #include "cartographer/sensor/point_cloud.h" @@ -191,7 +191,7 @@ FastCorrelativeScanMatcher2D::FastCorrelativeScanMatcher2D( : options_(options), limits_(grid.limits()), precomputation_grid_stack_( - common::make_unique(grid, options)) {} + absl::make_unique(grid, options)) {} FastCorrelativeScanMatcher2D::~FastCorrelativeScanMatcher2D() {} diff --git a/cartographer/mapping/internal/2d/scan_matching/real_time_correlative_scan_matcher_2d_test.cc b/cartographer/mapping/internal/2d/scan_matching/real_time_correlative_scan_matcher_2d_test.cc index cf4af1a..87a4d43 100644 --- a/cartographer/mapping/internal/2d/scan_matching/real_time_correlative_scan_matcher_2d_test.cc +++ b/cartographer/mapping/internal/2d/scan_matching/real_time_correlative_scan_matcher_2d_test.cc @@ -20,8 +20,8 @@ #include #include "Eigen/Geometry" +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary_test_helpers.h" -#include "cartographer/common/make_unique.h" #include "cartographer/mapping/2d/probability_grid.h" #include "cartographer/mapping/2d/probability_grid_range_data_inserter_2d.h" #include "cartographer/mapping/internal/scan_matching/real_time_correlative_scan_matcher.h" @@ -48,7 +48,7 @@ class RealTimeCorrelativeScanMatcherTest : public ::testing::Test { "miss_probability = 0.4, " "}"); range_data_inserter_ = - common::make_unique( + absl::make_unique( CreateProbabilityGridRangeDataInserterOptions2D( parameter_dictionary.get())); } @@ -72,7 +72,7 @@ class RealTimeCorrelativeScanMatcherTest : public ::testing::Test { "rotation_delta_cost_weight = 0., " "}"); real_time_correlative_scan_matcher_ = - common::make_unique( + absl::make_unique( CreateRealTimeCorrelativeScanMatcherOptions( parameter_dictionary.get())); } diff --git a/cartographer/mapping/internal/3d/local_slam_result_3d.cc b/cartographer/mapping/internal/3d/local_slam_result_3d.cc index 0f9d70b..6143008 100644 --- a/cartographer/mapping/internal/3d/local_slam_result_3d.cc +++ b/cartographer/mapping/internal/3d/local_slam_result_3d.cc @@ -23,7 +23,7 @@ namespace mapping { void LocalSlamResult3D::AddToTrajectoryBuilder( TrajectoryBuilderInterface* const trajectory_builder) { trajectory_builder->AddLocalSlamResultData( - common::make_unique(*this)); + absl::make_unique(*this)); } void LocalSlamResult3D::AddToPoseGraph(int trajectory_id, diff --git a/cartographer/mapping/internal/3d/local_trajectory_builder_3d.cc b/cartographer/mapping/internal/3d/local_trajectory_builder_3d.cc index 820c30f..c50076c 100644 --- a/cartographer/mapping/internal/3d/local_trajectory_builder_3d.cc +++ b/cartographer/mapping/internal/3d/local_trajectory_builder_3d.cc @@ -18,7 +18,7 @@ #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/time.h" #include "cartographer/mapping/internal/3d/scan_matching/rotational_scan_matcher.h" #include "cartographer/mapping/proto/3d/local_trajectory_builder_options_3d.pb.h" @@ -51,11 +51,10 @@ LocalTrajectoryBuilder3D::LocalTrajectoryBuilder3D( active_submaps_(options.submaps_options()), motion_filter_(options.motion_filter_options()), real_time_correlative_scan_matcher_( - common::make_unique( + absl::make_unique( options_.real_time_correlative_scan_matcher_options())), - ceres_scan_matcher_( - common::make_unique( - options_.ceres_scan_matcher_options())), + ceres_scan_matcher_(absl::make_unique( + options_.ceres_scan_matcher_options())), accumulated_range_data_{Eigen::Vector3f::Zero(), {}, {}}, range_data_collator_(expected_range_sensor_ids) {} @@ -66,7 +65,7 @@ std::unique_ptr LocalTrajectoryBuilder3D::ScanMatch( const sensor::PointCloud& low_resolution_point_cloud_in_tracking, const sensor::PointCloud& high_resolution_point_cloud_in_tracking) { if (active_submaps_.submaps().empty()) { - return common::make_unique(pose_prediction); + return absl::make_unique(pose_prediction); } std::shared_ptr matching_submap = active_submaps_.submaps().front(); @@ -100,8 +99,8 @@ std::unique_ptr LocalTrajectoryBuilder3D::ScanMatch( pose_observation_in_submap.rotation().angularDistance( initial_ceres_pose.rotation()); kScanMatcherResidualAngleMetric->Observe(residual_angle); - return common::make_unique(matching_submap->local_pose() * - pose_observation_in_submap); + return absl::make_unique(matching_submap->local_pose() * + pose_observation_in_submap); } void LocalTrajectoryBuilder3D::AddImuData(const sensor::ImuData& imu_data) { @@ -325,7 +324,7 @@ LocalTrajectoryBuilder3D::AddAccumulatedRangeData( } last_wall_time_ = wall_time; last_thread_cpu_time_seconds_ = thread_cpu_time_seconds; - return common::make_unique(MatchingResult{ + return absl::make_unique(MatchingResult{ time, *pose_estimate, std::move(filtered_range_data_in_local), std::move(insertion_result)}); } @@ -361,7 +360,7 @@ LocalTrajectoryBuilder3D::InsertIntoSubmap( filtered_range_data_in_tracking.returns, transform::Rigid3f::Rotation(gravity_alignment.cast())), options_.rotational_histogram_size()); - return common::make_unique( + return absl::make_unique( InsertionResult{std::make_shared( mapping::TrajectoryNode::Data{ time, diff --git a/cartographer/mapping/internal/3d/pose_graph_3d.cc b/cartographer/mapping/internal/3d/pose_graph_3d.cc index cc6726c..4594971 100644 --- a/cartographer/mapping/internal/3d/pose_graph_3d.cc +++ b/cartographer/mapping/internal/3d/pose_graph_3d.cc @@ -28,7 +28,7 @@ #include #include "Eigen/Eigenvalues" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/math.h" #include "cartographer/mapping/proto/pose_graph/constraint_builder_options.pb.h" #include "cartographer/sensor/compressed_point_cloud.h" @@ -155,8 +155,8 @@ void PoseGraph3D::AddWorkItem( const std::function& work_item) { common::MutexLocker locker(&work_queue_mutex_); if (work_queue_ == nullptr) { - work_queue_ = common::make_unique(); - auto task = common::make_unique(); + work_queue_ = absl::make_unique(); + auto task = absl::make_unique(); task->SetWorkItem([this]() { DrainWorkQueue(); }); thread_pool_->Schedule(std::move(task)); } @@ -180,7 +180,7 @@ void PoseGraph3D::AddTrajectoryIfNeeded(const int trajectory_id) { // Make sure we have a sampler for this trajectory. if (!global_localization_samplers_[trajectory_id]) { global_localization_samplers_[trajectory_id] = - common::make_unique( + absl::make_unique( options_.global_sampling_ratio()); } } diff --git a/cartographer/mapping/internal/3d/pose_graph_3d_test.cc b/cartographer/mapping/internal/3d/pose_graph_3d_test.cc index 3fa6178..293766d 100644 --- a/cartographer/mapping/internal/3d/pose_graph_3d_test.cc +++ b/cartographer/mapping/internal/3d/pose_graph_3d_test.cc @@ -57,8 +57,7 @@ class PoseGraph3DForTesting : public PoseGraph3D { class PoseGraph3DTest : public ::testing::Test { protected: - PoseGraph3DTest() - : thread_pool_(common::make_unique(1)) {} + PoseGraph3DTest() : thread_pool_(absl::make_unique(1)) {} void SetUp() override { const std::string kPoseGraphLua = R"text( @@ -70,17 +69,16 @@ class PoseGraph3DTest : public ::testing::Test { void BuildPoseGraph() { auto optimization_problem = - common::make_unique( + absl::make_unique( pose_graph_options_.optimization_problem_options()); - pose_graph_ = common::make_unique( + pose_graph_ = absl::make_unique( pose_graph_options_, std::move(optimization_problem), thread_pool_.get()); } void BuildPoseGraphWithFakeOptimization() { - auto optimization_problem = - common::make_unique(); - pose_graph_ = common::make_unique( + auto optimization_problem = absl::make_unique(); + pose_graph_ = absl::make_unique( pose_graph_options_, std::move(optimization_problem), thread_pool_.get()); } @@ -159,7 +157,7 @@ TEST_F(PoseGraph3DTest, PureLocalizationTrimmer) { pose_graph_->AddSerializedConstraints(FromProto(proto.constraint())); } } - pose_graph_->AddTrimmer(common::make_unique( + pose_graph_->AddTrimmer(absl::make_unique( trajectory_id, num_submaps_to_keep)); pose_graph_->WaitForAllComputations(); EXPECT_EQ( @@ -236,8 +234,7 @@ TEST_F(PoseGraph3DTest, EvenSubmapTrimmer) { pose_graph_->AddSerializedConstraints(FromProto(proto.constraint())); } } - pose_graph_->AddTrimmer( - common::make_unique(trajectory_id)); + pose_graph_->AddTrimmer(absl::make_unique(trajectory_id)); pose_graph_->WaitForAllComputations(); EXPECT_EQ( pose_graph_->GetAllSubmapPoses().SizeOfTrajectoryOrZero(trajectory_id), diff --git a/cartographer/mapping/internal/3d/scan_matching/ceres_scan_matcher_3d.cc b/cartographer/mapping/internal/3d/scan_matching/ceres_scan_matcher_3d.cc index ea8892c..7eb8fb5 100644 --- a/cartographer/mapping/internal/3d/scan_matching/ceres_scan_matcher_3d.cc +++ b/cartographer/mapping/internal/3d/scan_matching/ceres_scan_matcher_3d.cc @@ -20,8 +20,8 @@ #include #include +#include "absl/memory/memory.h" #include "cartographer/common/ceres_solver_options.h" -#include "cartographer/common/make_unique.h" #include "cartographer/mapping/internal/3d/rotation_parameterization.h" #include "cartographer/mapping/internal/3d/scan_matching/occupied_space_cost_function_3d.h" #include "cartographer/mapping/internal/3d/scan_matching/rotation_delta_cost_functor_3d.h" @@ -80,10 +80,10 @@ void CeresScanMatcher3D::Match( initial_pose_estimate, nullptr /* translation_parameterization */, options_.only_optimize_yaw() ? std::unique_ptr( - common::make_unique>()) : std::unique_ptr( - common::make_unique()), + absl::make_unique()), &problem); CHECK_EQ(options_.occupied_space_weight_size(), diff --git a/cartographer/mapping/internal/3d/scan_matching/fast_correlative_scan_matcher_3d.cc b/cartographer/mapping/internal/3d/scan_matching/fast_correlative_scan_matcher_3d.cc index 66e4fbe..d5ebeb9 100644 --- a/cartographer/mapping/internal/3d/scan_matching/fast_correlative_scan_matcher_3d.cc +++ b/cartographer/mapping/internal/3d/scan_matching/fast_correlative_scan_matcher_3d.cc @@ -22,7 +22,7 @@ #include #include "Eigen/Geometry" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/math.h" #include "cartographer/mapping/internal/3d/scan_matching/low_resolution_matcher.h" #include "cartographer/mapping/proto/scan_matching//fast_correlative_scan_matcher_options_3d.pb.h" @@ -136,7 +136,7 @@ FastCorrelativeScanMatcher3D::FastCorrelativeScanMatcher3D( resolution_(hybrid_grid.resolution()), width_in_voxels_(hybrid_grid.grid_size()), precomputation_grid_stack_( - common::make_unique(hybrid_grid, options)), + absl::make_unique(hybrid_grid, options)), low_resolution_hybrid_grid_(low_resolution_hybrid_grid), rotational_scan_matcher_(HistogramsAtAnglesFromNodes(nodes)) {} @@ -206,7 +206,7 @@ FastCorrelativeScanMatcher3D::MatchWithSearchParameters( search_parameters, discrete_scans, lowest_resolution_candidates, precomputation_grid_stack_->max_depth(), min_score); if (best_candidate.score > min_score) { - return common::make_unique(Result{ + return absl::make_unique(Result{ best_candidate.score, GetPoseFromCandidate(discrete_scans, best_candidate).cast(), discrete_scans[best_candidate.scan_index].rotational_score, diff --git a/cartographer/mapping/internal/3d/scan_matching/fast_correlative_scan_matcher_3d_test.cc b/cartographer/mapping/internal/3d/scan_matching/fast_correlative_scan_matcher_3d_test.cc index 786e3b8..0709167 100644 --- a/cartographer/mapping/internal/3d/scan_matching/fast_correlative_scan_matcher_3d_test.cc +++ b/cartographer/mapping/internal/3d/scan_matching/fast_correlative_scan_matcher_3d_test.cc @@ -21,8 +21,8 @@ #include #include +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary_test_helpers.h" -#include "cartographer/common/make_unique.h" #include "cartographer/mapping/3d/range_data_inserter_3d.h" #include "cartographer/transform/rigid_transform_test_helpers.h" #include "cartographer/transform/transform.h" @@ -96,7 +96,7 @@ class FastCorrelativeScanMatcher3DTest : public ::testing::Test { std::unique_ptr GetFastCorrelativeScanMatcher( const proto::FastCorrelativeScanMatcherOptions3D& options, const transform::Rigid3f& pose) { - hybrid_grid_ = common::make_unique(0.05f); + hybrid_grid_ = absl::make_unique(0.05f); range_data_inserter_.Insert( sensor::RangeData{pose.translation(), sensor::TransformPointCloud(point_cloud_, pose), @@ -104,7 +104,7 @@ class FastCorrelativeScanMatcher3DTest : public ::testing::Test { hybrid_grid_.get()); hybrid_grid_->FinishUpdate(); - return common::make_unique( + return absl::make_unique( *hybrid_grid_, hybrid_grid_.get(), std::vector( {{std::make_shared( diff --git a/cartographer/mapping/internal/constraints/constraint_builder_2d.cc b/cartographer/mapping/internal/constraints/constraint_builder_2d.cc index 8b36fea..a15a4ec 100644 --- a/cartographer/mapping/internal/constraints/constraint_builder_2d.cc +++ b/cartographer/mapping/internal/constraints/constraint_builder_2d.cc @@ -26,7 +26,7 @@ #include #include "Eigen/Eigenvalues" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/math.h" #include "cartographer/common/thread_pool.h" #include "cartographer/mapping/proto/scan_matching//ceres_scan_matcher_options_2d.pb.h" @@ -58,8 +58,8 @@ ConstraintBuilder2D::ConstraintBuilder2D( common::ThreadPoolInterface* const thread_pool) : options_(options), thread_pool_(thread_pool), - finish_node_task_(common::make_unique()), - when_done_task_(common::make_unique()), + finish_node_task_(absl::make_unique()), + when_done_task_(absl::make_unique()), sampler_(options.sampling_ratio()), ceres_scan_matcher_(options.ceres_scan_matcher_options()) {} @@ -92,7 +92,7 @@ void ConstraintBuilder2D::MaybeAddConstraint( auto* const constraint = &constraints_.back(); const auto* scan_matcher = DispatchScanMatcherConstruction(submap_id, submap->grid()); - auto constraint_task = common::make_unique(); + auto constraint_task = absl::make_unique(); constraint_task->SetWorkItem([=]() EXCLUDES(mutex_) { ComputeConstraint(submap_id, submap, node_id, false, /* match_full_submap */ constant_data, initial_relative_pose, *scan_matcher, @@ -117,7 +117,7 @@ void ConstraintBuilder2D::MaybeAddGlobalConstraint( auto* const constraint = &constraints_.back(); const auto* scan_matcher = DispatchScanMatcherConstruction(submap_id, submap->grid()); - auto constraint_task = common::make_unique(); + auto constraint_task = absl::make_unique(); constraint_task->SetWorkItem([=]() EXCLUDES(mutex_) { ComputeConstraint(submap_id, submap, node_id, true, /* match_full_submap */ constant_data, transform::Rigid2d::Identity(), @@ -138,7 +138,7 @@ void ConstraintBuilder2D::NotifyEndOfNode() { }); auto finish_node_task_handle = thread_pool_->Schedule(std::move(finish_node_task_)); - finish_node_task_ = common::make_unique(); + finish_node_task_ = absl::make_unique(); when_done_task_->AddDependency(finish_node_task_handle); ++num_started_nodes_; } @@ -148,12 +148,11 @@ void ConstraintBuilder2D::WhenDone( common::MutexLocker locker(&mutex_); CHECK(when_done_ == nullptr); // TODO(gaschler): Consider using just std::function, it can also be empty. - when_done_ = - common::make_unique>(callback); + when_done_ = absl::make_unique>(callback); CHECK(when_done_task_ != nullptr); when_done_task_->SetWorkItem([this] { RunWhenDoneCallback(); }); thread_pool_->Schedule(std::move(when_done_task_)); - when_done_task_ = common::make_unique(); + when_done_task_ = absl::make_unique(); } const ConstraintBuilder2D::SubmapScanMatcher* @@ -165,11 +164,11 @@ ConstraintBuilder2D::DispatchScanMatcherConstruction(const SubmapId& submap_id, auto& submap_scan_matcher = submap_scan_matchers_[submap_id]; submap_scan_matcher.grid = grid; auto& scan_matcher_options = options_.fast_correlative_scan_matcher_options(); - auto scan_matcher_task = common::make_unique(); + auto scan_matcher_task = absl::make_unique(); scan_matcher_task->SetWorkItem( [&submap_scan_matcher, &scan_matcher_options]() { submap_scan_matcher.fast_correlative_scan_matcher = - common::make_unique( + absl::make_unique( *submap_scan_matcher.grid, scan_matcher_options); }); submap_scan_matcher.creation_task_handle = diff --git a/cartographer/mapping/internal/constraints/constraint_builder_2d_test.cc b/cartographer/mapping/internal/constraints/constraint_builder_2d_test.cc index 088a70d..cf766e8 100644 --- a/cartographer/mapping/internal/constraints/constraint_builder_2d_test.cc +++ b/cartographer/mapping/internal/constraints/constraint_builder_2d_test.cc @@ -45,7 +45,7 @@ class ConstraintBuilder2DTest : public ::testing::Test { POSE_GRAPH.constraint_builder.min_score = 0 POSE_GRAPH.constraint_builder.global_localization_min_score = 0 return POSE_GRAPH.constraint_builder)text"); - constraint_builder_ = common::make_unique( + constraint_builder_ = absl::make_unique( CreateConstraintBuilderOptions(constraint_builder_parameters.get()), &thread_pool_); } @@ -78,7 +78,7 @@ TEST_F(ConstraintBuilder2DTest, FindsConstraints) { ValueConversionTables conversion_tables; Submap2D submap( Eigen::Vector2f(4.f, 5.f), - common::make_unique(map_limits, &conversion_tables), + absl::make_unique(map_limits, &conversion_tables), &conversion_tables); int expected_nodes = 0; for (int i = 0; i < 2; ++i) { diff --git a/cartographer/mapping/internal/constraints/constraint_builder_3d.cc b/cartographer/mapping/internal/constraints/constraint_builder_3d.cc index 8bf40f2..c4035e1 100644 --- a/cartographer/mapping/internal/constraints/constraint_builder_3d.cc +++ b/cartographer/mapping/internal/constraints/constraint_builder_3d.cc @@ -26,7 +26,7 @@ #include #include "Eigen/Eigenvalues" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/math.h" #include "cartographer/common/thread_pool.h" #include "cartographer/mapping/proto/scan_matching//ceres_scan_matcher_options_3d.pb.h" @@ -60,8 +60,8 @@ ConstraintBuilder3D::ConstraintBuilder3D( common::ThreadPoolInterface* const thread_pool) : options_(options), thread_pool_(thread_pool), - finish_node_task_(common::make_unique()), - when_done_task_(common::make_unique()), + finish_node_task_(absl::make_unique()), + when_done_task_(absl::make_unique()), sampler_(options.sampling_ratio()), ceres_scan_matcher_(options.ceres_scan_matcher_options_3d()) {} @@ -96,7 +96,7 @@ void ConstraintBuilder3D::MaybeAddConstraint( auto* const constraint = &constraints_.back(); const auto* scan_matcher = DispatchScanMatcherConstruction(submap_id, submap_nodes, submap); - auto constraint_task = common::make_unique(); + auto constraint_task = absl::make_unique(); constraint_task->SetWorkItem([=]() EXCLUDES(mutex_) { ComputeConstraint(submap_id, node_id, false, /* match_full_submap */ constant_data, global_node_pose, global_submap_pose, @@ -124,7 +124,7 @@ void ConstraintBuilder3D::MaybeAddGlobalConstraint( auto* const constraint = &constraints_.back(); const auto* scan_matcher = DispatchScanMatcherConstruction(submap_id, submap_nodes, submap); - auto constraint_task = common::make_unique(); + auto constraint_task = absl::make_unique(); constraint_task->SetWorkItem([=]() EXCLUDES(mutex_) { ComputeConstraint(submap_id, node_id, true, /* match_full_submap */ constant_data, @@ -147,7 +147,7 @@ void ConstraintBuilder3D::NotifyEndOfNode() { }); auto finish_node_task_handle = thread_pool_->Schedule(std::move(finish_node_task_)); - finish_node_task_ = common::make_unique(); + finish_node_task_ = absl::make_unique(); when_done_task_->AddDependency(finish_node_task_handle); ++num_started_nodes_; } @@ -157,12 +157,11 @@ void ConstraintBuilder3D::WhenDone( common::MutexLocker locker(&mutex_); CHECK(when_done_ == nullptr); // TODO(gaschler): Consider using just std::function, it can also be empty. - when_done_ = - common::make_unique>(callback); + when_done_ = absl::make_unique>(callback); CHECK(when_done_task_ != nullptr); when_done_task_->SetWorkItem([this] { RunWhenDoneCallback(); }); thread_pool_->Schedule(std::move(when_done_task_)); - when_done_task_ = common::make_unique(); + when_done_task_ = absl::make_unique(); } const ConstraintBuilder3D::SubmapScanMatcher* @@ -179,11 +178,11 @@ ConstraintBuilder3D::DispatchScanMatcherConstruction( &submap->low_resolution_hybrid_grid(); auto& scan_matcher_options = options_.fast_correlative_scan_matcher_options_3d(); - auto scan_matcher_task = common::make_unique(); + auto scan_matcher_task = absl::make_unique(); scan_matcher_task->SetWorkItem( [&submap_scan_matcher, &scan_matcher_options, submap_nodes]() { submap_scan_matcher.fast_correlative_scan_matcher = - common::make_unique( + absl::make_unique( *submap_scan_matcher.high_resolution_hybrid_grid, submap_scan_matcher.low_resolution_hybrid_grid, submap_nodes, scan_matcher_options); diff --git a/cartographer/mapping/internal/constraints/constraint_builder_3d_test.cc b/cartographer/mapping/internal/constraints/constraint_builder_3d_test.cc index d849509..acb44ca 100644 --- a/cartographer/mapping/internal/constraints/constraint_builder_3d_test.cc +++ b/cartographer/mapping/internal/constraints/constraint_builder_3d_test.cc @@ -48,7 +48,7 @@ class ConstraintBuilder3DTest : public ::testing::Test { POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.min_low_resolution_score = 0 POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.min_rotational_score = 0 return POSE_GRAPH.constraint_builder)text"); - constraint_builder_ = common::make_unique( + constraint_builder_ = absl::make_unique( CreateConstraintBuilderOptions(constraint_builder_parameters.get()), &thread_pool_); } diff --git a/cartographer/mapping/internal/global_trajectory_builder.cc b/cartographer/mapping/internal/global_trajectory_builder.cc index 03f946b..3260f05 100644 --- a/cartographer/mapping/internal/global_trajectory_builder.cc +++ b/cartographer/mapping/internal/global_trajectory_builder.cc @@ -18,7 +18,7 @@ #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/time.h" #include "cartographer/mapping/local_slam_result_data.h" #include "cartographer/metrics/family_factory.h" @@ -69,7 +69,7 @@ class GlobalTrajectoryBuilder : public mapping::TrajectoryBuilderInterface { matching_result->insertion_result->constant_data, trajectory_id_, matching_result->insertion_result->insertion_submaps); CHECK_EQ(node_id.trajectory_id, trajectory_id_); - insertion_result = common::make_unique(InsertionResult{ + insertion_result = absl::make_unique(InsertionResult{ node_id, matching_result->insertion_result->constant_data, std::vector>( matching_result->insertion_result->insertion_submaps.begin(), @@ -136,7 +136,7 @@ std::unique_ptr CreateGlobalTrajectoryBuilder2D( const int trajectory_id, mapping::PoseGraph2D* const pose_graph, const TrajectoryBuilderInterface::LocalSlamResultCallback& local_slam_result_callback) { - return common::make_unique< + return absl::make_unique< GlobalTrajectoryBuilder>( std::move(local_trajectory_builder), trajectory_id, pose_graph, local_slam_result_callback); @@ -147,7 +147,7 @@ std::unique_ptr CreateGlobalTrajectoryBuilder3D( const int trajectory_id, mapping::PoseGraph3D* const pose_graph, const TrajectoryBuilderInterface::LocalSlamResultCallback& local_slam_result_callback) { - return common::make_unique< + return absl::make_unique< GlobalTrajectoryBuilder>( std::move(local_trajectory_builder), trajectory_id, pose_graph, local_slam_result_callback); diff --git a/cartographer/mapping/internal/optimization/optimization_problem_2d.cc b/cartographer/mapping/internal/optimization/optimization_problem_2d.cc index 2fbcc2d..96d7cfe 100644 --- a/cartographer/mapping/internal/optimization/optimization_problem_2d.cc +++ b/cartographer/mapping/internal/optimization/optimization_problem_2d.cc @@ -120,7 +120,7 @@ void AddLandmarkCostFunctions( C_landmarks->emplace( landmark_id, CeresPose(starting_point, nullptr /* translation_parametrization */, - common::make_unique(), + absl::make_unique(), problem)); if (freeze_landmarks) { problem->SetParameterBlockConstant( @@ -336,12 +336,12 @@ std::unique_ptr OptimizationProblem2D::InterpolateOdometry( } if (it == odometry_data_.BeginOfTrajectory(trajectory_id)) { if (it->time == time) { - return common::make_unique(it->pose); + return absl::make_unique(it->pose); } return nullptr; } const auto prev_it = std::prev(it); - return common::make_unique( + return absl::make_unique( Interpolate(transform::TimestampedTransform{prev_it->time, prev_it->pose}, transform::TimestampedTransform{it->time, it->pose}, time) .transform); @@ -362,7 +362,7 @@ OptimizationProblem2D::CalculateOdometryBetweenNodes( first_node_odometry->inverse() * (*second_node_odometry) * transform::Rigid3d::Rotation( second_node_data.gravity_alignment.inverse()); - return common::make_unique(relative_odometry); + return absl::make_unique(relative_odometry); } } return nullptr; diff --git a/cartographer/mapping/internal/optimization/optimization_problem_3d.cc b/cartographer/mapping/internal/optimization/optimization_problem_3d.cc index 0b525b7..d46c16d 100644 --- a/cartographer/mapping/internal/optimization/optimization_problem_3d.cc +++ b/cartographer/mapping/internal/optimization/optimization_problem_3d.cc @@ -26,8 +26,8 @@ #include #include "Eigen/Core" +#include "absl/memory/memory.h" #include "cartographer/common/ceres_solver_options.h" -#include "cartographer/common/make_unique.h" #include "cartographer/common/math.h" #include "cartographer/common/time.h" #include "cartographer/mapping/internal/3d/imu_integration.h" @@ -63,12 +63,12 @@ std::unique_ptr Interpolate( } if (it == map_by_time.BeginOfTrajectory(trajectory_id)) { if (it->time == time) { - return common::make_unique(it->pose); + return absl::make_unique(it->pose); } return nullptr; } const auto prev_it = std::prev(it); - return common::make_unique( + return absl::make_unique( Interpolate(transform::TimestampedTransform{prev_it->time, prev_it->pose}, transform::TimestampedTransform{it->time, it->pose}, time) .transform); @@ -85,13 +85,13 @@ std::unique_ptr Interpolate( } if (it == map_by_time.BeginOfTrajectory(trajectory_id)) { if (it->time == time) { - return common::make_unique(it->pose.value()); + return absl::make_unique(it->pose.value()); } return nullptr; } const auto prev_it = std::prev(it); if (prev_it->pose.has_value()) { - return common::make_unique( + return absl::make_unique( Interpolate(transform::TimestampedTransform{prev_it->time, prev_it->pose.value()}, transform::TimestampedTransform{it->time, it->pose.value()}, @@ -164,7 +164,7 @@ void AddLandmarkCostFunctions( C_landmarks->emplace( landmark_id, CeresPose(starting_point, nullptr /* translation_parametrization */, - common::make_unique(), + absl::make_unique(), problem)); if (freeze_landmarks) { problem->SetParameterBlockConstant( @@ -279,7 +279,7 @@ void OptimizationProblem3D::Solve( const auto translation_parameterization = [this]() -> std::unique_ptr { return options_.fix_z_in_3d() - ? common::make_unique( + ? absl::make_unique( 3, std::vector{2}) : nullptr; }; @@ -302,7 +302,7 @@ void OptimizationProblem3D::Solve( submap_id_data.id, CeresPose(submap_id_data.data.global_pose, translation_parameterization(), - common::make_unique>(), &problem)); problem.SetParameterBlockConstant( @@ -312,7 +312,7 @@ void OptimizationProblem3D::Solve( submap_id_data.id, CeresPose(submap_id_data.data.global_pose, translation_parameterization(), - common::make_unique(), + absl::make_unique(), &problem)); } if (frozen) { @@ -328,7 +328,7 @@ void OptimizationProblem3D::Solve( C_nodes.Insert( node_id_data.id, CeresPose(node_id_data.data.global_pose, translation_parameterization(), - common::make_unique(), + absl::make_unique(), &problem)); if (frozen) { problem.SetParameterBlockConstant(C_nodes.at(node_id_data.id).rotation()); @@ -543,7 +543,7 @@ void OptimizationProblem3D::Solve( transform::GetYaw(fixed_frame_pose_in_map.rotation()), Eigen::Vector3d::UnitZ())), nullptr, - common::make_unique>(), &problem)); fixed_frame_pose_initialized = true; @@ -611,7 +611,7 @@ OptimizationProblem3D::CalculateOdometryBetweenNodes( if (first_node_odometry != nullptr && second_node_odometry != nullptr) { const transform::Rigid3d relative_odometry = first_node_odometry->inverse() * (*second_node_odometry); - return common::make_unique(relative_odometry); + return absl::make_unique(relative_odometry); } } return nullptr; diff --git a/cartographer/mapping/internal/range_data_collator.cc b/cartographer/mapping/internal/range_data_collator.cc index d6ef0ca..59f74ec 100644 --- a/cartographer/mapping/internal/range_data_collator.cc +++ b/cartographer/mapping/internal/range_data_collator.cc @@ -18,7 +18,7 @@ #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/mapping/local_slam_result_data.h" #include "glog/logging.h" diff --git a/cartographer/mapping/internal/range_data_collator.h b/cartographer/mapping/internal/range_data_collator.h index 68f3f48..8328828 100644 --- a/cartographer/mapping/internal/range_data_collator.h +++ b/cartographer/mapping/internal/range_data_collator.h @@ -19,7 +19,7 @@ #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/sensor/timed_point_cloud_data.h" namespace cartographer { diff --git a/cartographer/mapping/internal/testing/test_helpers.cc b/cartographer/mapping/internal/testing/test_helpers.cc index 18389be..d0468ab 100644 --- a/cartographer/mapping/internal/testing/test_helpers.cc +++ b/cartographer/mapping/internal/testing/test_helpers.cc @@ -16,10 +16,10 @@ #include "cartographer/mapping/internal/testing/test_helpers.h" +#include "absl/memory/memory.h" #include "cartographer/common/config.h" #include "cartographer/common/configuration_file_resolver.h" #include "cartographer/common/lua_parameter_dictionary_test_helpers.h" -#include "cartographer/common/make_unique.h" #include "cartographer/sensor/timed_point_cloud_data.h" #include "cartographer/transform/transform.h" @@ -29,12 +29,12 @@ namespace testing { std::unique_ptr<::cartographer::common::LuaParameterDictionary> ResolveLuaParameters(const std::string& lua_code) { - auto file_resolver = ::cartographer::common::make_unique< - ::cartographer::common::ConfigurationFileResolver>( - std::vector{ - std::string(::cartographer::common::kSourceDirectory) + - "/configuration_files"}); - return common::make_unique<::cartographer::common::LuaParameterDictionary>( + auto file_resolver = + absl::make_unique<::cartographer::common::ConfigurationFileResolver>( + std::vector{ + std::string(::cartographer::common::kSourceDirectory) + + "/configuration_files"}); + return absl::make_unique<::cartographer::common::LuaParameterDictionary>( lua_code, std::move(file_resolver)); } diff --git a/cartographer/mapping/map_builder.cc b/cartographer/mapping/map_builder.cc index 44d87bc..9070ab9 100644 --- a/cartographer/mapping/map_builder.cc +++ b/cartographer/mapping/map_builder.cc @@ -16,7 +16,7 @@ #include "cartographer/mapping/map_builder.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/time.h" #include "cartographer/io/internal/mapping_state_serialization.h" #include "cartographer/io/proto_stream.h" @@ -60,12 +60,12 @@ void MaybeAddPureLocalizationTrimmer( LOG(WARNING) << "'TrajectoryBuilderOptions::pure_localization' field is deprecated. " "Use 'TrajectoryBuilderOptions::pure_localization_trimmer' instead."; - pose_graph->AddTrimmer(common::make_unique( + pose_graph->AddTrimmer(absl::make_unique( trajectory_id, 3 /* max_submaps_to_keep */)); return; } if (trajectory_options.has_pure_localization_trimmer()) { - pose_graph->AddTrimmer(common::make_unique( + pose_graph->AddTrimmer(absl::make_unique( trajectory_id, trajectory_options.pure_localization_trimmer().max_submaps_to_keep())); } @@ -94,23 +94,23 @@ MapBuilder::MapBuilder(const proto::MapBuilderOptions& options) CHECK(options.use_trajectory_builder_2d() ^ options.use_trajectory_builder_3d()); if (options.use_trajectory_builder_2d()) { - pose_graph_ = common::make_unique( + pose_graph_ = absl::make_unique( options_.pose_graph_options(), - common::make_unique( + absl::make_unique( options_.pose_graph_options().optimization_problem_options()), &thread_pool_); } if (options.use_trajectory_builder_3d()) { - pose_graph_ = common::make_unique( + pose_graph_ = absl::make_unique( options_.pose_graph_options(), - common::make_unique( + absl::make_unique( options_.pose_graph_options().optimization_problem_options()), &thread_pool_); } if (options.collate_by_trajectory()) { - sensor_collator_ = common::make_unique(); + sensor_collator_ = absl::make_unique(); } else { - sensor_collator_ = common::make_unique(); + sensor_collator_ = absl::make_unique(); } } @@ -122,40 +122,38 @@ int MapBuilder::AddTrajectoryBuilder( if (options_.use_trajectory_builder_3d()) { std::unique_ptr local_trajectory_builder; if (trajectory_options.has_trajectory_builder_3d_options()) { - local_trajectory_builder = common::make_unique( + local_trajectory_builder = absl::make_unique( trajectory_options.trajectory_builder_3d_options(), SelectRangeSensorIds(expected_sensor_ids)); } DCHECK(dynamic_cast(pose_graph_.get())); - trajectory_builders_.push_back( - common::make_unique( - trajectory_options, sensor_collator_.get(), trajectory_id, - expected_sensor_ids, - CreateGlobalTrajectoryBuilder3D( - std::move(local_trajectory_builder), trajectory_id, - static_cast(pose_graph_.get()), - local_slam_result_callback))); + trajectory_builders_.push_back(absl::make_unique( + trajectory_options, sensor_collator_.get(), trajectory_id, + expected_sensor_ids, + CreateGlobalTrajectoryBuilder3D( + std::move(local_trajectory_builder), trajectory_id, + static_cast(pose_graph_.get()), + local_slam_result_callback))); } else { std::unique_ptr local_trajectory_builder; if (trajectory_options.has_trajectory_builder_2d_options()) { - local_trajectory_builder = common::make_unique( + local_trajectory_builder = absl::make_unique( trajectory_options.trajectory_builder_2d_options(), SelectRangeSensorIds(expected_sensor_ids)); } DCHECK(dynamic_cast(pose_graph_.get())); - trajectory_builders_.push_back( - common::make_unique( - trajectory_options, sensor_collator_.get(), trajectory_id, - expected_sensor_ids, - CreateGlobalTrajectoryBuilder2D( - std::move(local_trajectory_builder), trajectory_id, - static_cast(pose_graph_.get()), - local_slam_result_callback))); + trajectory_builders_.push_back(absl::make_unique( + trajectory_options, sensor_collator_.get(), trajectory_id, + expected_sensor_ids, + CreateGlobalTrajectoryBuilder2D( + std::move(local_trajectory_builder), trajectory_id, + static_cast(pose_graph_.get()), + local_slam_result_callback))); if (trajectory_options.has_overlapping_submaps_trimmer_2d()) { const auto& trimmer_options = trajectory_options.overlapping_submaps_trimmer_2d(); - pose_graph_->AddTrimmer(common::make_unique( + pose_graph_->AddTrimmer(absl::make_unique( trimmer_options.fresh_submaps_count(), trimmer_options.min_covered_area() / common::Pow2(trajectory_options.trajectory_builder_2d_options() diff --git a/cartographer/mapping/map_builder_test.cc b/cartographer/mapping/map_builder_test.cc index 6bf9190..9474742 100644 --- a/cartographer/mapping/map_builder_test.cc +++ b/cartographer/mapping/map_builder_test.cc @@ -62,7 +62,7 @@ class MapBuilderTest : public ::testing::Test { } void BuildMapBuilder() { - map_builder_ = common::make_unique(map_builder_options_); + map_builder_ = absl::make_unique(map_builder_options_); } void SetOptionsTo3D() { diff --git a/cartographer/mapping/pose_extrapolator.cc b/cartographer/mapping/pose_extrapolator.cc index 6898103..64aeda7 100644 --- a/cartographer/mapping/pose_extrapolator.cc +++ b/cartographer/mapping/pose_extrapolator.cc @@ -18,7 +18,7 @@ #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/transform/transform.h" #include "glog/logging.h" @@ -35,11 +35,11 @@ PoseExtrapolator::PoseExtrapolator(const common::Duration pose_queue_duration, std::unique_ptr PoseExtrapolator::InitializeWithImu( const common::Duration pose_queue_duration, const double imu_gravity_time_constant, const sensor::ImuData& imu_data) { - auto extrapolator = common::make_unique( + auto extrapolator = absl::make_unique( pose_queue_duration, imu_gravity_time_constant); extrapolator->AddImuData(imu_data); extrapolator->imu_tracker_ = - common::make_unique(imu_gravity_time_constant, imu_data.time); + absl::make_unique(imu_gravity_time_constant, imu_data.time); extrapolator->imu_tracker_->AddImuLinearAccelerationObservation( imu_data.linear_acceleration); extrapolator->imu_tracker_->AddImuAngularVelocityObservation( @@ -73,7 +73,7 @@ void PoseExtrapolator::AddPose(const common::Time time, tracker_start = std::min(tracker_start, imu_data_.front().time); } imu_tracker_ = - common::make_unique(gravity_time_constant_, tracker_start); + absl::make_unique(gravity_time_constant_, tracker_start); } timed_pose_queue_.push_back(TimedPose{time, pose}); while (timed_pose_queue_.size() > 2 && @@ -84,8 +84,8 @@ void PoseExtrapolator::AddPose(const common::Time time, AdvanceImuTracker(time, imu_tracker_.get()); TrimImuData(); TrimOdometryData(); - odometry_imu_tracker_ = common::make_unique(*imu_tracker_); - extrapolation_imu_tracker_ = common::make_unique(*imu_tracker_); + odometry_imu_tracker_ = absl::make_unique(*imu_tracker_); + extrapolation_imu_tracker_ = absl::make_unique(*imu_tracker_); } void PoseExtrapolator::AddImuData(const sensor::ImuData& imu_data) { diff --git a/cartographer/mapping/pose_extrapolator_test.cc b/cartographer/mapping/pose_extrapolator_test.cc index bb00d33..7aafe29 100644 --- a/cartographer/mapping/pose_extrapolator_test.cc +++ b/cartographer/mapping/pose_extrapolator_test.cc @@ -17,7 +17,7 @@ #include "cartographer/mapping/pose_extrapolator.h" #include "Eigen/Geometry" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "gtest/gtest.h" #include "transform/rigid_transform_test_helpers.h" diff --git a/cartographer/mapping/probability_values.cc b/cartographer/mapping/probability_values.cc index 8643853..a30f96e 100644 --- a/cartographer/mapping/probability_values.cc +++ b/cartographer/mapping/probability_values.cc @@ -16,7 +16,7 @@ #include "cartographer/mapping/probability_values.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" namespace cartographer { namespace mapping { @@ -37,7 +37,7 @@ float SlowValueToBoundedFloat(const uint16 value, const uint16 unknown_value, std::unique_ptr> PrecomputeValueToBoundedFloat( const uint16 unknown_value, const float unknown_result, const float lower_bound, const float upper_bound) { - auto result = common::make_unique>(); + auto result = absl::make_unique>(); // Repeat two times, so that both values with and without the update marker // can be converted to a probability. for (int repeat = 0; repeat != 2; ++repeat) { diff --git a/cartographer/mapping/trajectory_builder_interface.h b/cartographer/mapping/trajectory_builder_interface.h index 2cf93f7..1173d8e 100644 --- a/cartographer/mapping/trajectory_builder_interface.h +++ b/cartographer/mapping/trajectory_builder_interface.h @@ -21,8 +21,8 @@ #include #include +#include "absl/memory/memory.h" #include "cartographer/common/lua_parameter_dictionary.h" -#include "cartographer/common/make_unique.h" #include "cartographer/common/port.h" #include "cartographer/common/time.h" #include "cartographer/mapping/proto/trajectory_builder_options.pb.h" diff --git a/cartographer/mapping/value_conversion_tables.cc b/cartographer/mapping/value_conversion_tables.cc index bd978bc..9800015 100644 --- a/cartographer/mapping/value_conversion_tables.cc +++ b/cartographer/mapping/value_conversion_tables.cc @@ -16,7 +16,7 @@ #include "cartographer/mapping/value_conversion_tables.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "glog/logging.h" namespace cartographer { @@ -39,7 +39,7 @@ float SlowValueToBoundedFloat(const uint16 value, const uint16 unknown_value, std::unique_ptr> PrecomputeValueToBoundedFloat( const uint16 unknown_value, const float unknown_result, const float lower_bound, const float upper_bound) { - auto result = common::make_unique>(); + auto result = absl::make_unique>(); size_t num_values = std::numeric_limits::max() + 1; result->reserve(num_values); for (size_t value = 0; value != num_values; ++value) { diff --git a/cartographer/pose_graph/constraint/acceleration_constraint_3d.cc b/cartographer/pose_graph/constraint/acceleration_constraint_3d.cc index 77076a0..5972197 100644 --- a/cartographer/pose_graph/constraint/acceleration_constraint_3d.cc +++ b/cartographer/pose_graph/constraint/acceleration_constraint_3d.cc @@ -16,7 +16,7 @@ #include "cartographer/pose_graph/constraint/acceleration_constraint_3d.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/utils.h" namespace cartographer { @@ -56,7 +56,7 @@ AccelerationConstraint3D::AccelerationConstraint3D( third_(proto.third()), imu_(proto.imu_calibration()), cost_(new AccelerationCost3D(proto.parameters())), - ceres_cost_(common::make_unique(cost_)) {} + ceres_cost_(absl::make_unique(cost_)) {} void AccelerationConstraint3D::AddToOptimizer(Nodes* nodes, ceres::Problem* problem) const { diff --git a/cartographer/pose_graph/constraint/cost_function/relative_pose_cost_2d_test.cc b/cartographer/pose_graph/constraint/cost_function/relative_pose_cost_2d_test.cc index 6db8ff6..cf1a23f 100644 --- a/cartographer/pose_graph/constraint/cost_function/relative_pose_cost_2d_test.cc +++ b/cartographer/pose_graph/constraint/cost_function/relative_pose_cost_2d_test.cc @@ -16,7 +16,7 @@ #include "cartographer/pose_graph/constraint/cost_function/relative_pose_cost_2d.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/testing/test_helpers.h" #include "ceres/gradient_checker.h" @@ -50,7 +50,7 @@ constexpr char kParameters[] = R"PROTO( class RelativePoseCost2DTest : public ::testing::Test { public: RelativePoseCost2DTest() - : relative_pose_cost_2d_(common::make_unique( + : relative_pose_cost_2d_(absl::make_unique( ParseProto(kParameters))) { for (int i = 0; i < kParameterBlocksCount; ++i) { jacobian_ptrs_[i] = jacobian_[i].data(); diff --git a/cartographer/pose_graph/constraint/interpolated_relative_pose_constraint_2d.cc b/cartographer/pose_graph/constraint/interpolated_relative_pose_constraint_2d.cc index 26a43c8..39287f2 100644 --- a/cartographer/pose_graph/constraint/interpolated_relative_pose_constraint_2d.cc +++ b/cartographer/pose_graph/constraint/interpolated_relative_pose_constraint_2d.cc @@ -16,7 +16,7 @@ #include "cartographer/pose_graph/constraint/interpolated_relative_pose_constraint_2d.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/utils.h" namespace cartographer { @@ -52,7 +52,7 @@ InterpolatedRelativePoseConstraint2D::InterpolatedRelativePoseConstraint2D( first_end_(proto.first_end()), second_(proto.second()), cost_(new InterpolatedRelativePoseCost2D(proto.parameters())), - ceres_cost_(common::make_unique(cost_)) {} + ceres_cost_(absl::make_unique(cost_)) {} void InterpolatedRelativePoseConstraint2D::AddToOptimizer( Nodes* nodes, ceres::Problem* problem) const { diff --git a/cartographer/pose_graph/constraint/interpolated_relative_pose_constraint_3d.cc b/cartographer/pose_graph/constraint/interpolated_relative_pose_constraint_3d.cc index d81d84e..3c3cbf1 100644 --- a/cartographer/pose_graph/constraint/interpolated_relative_pose_constraint_3d.cc +++ b/cartographer/pose_graph/constraint/interpolated_relative_pose_constraint_3d.cc @@ -16,7 +16,7 @@ #include "cartographer/pose_graph/constraint/interpolated_relative_pose_constraint_3d.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/utils.h" namespace cartographer { @@ -44,7 +44,7 @@ InterpolatedRelativePoseConstraint3D::InterpolatedRelativePoseConstraint3D( first_end_(proto.first_end()), second_(proto.second()), cost_(new InterpolatedRelativePoseCost3D(proto.parameters())), - ceres_cost_(common::make_unique(cost_)) {} + ceres_cost_(absl::make_unique(cost_)) {} void InterpolatedRelativePoseConstraint3D::AddToOptimizer( Nodes* nodes, ceres::Problem* problem) const { diff --git a/cartographer/pose_graph/constraint/loss_function/loss_function.cc b/cartographer/pose_graph/constraint/loss_function/loss_function.cc index c501516..6620520 100644 --- a/cartographer/pose_graph/constraint/loss_function/loss_function.cc +++ b/cartographer/pose_graph/constraint/loss_function/loss_function.cc @@ -16,7 +16,7 @@ #include "cartographer/pose_graph/constraint/loss_function/loss_function.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" namespace cartographer { namespace pose_graph { @@ -26,7 +26,7 @@ std::unique_ptr CeresLossFromProto( const proto::LossFunction& proto) { switch (proto.Type_case()) { case proto::LossFunction::kHuberLoss: - return common::make_unique(proto.huber_loss().scale()); + return absl::make_unique(proto.huber_loss().scale()); case proto::LossFunction::kQuadraticLoss: return nullptr; default: diff --git a/cartographer/pose_graph/constraint/relative_pose_constraint_2d.cc b/cartographer/pose_graph/constraint/relative_pose_constraint_2d.cc index a1761ca..39da926 100644 --- a/cartographer/pose_graph/constraint/relative_pose_constraint_2d.cc +++ b/cartographer/pose_graph/constraint/relative_pose_constraint_2d.cc @@ -16,7 +16,7 @@ #include "cartographer/pose_graph/constraint/relative_pose_constraint_2d.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/utils.h" namespace cartographer { @@ -28,8 +28,7 @@ RelativePoseConstraint2D::RelativePoseConstraint2D( : Constraint(id, loss_function_proto), first_(proto.first()), second_(proto.second()), - ceres_cost_(common::make_unique(proto.parameters())) { -} + ceres_cost_(absl::make_unique(proto.parameters())) {} // TODO(pifon): Add a test. void RelativePoseConstraint2D::AddToOptimizer(Nodes* nodes, diff --git a/cartographer/pose_graph/constraint/relative_pose_constraint_3d.cc b/cartographer/pose_graph/constraint/relative_pose_constraint_3d.cc index 4bd7527..ee5f177 100644 --- a/cartographer/pose_graph/constraint/relative_pose_constraint_3d.cc +++ b/cartographer/pose_graph/constraint/relative_pose_constraint_3d.cc @@ -16,7 +16,7 @@ #include "cartographer/pose_graph/constraint/relative_pose_constraint_3d.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/utils.h" namespace cartographer { @@ -43,7 +43,7 @@ RelativePoseConstraint3D::RelativePoseConstraint3D( first_(proto.first()), second_(proto.second()), cost_(new RelativePoseCost3D(proto.parameters())), - ceres_cost_(common::make_unique(cost_)) {} + ceres_cost_(absl::make_unique(cost_)) {} void RelativePoseConstraint3D::AddToOptimizer(Nodes* nodes, ceres::Problem* problem) const { diff --git a/cartographer/pose_graph/constraint/rotation_constraint_3d.cc b/cartographer/pose_graph/constraint/rotation_constraint_3d.cc index f99ae7e..92d4338 100644 --- a/cartographer/pose_graph/constraint/rotation_constraint_3d.cc +++ b/cartographer/pose_graph/constraint/rotation_constraint_3d.cc @@ -16,7 +16,7 @@ #include "cartographer/pose_graph/constraint/rotation_constraint_3d.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/utils.h" namespace cartographer { @@ -41,7 +41,7 @@ RotationContraint3D::RotationContraint3D( second_(proto.second()), imu_calibration_(proto.imu_calibration()), cost_(new RotationCost3D(proto.parameters())), - ceres_cost_(common::make_unique(cost_)) {} + ceres_cost_(absl::make_unique(cost_)) {} void RotationContraint3D::AddToOptimizer(Nodes* nodes, ceres::Problem* problem) const { diff --git a/cartographer/pose_graph/optimizer/ceres_optimizer_test.cc b/cartographer/pose_graph/optimizer/ceres_optimizer_test.cc index a1579fc..db0ffcc 100644 --- a/cartographer/pose_graph/optimizer/ceres_optimizer_test.cc +++ b/cartographer/pose_graph/optimizer/ceres_optimizer_test.cc @@ -16,7 +16,7 @@ #include "cartographer/pose_graph/optimizer/ceres_optimizer.h" -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/pose_graph/constraint/relative_pose_constraint_2d.h" #include "cartographer/testing/test_helpers.h" @@ -76,7 +76,7 @@ TEST(CeresOptimizerTest, SmokeTest) { data.nodes.pose_2d_nodes.emplace( NodeId{"end_node", common::FromUniversal(1)}, GetPose2D(ParseProto(kEndNode))); - data.constraints.emplace_back(common::make_unique( + data.constraints.emplace_back(absl::make_unique( "constraint_1", ParseProto(R"(quadratic_loss: {})"), ParseProto(kRelativePose2D))); diff --git a/cartographer/sensor/data.h b/cartographer/sensor/data.h index 919dfdb..0bedbd2 100644 --- a/cartographer/sensor/data.h +++ b/cartographer/sensor/data.h @@ -17,7 +17,7 @@ #ifndef CARTOGRAPHER_MAPPING_DATA_H_ #define CARTOGRAPHER_MAPPING_DATA_H_ -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/time.h" #include "cartographer/transform/rigid_transform.h" diff --git a/cartographer/sensor/internal/collator_test.cc b/cartographer/sensor/internal/collator_test.cc index e68831c..e0f79b1 100644 --- a/cartographer/sensor/internal/collator_test.cc +++ b/cartographer/sensor/internal/collator_test.cc @@ -19,7 +19,7 @@ #include #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/time.h" #include "cartographer/sensor/imu_data.h" #include "cartographer/sensor/internal/test_helpers.h" diff --git a/cartographer/sensor/internal/dispatchable.h b/cartographer/sensor/internal/dispatchable.h index 50eadbb..5aae9de 100644 --- a/cartographer/sensor/internal/dispatchable.h +++ b/cartographer/sensor/internal/dispatchable.h @@ -43,7 +43,7 @@ class Dispatchable : public Data { template std::unique_ptr> MakeDispatchable( const std::string &sensor_id, const DataType &data) { - return common::make_unique>(sensor_id, data); + return absl::make_unique>(sensor_id, data); } } // namespace sensor diff --git a/cartographer/sensor/internal/ordered_multi_queue.cc b/cartographer/sensor/internal/ordered_multi_queue.cc index 39d7833..26c8ee1 100644 --- a/cartographer/sensor/internal/ordered_multi_queue.cc +++ b/cartographer/sensor/internal/ordered_multi_queue.cc @@ -20,7 +20,7 @@ #include #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "glog/logging.h" namespace cartographer { diff --git a/cartographer/sensor/internal/ordered_multi_queue_test.cc b/cartographer/sensor/internal/ordered_multi_queue_test.cc index 66557a5..196707d 100644 --- a/cartographer/sensor/internal/ordered_multi_queue_test.cc +++ b/cartographer/sensor/internal/ordered_multi_queue_test.cc @@ -18,7 +18,7 @@ #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "gtest/gtest.h" namespace cartographer { diff --git a/cartographer/sensor/internal/test_helpers.h b/cartographer/sensor/internal/test_helpers.h index d4d1f9a..d3bf3d2 100644 --- a/cartographer/sensor/internal/test_helpers.h +++ b/cartographer/sensor/internal/test_helpers.h @@ -20,7 +20,7 @@ #include #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/time.h" #include "cartographer/sensor/collator_interface.h" #include "cartographer/sensor/imu_data.h" diff --git a/cartographer/sensor/internal/trajectory_collator_test.cc b/cartographer/sensor/internal/trajectory_collator_test.cc index ace6f88..7f35eb8 100644 --- a/cartographer/sensor/internal/trajectory_collator_test.cc +++ b/cartographer/sensor/internal/trajectory_collator_test.cc @@ -19,7 +19,7 @@ #include #include -#include "cartographer/common/make_unique.h" +#include "absl/memory/memory.h" #include "cartographer/common/time.h" #include "cartographer/sensor/imu_data.h" #include "cartographer/sensor/internal/test_helpers.h"