[ABSL] Purge common::make_unique. (#1340)

master
Alexander Belyaev 2018-07-27 19:43:35 +02:00 committed by GitHub
parent 4990d4d5e9
commit 5b44305ea3
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
128 changed files with 480 additions and 486 deletions

View File

@ -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"],

View File

@ -34,7 +34,7 @@ namespace cartographer {
namespace cloud {
namespace {
using common::make_unique;
using absl::make_unique;
constexpr int kConnectionTimeoutInSeconds = 10;
} // namespace

View File

@ -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<std::thread>(
receive_local_slam_results_thread_ = absl::make_unique<std::thread>(
[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<handlers::AddRangefinderDataSignature>>(
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<async_grpc::Client<handlers::AddImuDataSignature>>(
absl::make_unique<async_grpc::Client<handlers::AddImuDataSignature>>(
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<handlers::AddOdometryDataSignature>>(
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<handlers::AddFixedFramePoseDataSignature>>(
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<handlers::AddLandmarkDataSignature>>(
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<InsertionResult>(
? absl::make_unique<InsertionResult>(
InsertionResult{mapping::NodeId{
response.insertion_result().node_id().trajectory_id(),
response.insertion_result().node_id().node_index()}})

View File

@ -138,42 +138,42 @@ class ClientServerTest : public ::testing::Test {
}
void InitializeRealServer() {
auto map_builder = common::make_unique<MapBuilder>(
auto map_builder = absl::make_unique<MapBuilder>(
map_builder_server_options_.map_builder_options());
server_ = common::make_unique<MapBuilderServer>(map_builder_server_options_,
std::move(map_builder));
server_ = absl::make_unique<MapBuilderServer>(map_builder_server_options_,
std::move(map_builder));
EXPECT_TRUE(server_ != nullptr);
}
void InitializeRealUploadingServer() {
auto map_builder = common::make_unique<MapBuilder>(
auto map_builder = absl::make_unique<MapBuilder>(
uploading_map_builder_server_options_.map_builder_options());
uploading_server_ = common::make_unique<MapBuilderServer>(
uploading_server_ = absl::make_unique<MapBuilderServer>(
uploading_map_builder_server_options_, std::move(map_builder));
EXPECT_TRUE(uploading_server_ != nullptr);
}
void InitializeServerWithMockMapBuilder() {
auto mock_map_builder = common::make_unique<MockMapBuilder>();
auto mock_map_builder = absl::make_unique<MockMapBuilder>();
mock_map_builder_ = mock_map_builder.get();
mock_pose_graph_ = common::make_unique<MockPoseGraph>();
mock_pose_graph_ = absl::make_unique<MockPoseGraph>();
EXPECT_CALL(*mock_map_builder_, pose_graph())
.WillOnce(::testing::Return(mock_pose_graph_.get()));
EXPECT_CALL(*mock_pose_graph_, SetGlobalSlamOptimizationCallback(_));
server_ = common::make_unique<MapBuilderServer>(
map_builder_server_options_, std::move(mock_map_builder));
server_ = absl::make_unique<MapBuilderServer>(map_builder_server_options_,
std::move(mock_map_builder));
EXPECT_TRUE(server_ != nullptr);
mock_trajectory_builder_ = common::make_unique<MockTrajectoryBuilder>();
mock_trajectory_builder_ = absl::make_unique<MockTrajectoryBuilder>();
}
void InitializeStub() {
stub_ = common::make_unique<MapBuilderStub>(
stub_ = absl::make_unique<MapBuilderStub>(
map_builder_server_options_.server_address(), kClientId);
EXPECT_TRUE(stub_ != nullptr);
}
void InitializeStubForUploadingServer() {
stub_for_uploading_server_ = common::make_unique<MapBuilderStub>(
stub_for_uploading_server_ = absl::make_unique<MapBuilderStub>(
uploading_map_builder_server_options_.server_address(), kClientId);
EXPECT_TRUE(stub_for_uploading_server_ != nullptr);
}

View File

@ -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<MapBuilderContextInterface>()
->local_trajectory_uploader()) {
auto sensor_data = common::make_unique<proto::SensorData>();
auto sensor_data = absl::make_unique<proto::SensorData>();
*sensor_data->mutable_sensor_metadata() = request.sensor_metadata();
*sensor_data->mutable_fixed_frame_pose_data() =
request.fixed_frame_pose_data();

View File

@ -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<MapBuilderContextInterface>()
->local_trajectory_uploader()) {
auto sensor_data = common::make_unique<proto::SensorData>();
auto sensor_data = absl::make_unique<proto::SensorData>();
*sensor_data->mutable_sensor_metadata() = request.sensor_metadata();
*sensor_data->mutable_imu_data() = request.imu_data();
GetUnsynchronizedContext<MapBuilderContextInterface>()

View File

@ -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<MapBuilderContextInterface>()
->local_trajectory_uploader()) {
auto sensor_data = common::make_unique<proto::SensorData>();
auto sensor_data = absl::make_unique<proto::SensorData>();
*sensor_data->mutable_sensor_metadata() = request.sensor_metadata();
*sensor_data->mutable_landmark_data() = request.landmark_data();
GetUnsynchronizedContext<MapBuilderContextInterface>()

View File

@ -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<MapBuilderContextInterface>()
->local_trajectory_uploader()) {
auto sensor_data = common::make_unique<proto::SensorData>();
auto sensor_data = absl::make_unique<proto::SensorData>();
*sensor_data->mutable_sensor_metadata() = request.sensor_metadata();
*sensor_data->mutable_odometry_data() = request.odometry_data();
GetUnsynchronizedContext<MapBuilderContextInterface>()

View File

@ -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"

View File

@ -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<google::protobuf::Empty>());
Send(absl::make_unique<google::protobuf::Empty>());
}
} // namespace handlers

View File

@ -50,7 +50,7 @@ class AddSensorDataHandlerBase
virtual void OnSensorData(const SensorDataType& request) = 0;
void OnReadsDone() override {
this->template Send(common::make_unique<google::protobuf::Empty>());
this->template Send(absl::make_unique<google::protobuf::Empty>());
}
};

View File

@ -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<proto::AddTrajectoryResponse>();
auto response = absl::make_unique<proto::AddTrajectoryResponse>();
response->set_trajectory_id(trajectory_id);
Send(std::move(response));
}

View File

@ -74,7 +74,7 @@ class AddTrajectoryHandlerTest
public:
void SetUp() override {
testing::HandlerTest<AddTrajectorySignature, AddTrajectoryHandler>::SetUp();
mock_map_builder_ = common::make_unique<mapping::testing::MockMapBuilder>();
mock_map_builder_ = absl::make_unique<mapping::testing::MockMapBuilder>();
EXPECT_CALL(*mock_map_builder_context_,
GetLocalSlamResultCallbackForSubscriptions())
.WillOnce(Return(nullptr));

View File

@ -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<google::protobuf::Empty>());
Send(absl::make_unique<google::protobuf::Empty>());
}
} // namespace handlers

View File

@ -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<google::protobuf::Empty>());
Send(absl::make_unique<google::protobuf::Empty>());
}
} // namespace handlers

View File

@ -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<proto::GetAllSubmapPosesResponse>();
auto response = absl::make_unique<proto::GetAllSubmapPosesResponse>();
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());

View File

@ -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<proto::GetConstraintsResponse>();
auto response = absl::make_unique<proto::GetConstraintsResponse>();
response->mutable_constraints()->Reserve(constraints.size());
for (const auto& constraint : constraints) {
*response->add_constraints() = mapping::ToProto(constraint);

View File

@ -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<proto::GetLandmarkPosesResponse>();
auto response = absl::make_unique<proto::GetLandmarkPosesResponse>();
for (const auto& landmark_pose : landmark_poses) {
auto* landmark = response->add_landmark_poses();
landmark->set_landmark_id(landmark_pose.first);

View File

@ -28,8 +28,7 @@ namespace handlers {
void GetLocalToGlobalTransformHandler::OnRequest(
const proto::GetLocalToGlobalTransformRequest& request) {
auto response =
common::make_unique<proto::GetLocalToGlobalTransformResponse>();
auto response = absl::make_unique<proto::GetLocalToGlobalTransformResponse>();
auto local_to_global =
GetContext<MapBuilderContextInterface>()
->map_builder()

View File

@ -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<proto::GetSubmapResponse>();
auto response = absl::make_unique<proto::GetSubmapResponse>();
response->set_error_msg(
GetContext<MapBuilderContextInterface>()->map_builder().SubmapToProto(
mapping::SubmapId{request.submap_id().trajectory_id(),

View File

@ -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<proto::GetTrajectoryNodePosesResponse>();
auto response = absl::make_unique<proto::GetTrajectoryNodePosesResponse>();
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());

View File

@ -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<proto::GetTrajectoryStatesResponse>();
auto response = absl::make_unique<proto::GetTrajectoryStatesResponse>();
for (const auto& entry : trajectories_state) {
(*response->mutable_trajectories_state())[entry.first] =
ToProto(entry.second);

View File

@ -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<proto::IsTrajectoryFinishedResponse>();
auto response = absl::make_unique<proto::IsTrajectoryFinishedResponse>();
response->set_is_finished(
GetContext<MapBuilderContextInterface>()
->map_builder()

View File

@ -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<proto::IsTrajectoryFrozenResponse>();
auto response = absl::make_unique<proto::IsTrajectoryFrozenResponse>();
response->set_is_frozen(GetContext<MapBuilderContextInterface>()
->map_builder()
.pose_graph()

View File

@ -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<MapBuilderContextInterface>()->RegisterClientIdForTrajectory(
request.client_id(), entry.second);
}
auto response = common::make_unique<proto::LoadStateFromFileResponse>();
auto response = absl::make_unique<proto::LoadStateFromFileResponse>();
*response->mutable_trajectory_remapping() = ToProto(trajectory_remapping);
Send(std::move(response));
}

View File

@ -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<MapBuilderContextInterface>()->RegisterClientIdForTrajectory(
client_id_, entry.second);
}
auto response = common::make_unique<proto::LoadStateResponse>();
auto response = absl::make_unique<proto::LoadStateResponse>();
*response->mutable_trajectory_remapping() = ToProto(trajectory_remapping);
Send(std::move(response));
}

View File

@ -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<proto::ReceiveGlobalSlamOptimizationsResponse> GenerateResponse(
const std::map<int, mapping::SubmapId> &last_optimized_submap_ids,
const std::map<int, mapping::NodeId> &last_optimized_node_ids) {
auto response =
common::make_unique<proto::ReceiveGlobalSlamOptimizationsResponse>();
absl::make_unique<proto::ReceiveGlobalSlamOptimizationsResponse>();
for (const auto &entry : last_optimized_submap_ids) {
entry.second.ToProto(
&(*response->mutable_last_optimized_submap_ids())[entry.first]);

View File

@ -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<proto::ReceiveLocalSlamResultsResponse> GenerateResponse(
std::unique_ptr<MapBuilderContextInterface::LocalSlamResult>
local_slam_result) {
auto response = common::make_unique<proto::ReceiveLocalSlamResultsResponse>();
auto response = absl::make_unique<proto::ReceiveLocalSlamResultsResponse>();
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<MapBuilderContextInterface::LocalSlamSubscriptionId>(
absl::make_unique<MapBuilderContextInterface::LocalSlamSubscriptionId>(
subscription_id);
}

View File

@ -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<google::protobuf::Empty>());
Send(absl::make_unique<google::protobuf::Empty>());
}
} // namespace handlers

View File

@ -34,7 +34,7 @@ void SetLandmarkPoseHandler::OnRequest(
->SetLandmarkPose(
request.landmark_pose().landmark_id(),
transform::ToRigid3(request.landmark_pose().global_pose()));
Send(common::make_unique<google::protobuf::Empty>());
Send(absl::make_unique<google::protobuf::Empty>());
}
} // namespace handlers

View File

@ -35,7 +35,7 @@ void WriteStateHandler::OnRequest(const google::protobuf::Empty& request) {
return true;
}
auto response = common::make_unique<proto::WriteStateResponse>();
auto response = absl::make_unique<proto::WriteStateResponse>();
if (proto->GetTypeName() ==
"cartographer.mapping.proto.SerializationHeader") {
response->mutable_header()->CopyFrom(*proto);

View File

@ -19,6 +19,7 @@
#include <map>
#include <thread>
#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;

View File

@ -27,9 +27,9 @@ template <>
void MapBuilderContext<mapping::Submap2D>::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<Data>(
map_builder_server_->incoming_data_queue_.Push(absl::make_unique<Data>(
Data{trajectory_id,
common::make_unique<mapping::LocalSlamResult2D>(
absl::make_unique<mapping::LocalSlamResult2D>(
sensor_id, local_slam_result_data, &submap_controller_)}));
}
@ -37,9 +37,9 @@ template <>
void MapBuilderContext<mapping::Submap3D>::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<Data>(
map_builder_server_->incoming_data_queue_.Push(absl::make_unique<Data>(
Data{trajectory_id,
common::make_unique<mapping::LocalSlamResult3D>(
absl::make_unique<mapping::LocalSlamResult3D>(
sensor_id, local_slam_result_data, &submap_controller_)}));
}

View File

@ -104,7 +104,7 @@ template <class SubmapType>
void MapBuilderContext<SubmapType>::EnqueueSensorData(
int trajectory_id, std::unique_ptr<sensor::Data> data) {
map_builder_server_->incoming_data_queue_.Push(
common::make_unique<Data>(Data{trajectory_id, std::move(data)}));
absl::make_unique<Data>(Data{trajectory_id, std::move(data)}));
}
template <class SubmapType>

View File

@ -100,11 +100,11 @@ MapBuilderServer::MapBuilderServer(
if (map_builder_server_options.map_builder_options()
.use_trajectory_builder_2d()) {
grpc_server_->SetExecutionContext(
common::make_unique<MapBuilderContext<mapping::Submap2D>>(this));
absl::make_unique<MapBuilderContext<mapping::Submap2D>>(this));
} else if (map_builder_server_options.map_builder_options()
.use_trajectory_builder_3d()) {
grpc_server_->SetExecutionContext(
common::make_unique<MapBuilderContext<mapping::Submap3D>>(this));
absl::make_unique<MapBuilderContext<mapping::Submap3D>>(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<std::thread>(
slam_thread_ = absl::make_unique<std::thread>(
[this]() { this->ProcessSensorDataQueue(); });
}
@ -183,7 +183,7 @@ void MapBuilderServer::OnLocalSlamResult(
if (insertion_result &&
grpc_server_->GetUnsynchronizedContext<MapBuilderContextInterface>()
->local_trajectory_uploader()) {
auto sensor_data = common::make_unique<proto::SensorData>();
auto sensor_data = absl::make_unique<proto::SensorData>();
auto sensor_id =
grpc_server_->GetUnsynchronizedContext<MapBuilderContextInterface>()
->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<MapBuilderContextInterface::LocalSlamResult>(
absl::make_unique<MapBuilderContextInterface::LocalSlamResult>(
MapBuilderContextInterface::LocalSlamResult{
trajectory_id, time, local_pose, shared_range_data,
std::move(copy_of_insertion_result)}))) {

View File

@ -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 <typename HandlerConcept, typename HandlerType>
class HandlerTest : public Test {
public:
void SetUp() override {
test_server_ = common::make_unique<
test_server_ = absl::make_unique<
async_grpc::testing::RpcHandlerTestServer<HandlerConcept, HandlerType>>(
common::make_unique<MockMapBuilderContext>());
absl::make_unique<MockMapBuilderContext>());
mock_map_builder_context_ =
test_server_
->template GetUnsynchronizedContext<MockMapBuilderContext>();
mock_local_trajectory_uploader_ =
common::make_unique<MockLocalTrajectoryUploader>();
mock_map_builder_ = common::make_unique<mapping::testing::MockMapBuilder>();
mock_pose_graph_ = common::make_unique<mapping::testing::MockPoseGraph>();
absl::make_unique<MockLocalTrajectoryUploader>();
mock_map_builder_ = absl::make_unique<mapping::testing::MockMapBuilder>();
mock_pose_graph_ = absl::make_unique<mapping::testing::MockPoseGraph>();
EXPECT_CALL(*mock_map_builder_context_, map_builder())
.Times(::testing::AnyNumber())

View File

@ -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<MapBuilderServerInterface> CreateMapBuilderServer(
const proto::MapBuilderServerOptions& map_builder_server_options,
std::unique_ptr<mapping::MapBuilderInterface> map_builder) {
return common::make_unique<MapBuilderServer>(map_builder_server_options,
std::move(map_builder));
return absl::make_unique<MapBuilderServer>(map_builder_server_options,
std::move(map_builder));
}
} // namespace cloud

View File

@ -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<mapping::MapBuilder>(
auto map_builder = absl::make_unique<mapping::MapBuilder>(
map_builder_server_options.map_builder_options());
std::unique_ptr<MapBuilderServerInterface> map_builder_server =
CreateMapBuilderServer(map_builder_server_options,

View File

@ -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<common::ConfigurationFileResolver>(
auto file_resolver = absl::make_unique<common::ConfigurationFileResolver>(
std::vector<std::string>{configuration_directory});
const std::string code =
file_resolver->GetFileContentOrDie(configuration_basename);

View File

@ -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<std::string, std::string>& labels) override {
::prometheus::Counter* counter = &prometheus_->Add(labels);
auto wrapper = common::make_unique<Counter>(counter);
auto wrapper = absl::make_unique<Counter>(counter);
auto* ptr = wrapper.get();
wrappers_.emplace_back(std::move(wrapper));
return ptr;
@ -84,7 +84,7 @@ class GaugeFamily
Gauge* Add(const std::map<std::string, std::string>& labels) override {
::prometheus::Gauge* gauge = &prometheus_->Add(labels);
auto wrapper = common::make_unique<Gauge>(gauge);
auto wrapper = absl::make_unique<Gauge>(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<std::string, std::string>& labels) override {
::prometheus::Histogram* histogram = &prometheus_->Add(labels, boundaries_);
auto wrapper = common::make_unique<Histogram>(histogram);
auto wrapper = absl::make_unique<Histogram>(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<CounterFamily>(&family);
auto wrapper = absl::make_unique<CounterFamily>(&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<GaugeFamily>(&family);
auto wrapper = absl::make_unique<GaugeFamily>(&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<HistogramFamily>(&family, boundaries);
auto wrapper = absl::make_unique<HistogramFamily>(&family, boundaries);
auto* ptr = wrapper.get();
histograms_.emplace_back(std::move(wrapper));
return ptr;

View File

@ -19,7 +19,7 @@
#include <memory>
#include <thread>
#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<std::unique_ptr<int>> blocking_queue;
blocking_queue.Push(common::make_unique<int>(42));
blocking_queue.Push(absl::make_unique<int>(42));
ASSERT_EQ(1, blocking_queue.Size());
blocking_queue.Push(common::make_unique<int>(24));
blocking_queue.Push(absl::make_unique<int>(24));
ASSERT_EQ(2, blocking_queue.Size());
EXPECT_EQ(42, *blocking_queue.Peek<int>());
ASSERT_EQ(2, blocking_queue.Size());
@ -60,10 +60,10 @@ TEST(BlockingQueueTest, testPopWithTimeout) {
TEST(BlockingQueueTest, testPushWithTimeout) {
BlockingQueue<std::unique_ptr<int>> blocking_queue(1);
EXPECT_EQ(true,
blocking_queue.PushWithTimeout(common::make_unique<int>(42),
blocking_queue.PushWithTimeout(absl::make_unique<int>(42),
common::FromMilliseconds(150)));
EXPECT_EQ(false,
blocking_queue.PushWithTimeout(common::make_unique<int>(15),
blocking_queue.PushWithTimeout(absl::make_unique<int>(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<std::unique_ptr<int>> blocking_queue;
EXPECT_EQ(true,
blocking_queue.PushWithTimeout(common::make_unique<int>(42),
blocking_queue.PushWithTimeout(absl::make_unique<int>(42),
common::FromMilliseconds(150)));
EXPECT_EQ(true,
blocking_queue.PushWithTimeout(common::make_unique<int>(45),
blocking_queue.PushWithTimeout(absl::make_unique<int>(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<int>(42));
blocking_queue.Push(absl::make_unique<int>(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<int>(42));
blocking_queue.Push(absl::make_unique<int>(42));
thread.join();
ASSERT_EQ(0, blocking_queue.Size());
EXPECT_EQ(42, pop);

View File

@ -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>{
std::string(::cartographer::common::kSourceDirectory) +
"/configuration_files"});
auto file_resolver =
::absl::make_unique< ::cartographer::common::ConfigurationFileResolver>(
std::vector<std::string>{
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>{
std::string(::cartographer::common::kSourceDirectory) +
"/configuration_files"});
auto file_resolver =
::absl::make_unique< ::cartographer::common::ConfigurationFileResolver>(
std::vector<std::string>{
std::string(::cartographer::common::kSourceDirectory) +
"/configuration_files"});
::cartographer::common::LuaParameterDictionary lua_parameter_dictionary(
kCode, std::move(file_resolver));
::cartographer::mapping::CreateTrajectoryBuilderOptions(

View File

@ -21,7 +21,7 @@
#include <chrono>
#include <numeric>
#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"

View File

@ -20,7 +20,7 @@
#include <atomic>
#include <memory>
#include "cartographer/common/make_unique.h"
#include "absl/memory/memory.h"
#include "glog/logging.h"
namespace cartographer {

View File

@ -7,13 +7,13 @@ namespace {
TEST(LocklessQueueTest, PushAndPop) {
LocklessQueue<int> queue;
queue.Push(common::make_unique<int>(1));
queue.Push(common::make_unique<int>(2));
queue.Push(absl::make_unique<int>(1));
queue.Push(absl::make_unique<int>(2));
EXPECT_EQ(*queue.Pop(), 1);
queue.Push(common::make_unique<int>(3));
queue.Push(common::make_unique<int>(4));
queue.Push(absl::make_unique<int>(3));
queue.Push(absl::make_unique<int>(4));
EXPECT_EQ(*queue.Pop(), 2);
queue.Push(common::make_unique<int>(5));
queue.Push(absl::make_unique<int>(5));
EXPECT_EQ(*queue.Pop(), 3);
EXPECT_EQ(*queue.Pop(), 4);
EXPECT_EQ(*queue.Pop(), 5);

View File

@ -20,8 +20,8 @@
#include <cmath>
#include <memory>
#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<LuaParameterDictionary> MakeNonReferenceCounted(
const std::string& code) {
return LuaParameterDictionary::NonReferenceCounted(
code, common::make_unique<DummyFileResolver>());
code, absl::make_unique<DummyFileResolver>());
}
class LuaParameterDictionaryTest : public ::testing::Test {

View File

@ -20,8 +20,8 @@
#include <memory>
#include <string>
#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<LuaParameterDictionary> MakeDictionary(
const std::string& code) {
return common::make_unique<LuaParameterDictionary>(
code, common::make_unique<DummyFileResolver>());
return absl::make_unique<LuaParameterDictionary>(
code, absl::make_unique<DummyFileResolver>());
}
} // namespace common

View File

@ -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 <cstddef>
#include <memory>
#include <type_traits>
#include <utility>
namespace cartographer {
namespace common {
// Implementation of c++14's std::make_unique, taken from
// https://isocpp.org/files/papers/N3656.txt
template <class T>
struct _Unique_if {
typedef std::unique_ptr<T> _Single_object;
};
template <class T>
struct _Unique_if<T[]> {
typedef std::unique_ptr<T[]> _Unknown_bound;
};
template <class T, size_t N>
struct _Unique_if<T[N]> {
typedef void _Known_bound;
};
template <class T, class... Args>
typename _Unique_if<T>::_Single_object make_unique(Args&&... args) {
return std::unique_ptr<T>(new T(std::forward<Args>(args)...));
}
template <class T>
typename _Unique_if<T>::_Unknown_bound make_unique(size_t n) {
typedef typename std::remove_extent<T>::type U;
return std::unique_ptr<T>(new U[n]());
}
template <class T, class... Args>
typename _Unique_if<T>::_Known_bound make_unique(Args&&...) = delete;
} // namespace common
} // namespace cartographer
#endif // CARTOGRAPHER_COMMON_MAKE_UNIQUE_H_

View File

@ -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 <memory>
#include "absl/memory/memory.h"
#include "glog/logging.h"
namespace cartographer {
namespace common {
template <class T>
class optional {
public:
optional() {}
optional(const optional& other) {
if (other.has_value()) {
value_ = absl::make_unique<T>(other.value());
}
}
explicit optional(const T& value) { value_ = absl::make_unique<T>(value); }
bool has_value() const { return value_ != nullptr; }
const T& value() const {
CHECK(value_ != nullptr);
return *value_;
}
optional<T>& operator=(const T& other_value) {
this->value_ = absl::make_unique<T>(other_value);
return *this;
}
optional<T>& operator=(const optional<T>& other) {
if (!other.has_value()) {
this->value_ = nullptr;
} else {
this->value_ = absl::make_unique<T>(other.value());
}
return *this;
}
private:
std::unique_ptr<T> value_;
};
} // namespace common
} // namespace cartographer
#endif // CARTOGRAPHER_COMMON_OPTIONAL_H_

View File

@ -19,7 +19,7 @@
#include <memory>
#include <queue>
#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<Task>();
auto a = absl::make_unique<Task>();
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<Task>();
auto b = make_unique<Task>();
auto a = absl::make_unique<Task>();
auto b = absl::make_unique<Task>();
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<Task>();
auto b = make_unique<Task>();
auto c = make_unique<Task>();
auto d = make_unique<Task>();
auto a = absl::make_unique<Task>();
auto b = absl::make_unique<Task>();
auto c = absl::make_unique<Task>();
auto d = absl::make_unique<Task>();
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<Task>();
auto a = absl::make_unique<Task>();
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<Task>();
auto b = absl::make_unique<Task>();
MockCallback callback_b;
b->SetWorkItem([&callback_b]() { callback_b.Run(); });
b->AddDependency(shared_a);

View File

@ -21,7 +21,7 @@
#include <chrono>
#include <numeric>
#include "cartographer/common/make_unique.h"
#include "absl/memory/memory.h"
#include "cartographer/common/task.h"
#include "glog/logging.h"

View File

@ -18,7 +18,7 @@
#include <vector>
#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<Task>();
auto task = absl::make_unique<Task>();
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<Task>();
auto task = absl::make_unique<Task>();
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<Task>();
auto task_2 = absl::make_unique<Task>();
task_2->SetWorkItem([&receiver]() { receiver.Receive(2); });
auto task_1 = common::make_unique<Task>();
auto task_1 = absl::make_unique<Task>();
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<Task>();
auto task_2 = absl::make_unique<Task>();
task_2->SetWorkItem([&receiver]() { receiver.Receive(2); });
{
auto task_1 = common::make_unique<Task>();
auto task_1 = absl::make_unique<Task>();
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<Task>();
auto task = absl::make_unique<Task>();
task->SetWorkItem([&receiver]() { receiver.Receive(1); });
for (int i = 0; i < kNumDependencies; ++i) {
auto dependency_task = common::make_unique<Task>();
auto dependency_task = absl::make_unique<Task>();
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<Task>();
auto dependency_task = absl::make_unique<Task>();
dependency_task->SetWorkItem([]() {});
auto dependency_handle = pool.Schedule(std::move(dependency_task));
for (int i = 0; i < kNumDependants; ++i) {
auto task = common::make_unique<Task>();
auto task = absl::make_unique<Task>();
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<Task>();
auto task_1 = absl::make_unique<Task>();
task_1->SetWorkItem([&receiver]() { receiver.Receive(1); });
auto task_2a = common::make_unique<Task>();
auto task_2a = absl::make_unique<Task>();
task_2a->SetWorkItem([&receiver]() { receiver.Receive(2); });
auto task_2b = common::make_unique<Task>();
auto task_2b = absl::make_unique<Task>();
task_2b->SetWorkItem([&receiver]() { receiver.Receive(2); });
auto task_3 = common::make_unique<Task>();
auto task_3 = absl::make_unique<Task>();
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<Task>();
auto task_1 = absl::make_unique<Task>();
task_1->SetWorkItem([&receiver]() { receiver.Receive(1); });
auto task_2 = common::make_unique<Task>();
auto task_2 = absl::make_unique<Task>();
task_2->SetWorkItem([&receiver]() { receiver.Receive(2); });
auto weak_task_1 = pool.Schedule(std::move(task_1));
task_2->AddDependency(weak_task_1);

View File

@ -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<uint8>(color_values[0]),
static_cast<uint8>(color_values[1]),
static_cast<uint8>(color_values[2])}};
return common::make_unique<ColoringPointsProcessor>(ToFloatColor(color),
frame_id, next);
return absl::make_unique<ColoringPointsProcessor>(ToFloatColor(color),
frame_id, next);
}
ColoringPointsProcessor::ColoringPointsProcessor(const FloatColor& color,

View File

@ -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>
CountingPointsProcessor::FromDictionary(
common::LuaParameterDictionary* const dictionary,
PointsProcessor* const next) {
return common::make_unique<CountingPointsProcessor>(next);
return absl::make_unique<CountingPointsProcessor>(next);
}
void CountingPointsProcessor::Process(std::unique_ptr<PointsBatch> batch) {

View File

@ -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<FixedRatioSamplingPointsProcessor>(sampling_ratio,
next);
return absl::make_unique<FixedRatioSamplingPointsProcessor>(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<common::FixedRatioSampler>(sampling_ratio_);
sampler_ = absl::make_unique<common::FixedRatioSampler>(sampling_ratio_);
return PointsProcessor::FlushResult::kRestartStream;
}
LOG(FATAL);

View File

@ -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<FrameIdFilteringPointsProcessor>(
return absl::make_unique<FrameIdFilteringPointsProcessor>(
std::unordered_set<std::string>(keep_frames.begin(), keep_frames.end()),
std::unordered_set<std::string>(drop_frames.begin(), drop_frames.end()),
next);

View File

@ -4,7 +4,7 @@
#include <string>
#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<HybridGridPointsProcessor>(
return absl::make_unique<HybridGridPointsProcessor>(
dictionary->GetDouble("voxel_size"),
mapping::CreateRangeDataInserterOptions3D(
dictionary->GetDictionary("range_data_inserter").get()),

View File

@ -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<IntensityToColorPointsProcessor>(
return absl::make_unique<IntensityToColorPointsProcessor>(
min_intensity, max_intensity, frame_id, next);
}

View File

@ -19,7 +19,7 @@
#include <queue>
#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 <typename MessageType>
void AddProto(const MessageType& proto) {
state_chunks_.push(common::make_unique<MessageType>(proto));
state_chunks_.push(absl::make_unique<MessageType>(proto));
}
bool ReadProto(google::protobuf::Message* proto) override;

View File

@ -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;

View File

@ -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>
MinMaxRangeFiteringPointsProcessor::FromDictionary(
common::LuaParameterDictionary* const dictionary,
PointsProcessor* const next) {
return common::make_unique<MinMaxRangeFiteringPointsProcessor>(
return absl::make_unique<MinMaxRangeFiteringPointsProcessor>(
dictionary->GetDouble("min_range"), dictionary->GetDouble("max_range"),
next);
}

View File

@ -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>
OutlierRemovingPointsProcessor::FromDictionary(
common::LuaParameterDictionary* const dictionary,
PointsProcessor* const next) {
return common::make_unique<OutlierRemovingPointsProcessor>(
return absl::make_unique<OutlierRemovingPointsProcessor>(
dictionary->GetDouble("voxel_size"), next);
}

View File

@ -20,8 +20,8 @@
#include <sstream>
#include <string>
#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<PcdWritingPointsProcessor>(
return absl::make_unique<PcdWritingPointsProcessor>(
file_writer_factory(dictionary->GetString("filename")), next);
}

View File

@ -20,8 +20,8 @@
#include <sstream>
#include <string>
#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<PlyWritingPointsProcessor>(
return absl::make_unique<PlyWritingPointsProcessor>(
file_writer_factory(dictionary->GetString("filename")), next);
}

View File

@ -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<NullPointsProcessor>());
pipeline.emplace_back(absl::make_unique<NullPointsProcessor>());
std::vector<std::unique_ptr<common::LuaParameterDictionary>> configurations =
dictionary->GetArrayValuesAsDictionaries();

View File

@ -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<ProbabilityGridPointsProcessor>(
return absl::make_unique<ProbabilityGridPointsProcessor>(
dictionary->GetDouble("resolution"),
mapping::CreateProbabilityGridRangeDataInserterOptions2D(
dictionary->GetDictionary("range_data_inserter").get()),
@ -178,8 +178,8 @@ std::unique_ptr<Image> DrawProbabilityGrid(
LOG(WARNING) << "Not writing output: empty probability grid";
return nullptr;
}
auto image = common::make_unique<Image>(cell_limits.num_x_cells,
cell_limits.num_y_cells);
auto image = absl::make_unique<Image>(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;

View File

@ -32,7 +32,7 @@ namespace io {
namespace {
std::unique_ptr<PointsBatch> CreatePointsBatch() {
auto points_batch = cartographer::common::make_unique<PointsBatch>();
auto points_batch = ::absl::make_unique<PointsBatch>();
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<PointsBatch> 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<mapping::proto::Trajectory>& 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<common::LuaParameterDictionary> CreateParameterDictionary() {
}
return pipeline
)text",
common::make_unique<cartographer::common::DummyFileResolver>());
absl::make_unique<cartographer::common::DummyFileResolver>());
return parameter_dictionary;
}

View File

@ -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<ProtoStreamDeserializer>(reader_.get()),
EXPECT_DEATH(absl::make_unique<ProtoStreamDeserializer>(reader_.get()),
"Unsupported serialization format");
}

View File

@ -25,17 +25,17 @@ std::unique_ptr<InMemoryProtoStreamReader> ProtoReaderFromStrings(
const std::string &header_textpb,
const std::initializer_list<std::string> &data_textpbs) {
std::queue<std::unique_ptr<::google::protobuf::Message>> 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<InMemoryProtoStreamReader>(std::move(proto_queue));
return absl::make_unique<InMemoryProtoStreamReader>(std::move(proto_queue));
}
} // namespace testing

View File

@ -20,8 +20,8 @@
#include <string>
#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> XRayPointsProcessor::FromDictionary(
floors = mapping::DetectFloors(trajectories.at(0));
}
return common::make_unique<XRayPointsProcessor>(
return absl::make_unique<XRayPointsProcessor>(
dictionary->GetDouble("voxel_size"),
transform::FromDictionary(dictionary->GetDictionary("transform").get())
.cast<float>(),

View File

@ -2,7 +2,7 @@
#include <iomanip>
#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<XyzWriterPointsProcessor>(
return absl::make_unique<XyzWriterPointsProcessor>(
file_writer_factory(dictionary->GetString("filename")), next);
}

View File

@ -17,7 +17,7 @@
#include <limits>
#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<Grid2D> ProbabilityGrid::ComputeCroppedGrid() const {
const Eigen::Vector2d max =
limits().max() - resolution * Eigen::Vector2d(offset.y(), offset.x());
std::unique_ptr<ProbabilityGrid> cropped_grid =
common::make_unique<ProbabilityGrid>(
absl::make_unique<ProbabilityGrid>(
MapLimits(resolution, max, cell_limits), conversion_tables_);
for (const Eigen::Array2i& xy_index : XYIndexRangeIterator(cell_limits)) {
if (!IsKnown(xy_index + offset)) continue;

View File

@ -18,9 +18,9 @@
#include <memory>
#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<ProbabilityGridRangeDataInserter2D>(options_);
absl::make_unique<ProbabilityGridRangeDataInserter2D>(options_);
}
void InsertPointCloud() {

View File

@ -23,7 +23,7 @@
#include <limits>
#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<ProbabilityGrid>(proto.grid(), conversion_tables_);
absl::make_unique<ProbabilityGrid>(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<ProbabilityGrid>(submap_2d.grid(),
conversion_tables_);
grid_ = absl::make_unique<ProbabilityGrid>(submap_2d.grid(),
conversion_tables_);
}
}
@ -159,7 +159,7 @@ std::vector<std::shared_ptr<const Submap2D>> ActiveSubmaps2D::InsertRangeData(
std::unique_ptr<RangeDataInserterInterface>
ActiveSubmaps2D::CreateRangeDataInserter() {
return common::make_unique<ProbabilityGridRangeDataInserter2D>(
return absl::make_unique<ProbabilityGridRangeDataInserter2D>(
options_.range_data_inserter_options()
.probability_grid_range_data_inserter_options_2d());
}
@ -168,7 +168,7 @@ std::unique_ptr<GridInterface> ActiveSubmaps2D::CreateGrid(
const Eigen::Vector2f& origin) {
constexpr int kInitialSubmapSize = 100;
float resolution = options_.grid_options_2d().resolution();
return common::make_unique<ProbabilityGrid>(
return absl::make_unique<ProbabilityGrid>(
MapLimits(resolution,
origin.cast<double>() + 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<Submap2D>(
submaps_.push_back(absl::make_unique<Submap2D>(
origin,
std::unique_ptr<Grid2D>(
static_cast<Grid2D*>(CreateGrid(origin).release())),

View File

@ -100,8 +100,8 @@ TEST(Submap2DTest, ToFromProto) {
CellLimits(100, 110));
ValueConversionTables conversion_tables;
Submap2D expected(Eigen::Vector2f(4.f, 5.f),
common::make_unique<ProbabilityGrid>(expected_map_limits,
&conversion_tables),
absl::make_unique<ProbabilityGrid>(expected_map_limits,
&conversion_tables),
&conversion_tables);
const proto::Submap proto =
expected.ToProto(true /* include_probability_grid_data */);

View File

@ -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<TSDValueConverter>(
value_converter_(absl::make_unique<TSDValueConverter>(
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<TSDValueConverter>(
value_converter_ = absl::make_unique<TSDValueConverter>(
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<Grid2D> TSDF2D::ComputeCroppedGrid() const {
const double resolution = limits().resolution();
const Eigen::Vector2d max =
limits().max() - resolution * Eigen::Vector2d(offset.y(), offset.x());
std::unique_ptr<TSDF2D> cropped_grid = common::make_unique<TSDF2D>(
std::unique_ptr<TSDF2D> cropped_grid = absl::make_unique<TSDF2D>(
MapLimits(resolution, max, cell_limits), value_converter_->getMaxTSD(),
value_converter_->getMaxWeight(), conversion_tables_);
for (const Eigen::Array2i& xy_index : XYIndexRangeIterator(cell_limits)) {

View File

@ -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<TSDFRangeDataInserter2D>(options_);
range_data_inserter_ = absl::make_unique<TSDFRangeDataInserter2D>(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<TSDFRangeDataInserter2D>(options_);
range_data_inserter_ = absl::make_unique<TSDFRangeDataInserter2D>(options_);
InsertPoint();
const float truncation_distance =
static_cast<float>(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<TSDFRangeDataInserter2D>(options_);
range_data_inserter_ = absl::make_unique<TSDFRangeDataInserter2D>(options_);
InsertPoint();
const float truncation_distance =
static_cast<float>(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<TSDFRangeDataInserter2D>(options_);
range_data_inserter_ = absl::make_unique<TSDFRangeDataInserter2D>(options_);
InsertPoint();
const float truncation_distance =
static_cast<float>(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<TSDFRangeDataInserter2D>(options_);
range_data_inserter_ = absl::make_unique<TSDFRangeDataInserter2D>(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<TSDFRangeDataInserter2D>(options_);
range_data_inserter_ = absl::make_unique<TSDFRangeDataInserter2D>(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<TSDFRangeDataInserter2D>(options_);
range_data_inserter_ = absl::make_unique<TSDFRangeDataInserter2D>(options_);
InsertPoint();
const float truncation_distance =
static_cast<float>(options_.truncation_distance());

View File

@ -24,7 +24,7 @@
#include <vector>
#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<WrappedGrid>& meta_cell =
meta_cells_[ToFlatIndex(meta_index, kBits)];
if (meta_cell == nullptr) {
meta_cell = common::make_unique<WrappedGrid>();
meta_cell = absl::make_unique<WrappedGrid>();
}
const Eigen::Array3i inner_index =
index - meta_index * WrappedGrid::grid_size();
@ -292,7 +292,7 @@ class DynamicGrid {
std::unique_ptr<WrappedGrid>& meta_cell =
meta_cells_[ToFlatIndex(meta_index, bits_)];
if (meta_cell == nullptr) {
meta_cell = common::make_unique<WrappedGrid>();
meta_cell = absl::make_unique<WrappedGrid>();
}
const Eigen::Array3i inner_index =
shifted_index - meta_index * WrappedGrid::grid_size();

View File

@ -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<HybridGrid>(high_resolution)),
absl::make_unique<HybridGrid>(high_resolution)),
low_resolution_hybrid_grid_(
common::make_unique<HybridGrid>(low_resolution)) {}
absl::make_unique<HybridGrid>(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<HybridGrid>(
submap_3d.high_resolution_hybrid_grid());
high_resolution_hybrid_grid_ =
absl::make_unique<HybridGrid>(submap_3d.high_resolution_hybrid_grid());
}
if (submap_3d.has_low_resolution_hybrid_grid()) {
low_resolution_hybrid_grid_ =
common::make_unique<HybridGrid>(submap_3d.low_resolution_hybrid_grid());
absl::make_unique<HybridGrid>(submap_3d.low_resolution_hybrid_grid());
}
}

View File

@ -27,7 +27,7 @@
#include <tuple>
#include <vector>
#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<const IdDataReference> operator->() const {
return common::make_unique<const IdDataReference>(this->operator*());
return absl::make_unique<const IdDataReference>(this->operator*());
}
ConstIterator& operator++() {

View File

@ -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<ImuTracker>(kGravityTimeConstant, time_);
imu_tracker_ = absl::make_unique<ImuTracker>(kGravityTimeConstant, time_);
angular_velocity_ = Eigen::Vector3d(0, 0, 0);
linear_acceleration_ = Eigen::Vector3d(0, 0, 9.9);
EXPECT_NEAR(0.,

View File

@ -23,7 +23,7 @@ namespace mapping {
void LocalSlamResult2D::AddToTrajectoryBuilder(
TrajectoryBuilderInterface* const trajectory_builder) {
trajectory_builder->AddLocalSlamResultData(
common::make_unique<LocalSlamResult2D>(*this));
absl::make_unique<LocalSlamResult2D>(*this));
}
void LocalSlamResult2D::AddToPoseGraph(int trajectory_id,

View File

@ -19,7 +19,7 @@
#include <limits>
#include <memory>
#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<transform::Rigid2d> 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<transform::Rigid2d>(pose_prediction);
return absl::make_unique<transform::Rigid2d>(pose_prediction);
}
std::shared_ptr<const Submap2D> matching_submap =
active_submaps_.submaps().front();
@ -84,7 +84,7 @@ std::unique_ptr<transform::Rigid2d> LocalTrajectoryBuilder2D::ScanMatch(
kRealTimeCorrelativeScanMatcherScoreMetric->Observe(score);
}
auto pose_observation = common::make_unique<transform::Rigid2d>();
auto pose_observation = absl::make_unique<transform::Rigid2d>();
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<MatchingResult>(
return absl::make_unique<MatchingResult>(
MatchingResult{time, pose_estimate, std::move(range_data_in_local),
std::move(insertion_result)});
}
@ -287,7 +287,7 @@ LocalTrajectoryBuilder2D::InsertIntoSubmap(
}
std::vector<std::shared_ptr<const Submap2D>> insertion_submaps =
active_submaps_.InsertRangeData(range_data_in_local);
return common::make_unique<InsertionResult>(InsertionResult{
return absl::make_unique<InsertionResult>(InsertionResult{
std::make_shared<const TrajectoryNode::Data>(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<PoseExtrapolator>(
extrapolator_ = absl::make_unique<PoseExtrapolator>(
::cartographer::common::FromSeconds(kExtrapolationEstimationTimeSec),
options_.imu_gravity_time_constant());
extrapolator_->AddPose(time, transform::Rigid3d::Identity());

View File

@ -29,7 +29,7 @@
#include <string>
#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<WorkItem::Result()>& work_item) {
common::MutexLocker locker(&work_queue_mutex_);
if (work_queue_ == nullptr) {
work_queue_ = common::make_unique<WorkQueue>();
auto task = common::make_unique<common::Task>();
work_queue_ = absl::make_unique<WorkQueue>();
auto task = absl::make_unique<common::Task>();
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<common::FixedRatioSampler>(
absl::make_unique<common::FixedRatioSampler>(
options_.global_sampling_ratio());
}
}

View File

@ -20,8 +20,8 @@
#include <memory>
#include <random>
#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<ActiveSubmaps2D>(
active_submaps_ = absl::make_unique<ActiveSubmaps2D>(
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<PoseGraph2D>(
pose_graph_ = absl::make_unique<PoseGraph2D>(
options,
common::make_unique<optimization::OptimizationProblem2D>(
absl::make_unique<optimization::OptimizationProblem2D>(
options.optimization_problem_options()),
&thread_pool_);
}

View File

@ -18,9 +18,9 @@
#include <memory>
#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<CeresScanMatcher2D>(options);
ceres_scan_matcher_ = absl::make_unique<CeresScanMatcher2D>(options);
}
void TestFromInitialPose(const transform::Rigid2d& initial_pose) {

View File

@ -23,7 +23,7 @@
#include <limits>
#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<PrecomputationGridStack2D>(grid, options)) {}
absl::make_unique<PrecomputationGridStack2D>(grid, options)) {}
FastCorrelativeScanMatcher2D::~FastCorrelativeScanMatcher2D() {}

View File

@ -20,8 +20,8 @@
#include <memory>
#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<ProbabilityGridRangeDataInserter2D>(
absl::make_unique<ProbabilityGridRangeDataInserter2D>(
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<RealTimeCorrelativeScanMatcher2D>(
absl::make_unique<RealTimeCorrelativeScanMatcher2D>(
CreateRealTimeCorrelativeScanMatcherOptions(
parameter_dictionary.get()));
}

View File

@ -23,7 +23,7 @@ namespace mapping {
void LocalSlamResult3D::AddToTrajectoryBuilder(
TrajectoryBuilderInterface* const trajectory_builder) {
trajectory_builder->AddLocalSlamResultData(
common::make_unique<LocalSlamResult3D>(*this));
absl::make_unique<LocalSlamResult3D>(*this));
}
void LocalSlamResult3D::AddToPoseGraph(int trajectory_id,

View File

@ -18,7 +18,7 @@
#include <memory>
#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<scan_matching::RealTimeCorrelativeScanMatcher3D>(
absl::make_unique<scan_matching::RealTimeCorrelativeScanMatcher3D>(
options_.real_time_correlative_scan_matcher_options())),
ceres_scan_matcher_(
common::make_unique<scan_matching::CeresScanMatcher3D>(
options_.ceres_scan_matcher_options())),
ceres_scan_matcher_(absl::make_unique<scan_matching::CeresScanMatcher3D>(
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<transform::Rigid3d> 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<transform::Rigid3d>(pose_prediction);
return absl::make_unique<transform::Rigid3d>(pose_prediction);
}
std::shared_ptr<const mapping::Submap3D> matching_submap =
active_submaps_.submaps().front();
@ -100,8 +99,8 @@ std::unique_ptr<transform::Rigid3d> LocalTrajectoryBuilder3D::ScanMatch(
pose_observation_in_submap.rotation().angularDistance(
initial_ceres_pose.rotation());
kScanMatcherResidualAngleMetric->Observe(residual_angle);
return common::make_unique<transform::Rigid3d>(matching_submap->local_pose() *
pose_observation_in_submap);
return absl::make_unique<transform::Rigid3d>(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>(MatchingResult{
return absl::make_unique<MatchingResult>(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<float>())),
options_.rotational_histogram_size());
return common::make_unique<InsertionResult>(
return absl::make_unique<InsertionResult>(
InsertionResult{std::make_shared<const mapping::TrajectoryNode::Data>(
mapping::TrajectoryNode::Data{
time,

View File

@ -28,7 +28,7 @@
#include <string>
#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<WorkItem::Result()>& work_item) {
common::MutexLocker locker(&work_queue_mutex_);
if (work_queue_ == nullptr) {
work_queue_ = common::make_unique<WorkQueue>();
auto task = common::make_unique<common::Task>();
work_queue_ = absl::make_unique<WorkQueue>();
auto task = absl::make_unique<common::Task>();
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<common::FixedRatioSampler>(
absl::make_unique<common::FixedRatioSampler>(
options_.global_sampling_ratio());
}
}

View File

@ -57,8 +57,7 @@ class PoseGraph3DForTesting : public PoseGraph3D {
class PoseGraph3DTest : public ::testing::Test {
protected:
PoseGraph3DTest()
: thread_pool_(common::make_unique<common::ThreadPool>(1)) {}
PoseGraph3DTest() : thread_pool_(absl::make_unique<common::ThreadPool>(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<optimization::OptimizationProblem3D>(
absl::make_unique<optimization::OptimizationProblem3D>(
pose_graph_options_.optimization_problem_options());
pose_graph_ = common::make_unique<PoseGraph3DForTesting>(
pose_graph_ = absl::make_unique<PoseGraph3DForTesting>(
pose_graph_options_, std::move(optimization_problem),
thread_pool_.get());
}
void BuildPoseGraphWithFakeOptimization() {
auto optimization_problem =
common::make_unique<MockOptimizationProblem3D>();
pose_graph_ = common::make_unique<PoseGraph3DForTesting>(
auto optimization_problem = absl::make_unique<MockOptimizationProblem3D>();
pose_graph_ = absl::make_unique<PoseGraph3DForTesting>(
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<PureLocalizationTrimmer>(
pose_graph_->AddTrimmer(absl::make_unique<PureLocalizationTrimmer>(
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<EvenSubmapTrimmer>(trajectory_id));
pose_graph_->AddTrimmer(absl::make_unique<EvenSubmapTrimmer>(trajectory_id));
pose_graph_->WaitForAllComputations();
EXPECT_EQ(
pose_graph_->GetAllSubmapPoses().SizeOfTrajectoryOrZero(trajectory_id),

View File

@ -20,8 +20,8 @@
#include <utility>
#include <vector>
#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<ceres::LocalParameterization>(
common::make_unique<ceres::AutoDiffLocalParameterization<
absl::make_unique<ceres::AutoDiffLocalParameterization<
YawOnlyQuaternionPlus, 4, 1>>())
: std::unique_ptr<ceres::LocalParameterization>(
common::make_unique<ceres::QuaternionParameterization>()),
absl::make_unique<ceres::QuaternionParameterization>()),
&problem);
CHECK_EQ(options_.occupied_space_weight_size(),

View File

@ -22,7 +22,7 @@
#include <limits>
#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<PrecomputationGridStack3D>(hybrid_grid, options)),
absl::make_unique<PrecomputationGridStack3D>(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>(Result{
return absl::make_unique<Result>(Result{
best_candidate.score,
GetPoseFromCandidate(discrete_scans, best_candidate).cast<double>(),
discrete_scans[best_candidate.scan_index].rotational_score,

View File

@ -21,8 +21,8 @@
#include <random>
#include <string>
#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<FastCorrelativeScanMatcher3D> GetFastCorrelativeScanMatcher(
const proto::FastCorrelativeScanMatcherOptions3D& options,
const transform::Rigid3f& pose) {
hybrid_grid_ = common::make_unique<HybridGrid>(0.05f);
hybrid_grid_ = absl::make_unique<HybridGrid>(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<FastCorrelativeScanMatcher3D>(
return absl::make_unique<FastCorrelativeScanMatcher3D>(
*hybrid_grid_, hybrid_grid_.get(),
std::vector<TrajectoryNode>(
{{std::make_shared<const TrajectoryNode::Data>(

View File

@ -26,7 +26,7 @@
#include <string>
#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<common::Task>()),
when_done_task_(common::make_unique<common::Task>()),
finish_node_task_(absl::make_unique<common::Task>()),
when_done_task_(absl::make_unique<common::Task>()),
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<common::Task>();
auto constraint_task = absl::make_unique<common::Task>();
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<common::Task>();
auto constraint_task = absl::make_unique<common::Task>();
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<common::Task>();
finish_node_task_ = absl::make_unique<common::Task>();
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<std::function<void(const Result&)>>(callback);
when_done_ = absl::make_unique<std::function<void(const Result&)>>(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<common::Task>();
when_done_task_ = absl::make_unique<common::Task>();
}
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<common::Task>();
auto scan_matcher_task = absl::make_unique<common::Task>();
scan_matcher_task->SetWorkItem(
[&submap_scan_matcher, &scan_matcher_options]() {
submap_scan_matcher.fast_correlative_scan_matcher =
common::make_unique<scan_matching::FastCorrelativeScanMatcher2D>(
absl::make_unique<scan_matching::FastCorrelativeScanMatcher2D>(
*submap_scan_matcher.grid, scan_matcher_options);
});
submap_scan_matcher.creation_task_handle =

View File

@ -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<ConstraintBuilder2D>(
constraint_builder_ = absl::make_unique<ConstraintBuilder2D>(
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<ProbabilityGrid>(map_limits, &conversion_tables),
absl::make_unique<ProbabilityGrid>(map_limits, &conversion_tables),
&conversion_tables);
int expected_nodes = 0;
for (int i = 0; i < 2; ++i) {

View File

@ -26,7 +26,7 @@
#include <string>
#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<common::Task>()),
when_done_task_(common::make_unique<common::Task>()),
finish_node_task_(absl::make_unique<common::Task>()),
when_done_task_(absl::make_unique<common::Task>()),
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<common::Task>();
auto constraint_task = absl::make_unique<common::Task>();
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<common::Task>();
auto constraint_task = absl::make_unique<common::Task>();
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<common::Task>();
finish_node_task_ = absl::make_unique<common::Task>();
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<std::function<void(const Result&)>>(callback);
when_done_ = absl::make_unique<std::function<void(const Result&)>>(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<common::Task>();
when_done_task_ = absl::make_unique<common::Task>();
}
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<common::Task>();
auto scan_matcher_task = absl::make_unique<common::Task>();
scan_matcher_task->SetWorkItem(
[&submap_scan_matcher, &scan_matcher_options, submap_nodes]() {
submap_scan_matcher.fast_correlative_scan_matcher =
common::make_unique<scan_matching::FastCorrelativeScanMatcher3D>(
absl::make_unique<scan_matching::FastCorrelativeScanMatcher3D>(
*submap_scan_matcher.high_resolution_hybrid_grid,
submap_scan_matcher.low_resolution_hybrid_grid, submap_nodes,
scan_matcher_options);

View File

@ -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<ConstraintBuilder3D>(
constraint_builder_ = absl::make_unique<ConstraintBuilder3D>(
CreateConstraintBuilderOptions(constraint_builder_parameters.get()),
&thread_pool_);
}

View File

@ -18,7 +18,7 @@
#include <memory>
#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>(InsertionResult{
insertion_result = absl::make_unique<InsertionResult>(InsertionResult{
node_id, matching_result->insertion_result->constant_data,
std::vector<std::shared_ptr<const Submap>>(
matching_result->insertion_result->insertion_submaps.begin(),
@ -136,7 +136,7 @@ std::unique_ptr<TrajectoryBuilderInterface> 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<LocalTrajectoryBuilder2D, mapping::PoseGraph2D>>(
std::move(local_trajectory_builder), trajectory_id, pose_graph,
local_slam_result_callback);
@ -147,7 +147,7 @@ std::unique_ptr<TrajectoryBuilderInterface> 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<LocalTrajectoryBuilder3D, mapping::PoseGraph3D>>(
std::move(local_trajectory_builder), trajectory_id, pose_graph,
local_slam_result_callback);

Some files were not shown because too many files have changed in this diff Show More