[ABSL] Purge common::optional. (#1339)

master
Alexander Belyaev 2018-07-27 19:05:45 +02:00 committed by GitHub
parent dafb4149ed
commit 4990d4d5e9
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
23 changed files with 47 additions and 168 deletions

View File

@ -95,12 +95,12 @@ cc_library(
deps = [
":cc_protos",
"@boost//:iostreams",
"@com_google_absl//absl/types:optional",
"@com_google_glog//:glog",
"@org_cairographics_cairo//:cairo",
"@org_ceres_solver_ceres_solver//:ceres",
"@org_lua_lua//:lua",
"@org_tuxfamily_eigen//:eigen",
"@com_google_absl//absl/strings",
],
)

View File

@ -93,7 +93,7 @@ PoseGraphStub::GetTrajectoryNodePoses() const {
CHECK(client.Write(request));
mapping::MapById<mapping::NodeId, mapping::TrajectoryNodePose> node_poses;
for (const auto& node_pose : client.response().node_poses()) {
common::optional<mapping::TrajectoryNodePose::ConstantPoseData>
absl::optional<mapping::TrajectoryNodePose::ConstantPoseData>
constant_pose_data;
if (node_pose.has_constant_pose_data()) {
constant_pose_data = mapping::TrajectoryNodePose::ConstantPoseData{

View File

@ -39,7 +39,7 @@ class ReceiveGlobalSlamOptimizationsHandler
void OnFinish() override;
private:
common::optional<int> subscription_index_;
absl::optional<int> subscription_index_;
};
} // namespace handlers

View File

@ -1,69 +0,0 @@
/*
* Copyright 2017 The Cartographer Authors
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef CARTOGRAPHER_COMMON_OPTIONAL_H_
#define CARTOGRAPHER_COMMON_OPTIONAL_H_
#include <memory>
#include "cartographer/common/make_unique.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_ = common::make_unique<T>(other.value());
}
}
explicit optional(const T& value) { value_ = common::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_ = common::make_unique<T>(other_value);
return *this;
}
optional<T>& operator=(const optional<T>& other) {
if (!other.has_value()) {
this->value_ = nullptr;
} else {
this->value_ = common::make_unique<T>(other.value());
}
return *this;
}
private:
std::unique_ptr<T> value_;
};
} // namespace common
} // namespace cartographer
#endif // CARTOGRAPHER_COMMON_OPTIONAL_H_

View File

@ -1,63 +0,0 @@
/*
* Copyright 2017 The Cartographer Authors
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include "cartographer/common/optional.h"
#include "gtest/gtest.h"
namespace cartographer {
namespace common {
namespace {
TEST(OptionalTest, CreateDisengagedObject) {
const optional<int> o;
EXPECT_FALSE(o.has_value());
const optional<float> x;
EXPECT_FALSE(x.has_value());
}
TEST(OptionalTest, CreateWithValue) {
const optional<int> a(5);
EXPECT_TRUE(a.has_value());
EXPECT_EQ(5, a.value());
}
TEST(OptionalTest, CreateFromOtherOptional) {
const optional<int> a(5);
const optional<int> b = a;
EXPECT_TRUE(a.has_value());
EXPECT_TRUE(b.has_value());
EXPECT_EQ(5, a.value());
EXPECT_EQ(5, b.value());
}
TEST(OptionalTest, AssignmentOperator) {
optional<int> a(5);
optional<int> b(4);
optional<int> c;
a = b;
EXPECT_TRUE(a.has_value());
EXPECT_EQ(4, a.value());
a = c;
EXPECT_FALSE(a.has_value());
a = 3;
EXPECT_TRUE(a.has_value());
EXPECT_EQ(3, a.value());
}
} // namespace
} // namespace common
} // namespace cartographer

View File

@ -16,6 +16,8 @@
#include "cartographer/mapping/2d/tsdf_2d.h"
#include "cartographer/common/make_unique.h"
namespace cartographer {
namespace mapping {

View File

@ -187,7 +187,7 @@ LocalTrajectoryBuilder2D::AddRangeData(
if (num_accumulated_ >= options_.num_accumulated_range_data()) {
const common::Time current_sensor_time = synchronized_data.time;
common::optional<common::Duration> sensor_duration;
absl::optional<common::Duration> sensor_duration;
if (last_sensor_time_.has_value()) {
sensor_duration = current_sensor_time - last_sensor_time_.value();
}
@ -213,7 +213,7 @@ LocalTrajectoryBuilder2D::AddAccumulatedRangeData(
const common::Time time,
const sensor::RangeData& gravity_aligned_range_data,
const transform::Rigid3d& gravity_alignment,
const common::optional<common::Duration>& sensor_duration) {
const absl::optional<common::Duration>& sensor_duration) {
if (gravity_aligned_range_data.returns.empty()) {
LOG(WARNING) << "Dropped empty horizontal range data.";
return nullptr;

View File

@ -80,7 +80,7 @@ class LocalTrajectoryBuilder2D {
std::unique_ptr<MatchingResult> AddAccumulatedRangeData(
common::Time time, const sensor::RangeData& gravity_aligned_range_data,
const transform::Rigid3d& gravity_alignment,
const common::optional<common::Duration>& sensor_duration);
const absl::optional<common::Duration>& sensor_duration);
sensor::RangeData TransformToGravityAlignedFrameAndFilter(
const transform::Rigid3f& transform_to_gravity_aligned_frame,
const sensor::RangeData& range_data) const;
@ -112,9 +112,9 @@ class LocalTrajectoryBuilder2D {
int num_accumulated_ = 0;
sensor::RangeData accumulated_range_data_;
common::optional<std::chrono::steady_clock::time_point> last_wall_time_;
common::optional<double> last_thread_cpu_time_seconds_;
common::optional<common::Time> last_sensor_time_;
absl::optional<std::chrono::steady_clock::time_point> last_wall_time_;
absl::optional<double> last_thread_cpu_time_seconds_;
absl::optional<common::Time> last_sensor_time_;
RangeDataCollator range_data_collator_;
};

View File

@ -845,7 +845,7 @@ MapById<NodeId, TrajectoryNodePose> PoseGraph2D::GetTrajectoryNodePoses()
MapById<NodeId, TrajectoryNodePose> node_poses;
common::MutexLocker locker(&mutex_);
for (const auto& node_id_data : data_.trajectory_nodes) {
common::optional<TrajectoryNodePose::ConstantPoseData> constant_pose_data;
absl::optional<TrajectoryNodePose::ConstantPoseData> constant_pose_data;
if (node_id_data.data.constant_data != nullptr) {
constant_pose_data = TrajectoryNodePose::ConstantPoseData{
node_id_data.data.constant_data->time,

View File

@ -198,7 +198,7 @@ LocalTrajectoryBuilder3D::AddRangeData(
++num_accumulated_;
if (num_accumulated_ >= options_.num_accumulated_range_data()) {
common::optional<common::Duration> sensor_duration;
absl::optional<common::Duration> sensor_duration;
if (last_sensor_time_.has_value()) {
sensor_duration = current_sensor_time - last_sensor_time_.value();
}
@ -237,7 +237,7 @@ std::unique_ptr<LocalTrajectoryBuilder3D::MatchingResult>
LocalTrajectoryBuilder3D::AddAccumulatedRangeData(
const common::Time time,
const sensor::RangeData& filtered_range_data_in_tracking,
const common::optional<common::Duration>& sensor_duration) {
const absl::optional<common::Duration>& sensor_duration) {
if (filtered_range_data_in_tracking.returns.empty()) {
LOG(WARNING) << "Dropped empty range data.";
return nullptr;

View File

@ -78,7 +78,7 @@ class LocalTrajectoryBuilder3D {
std::unique_ptr<MatchingResult> AddAccumulatedRangeData(
common::Time time,
const sensor::RangeData& filtered_range_data_in_tracking,
const common::optional<common::Duration>& sensor_duration);
const absl::optional<common::Duration>& sensor_duration);
std::unique_ptr<InsertionResult> InsertIntoSubmap(
common::Time time, const sensor::RangeData& filtered_range_data_in_local,
@ -107,13 +107,13 @@ class LocalTrajectoryBuilder3D {
int num_accumulated_ = 0;
sensor::RangeData accumulated_range_data_;
common::optional<std::chrono::steady_clock::time_point> last_wall_time_;
absl::optional<std::chrono::steady_clock::time_point> last_wall_time_;
common::optional<double> last_thread_cpu_time_seconds_;
absl::optional<double> last_thread_cpu_time_seconds_;
RangeDataCollator range_data_collator_;
common::optional<common::Time> last_sensor_time_;
absl::optional<common::Time> last_sensor_time_;
};
} // namespace mapping

View File

@ -888,7 +888,7 @@ MapById<NodeId, TrajectoryNodePose> PoseGraph3D::GetTrajectoryNodePoses()
MapById<NodeId, TrajectoryNodePose> node_poses;
common::MutexLocker locker(&mutex_);
for (const auto& node_id_data : data_.trajectory_nodes) {
common::optional<TrajectoryNodePose::ConstantPoseData> constant_pose_data;
absl::optional<TrajectoryNodePose::ConstantPoseData> constant_pose_data;
if (node_id_data.data.constant_data != nullptr) {
constant_pose_data = TrajectoryNodePose::ConstantPoseData{
node_id_data.data.constant_data->time,

View File

@ -24,7 +24,7 @@
#include "Eigen/Core"
#include "Eigen/Geometry"
#include "cartographer/common/optional.h"
#include "absl/types/optional.h"
#include "cartographer/common/port.h"
#include "cartographer/common/time.h"
#include "cartographer/mapping/id.h"

View File

@ -20,7 +20,7 @@
#include <chrono>
#include <vector>
#include "cartographer/common/optional.h"
#include "absl/types/optional.h"
#include "cartographer/mapping/id.h"
#include "cartographer/mapping/submaps.h"
#include "cartographer/transform/rigid_transform.h"
@ -61,7 +61,7 @@ class PoseGraphInterface {
double rotation_weight;
};
std::vector<LandmarkObservation> landmark_observations;
common::optional<transform::Rigid3d> global_landmark_pose;
absl::optional<transform::Rigid3d> global_landmark_pose;
};
struct SubmapPose {
@ -77,7 +77,7 @@ class PoseGraphInterface {
struct TrajectoryData {
double gravity_constant = 9.8;
std::array<double, 4> imu_calibration{{1., 0., 0., 0.}};
common::optional<transform::Rigid3d> fixed_frame_origin_in_map;
absl::optional<transform::Rigid3d> fixed_frame_origin_in_map;
};
enum class TrajectoryState { ACTIVE, FINISHED, FROZEN, DELETED };

View File

@ -21,7 +21,7 @@
#include <vector>
#include "Eigen/Core"
#include "cartographer/common/optional.h"
#include "absl/types/optional.h"
#include "cartographer/common/time.h"
#include "cartographer/mapping/proto/trajectory_node_data.pb.h"
#include "cartographer/sensor/range_data.h"
@ -38,7 +38,7 @@ struct TrajectoryNodePose {
// The node pose in the global SLAM frame.
transform::Rigid3d global_pose;
common::optional<ConstantPoseData> constant_pose_data;
absl::optional<ConstantPoseData> constant_pose_data;
};
struct TrajectoryNode {

View File

@ -22,7 +22,7 @@
#include <unordered_set>
#include <vector>
#include "cartographer/common/optional.h"
#include "absl/types/optional.h"
#include "cartographer/sensor/data.h"
namespace cartographer {
@ -61,7 +61,7 @@ class CollatorInterface {
// the ID of the trajectory that needs more data before CollatorInterface is
// unblocked. Returns 'nullopt' for implementations that do not wait for a
// particular trajectory.
virtual common::optional<int> GetBlockingTrajectoryId() const = 0;
virtual absl::optional<int> GetBlockingTrajectoryId() const = 0;
};
} // namespace sensor

View File

@ -16,7 +16,7 @@
#include "cartographer/sensor/fixed_frame_pose_data.h"
#include "cartographer/common/optional.h"
#include "absl/types/optional.h"
#include "cartographer/transform/transform.h"
namespace cartographer {
@ -34,9 +34,9 @@ proto::FixedFramePoseData ToProto(const FixedFramePoseData& pose_data) {
FixedFramePoseData FromProto(const proto::FixedFramePoseData& proto) {
return FixedFramePoseData{common::FromUniversal(proto.timestamp()),
proto.has_pose()
? common::optional<transform::Rigid3d>(
? absl::optional<transform::Rigid3d>(
transform::ToRigid3(proto.pose()))
: common::optional<transform::Rigid3d>()};
: absl::optional<transform::Rigid3d>()};
}
} // namespace sensor

View File

@ -19,7 +19,7 @@
#include <memory>
#include "cartographer/common/optional.h"
#include "absl/types/optional.h"
#include "cartographer/common/time.h"
#include "cartographer/sensor/proto/sensor.pb.h"
#include "cartographer/transform/rigid_transform.h"
@ -31,7 +31,7 @@ namespace sensor {
// optimization.
struct FixedFramePoseData {
common::Time time;
common::optional<transform::Rigid3d> pose;
absl::optional<transform::Rigid3d> pose;
};
// Converts 'pose_data' to a proto::FixedFramePoseData.

View File

@ -47,8 +47,8 @@ void Collator::AddSensorData(const int trajectory_id,
void Collator::Flush() { queue_.Flush(); }
common::optional<int> Collator::GetBlockingTrajectoryId() const {
return common::optional<int>(queue_.GetBlocker().trajectory_id);
absl::optional<int> Collator::GetBlockingTrajectoryId() const {
return absl::optional<int>(queue_.GetBlocker().trajectory_id);
}
} // namespace sensor

View File

@ -47,7 +47,7 @@ class Collator : public CollatorInterface {
void Flush() override;
common::optional<int> GetBlockingTrajectoryId() const override;
absl::optional<int> GetBlockingTrajectoryId() const override;
private:
// Queue keys are a pair of trajectory ID and sensor identifier.

View File

@ -53,8 +53,8 @@ void TrajectoryCollator::Flush() {
}
}
common::optional<int> TrajectoryCollator::GetBlockingTrajectoryId() const {
return common::optional<int>();
absl::optional<int> TrajectoryCollator::GetBlockingTrajectoryId() const {
return absl::optional<int>();
}
} // namespace sensor

View File

@ -50,7 +50,7 @@ class TrajectoryCollator : public CollatorInterface {
void Flush() override;
common::optional<int> GetBlockingTrajectoryId() const override;
absl::optional<int> GetBlockingTrajectoryId() const override;
private:
std::unordered_map<int, OrderedMultiQueue> trajectory_to_queue_;

View File

@ -54,11 +54,20 @@ if(NOT TARGET standalone_absl)
"${ABSEIL_PROJECT_BUILD_DIR}/absl/types/libabsl_variant.a"
"${ABSEIL_PROJECT_BUILD_DIR}/absl/utility/libabsl_utility.a"
)
if(CMAKE_GENERATOR MATCHES "Ninja")
set (ABSL_BUILD_COMMAND "ninja")
else()
set (ABSL_BUILD_COMMAND "make")
endif()
ExternalProject_Add(${ABSEIL_PROJECT_NAME}
PREFIX ${ABSEIL_PROJECT_NAME}
GIT_REPOSITORY https://github.com/abseil/abseil-cpp.git
GIT_TAG 44aa275286baf97fc13529aca547a88b180beb08
INSTALL_COMMAND ""
BUILD_ALWAYS TRUE
BUILD_COMMAND ${ABSEIL_BUILD_COMMAND}
CMAKE_CACHE_ARGS "-DCMAKE_POSITION_INDEPENDENT_CODE:BOOL=ON;-DBUILD_TESTING:BOOL=OFF;-DCMAKE_BUILD_TYPE:STRING=Release"
BUILD_BYPRODUCTS "${ABSEIL_LIBRARY_PATH};${ABSEIL_DEPENDENT_LIBRARIES}"
)