Follow the Absl update. (#955)
parent
15dece61af
commit
2910529446
|
@ -46,6 +46,7 @@ find_package(catkin REQUIRED COMPONENTS ${PACKAGE_DEPENDENCIES})
|
|||
|
||||
include(FindPkgConfig)
|
||||
|
||||
find_package(Abseil REQUIRED)
|
||||
find_package(LuaGoogle REQUIRED)
|
||||
find_package(PCL REQUIRED COMPONENTS common)
|
||||
find_package(Eigen3 REQUIRED)
|
||||
|
|
|
@ -20,8 +20,8 @@
|
|||
#include <fstream>
|
||||
#include <iostream>
|
||||
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer/common/configuration_file_resolver.h"
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "cartographer/common/math.h"
|
||||
#include "cartographer/io/file_writer.h"
|
||||
#include "cartographer/io/points_processor.h"
|
||||
|
@ -61,8 +61,7 @@ CreatePipelineBuilder(
|
|||
const std::string file_prefix) {
|
||||
const auto file_writer_factory =
|
||||
AssetsWriter::CreateFileWriterFactory(file_prefix);
|
||||
auto builder =
|
||||
carto::common::make_unique<carto::io::PointsProcessorPipelineBuilder>();
|
||||
auto builder = absl::make_unique<carto::io::PointsProcessorPipelineBuilder>();
|
||||
carto::io::RegisterBuiltInPointsProcessors(trajectories, file_writer_factory,
|
||||
builder.get());
|
||||
builder->Register(RosMapWritingPointsProcessor::kConfigurationFileActionName,
|
||||
|
@ -80,13 +79,13 @@ std::unique_ptr<carto::common::LuaParameterDictionary> LoadLuaDictionary(
|
|||
const std::string& configuration_directory,
|
||||
const std::string& configuration_basename) {
|
||||
auto file_resolver =
|
||||
carto::common::make_unique<carto::common::ConfigurationFileResolver>(
|
||||
absl::make_unique<carto::common::ConfigurationFileResolver>(
|
||||
std::vector<std::string>{configuration_directory});
|
||||
|
||||
const std::string code =
|
||||
file_resolver->GetFileContentOrDie(configuration_basename);
|
||||
auto lua_parameter_dictionary =
|
||||
carto::common::make_unique<carto::common::LuaParameterDictionary>(
|
||||
absl::make_unique<carto::common::LuaParameterDictionary>(
|
||||
code, std::move(file_resolver));
|
||||
return lua_parameter_dictionary;
|
||||
}
|
||||
|
@ -99,7 +98,7 @@ std::unique_ptr<carto::io::PointsBatch> HandleMessage(
|
|||
transform_interpolation_buffer) {
|
||||
const carto::common::Time start_time = FromRos(message.header.stamp);
|
||||
|
||||
auto points_batch = carto::common::make_unique<carto::io::PointsBatch>();
|
||||
auto points_batch = absl::make_unique<carto::io::PointsBatch>();
|
||||
points_batch->start_time = start_time;
|
||||
points_batch->frame_id = message.header.frame_id;
|
||||
|
||||
|
@ -264,8 +263,7 @@ void AssetsWriter::Run(const std::string& configuration_directory,
|
|||
::cartographer::io::FileWriterFactory AssetsWriter::CreateFileWriterFactory(
|
||||
const std::string& file_path) {
|
||||
const auto file_writer_factory = [file_path](const std::string& filename) {
|
||||
return carto::common::make_unique<carto::io::StreamFileWriter>(file_path +
|
||||
filename);
|
||||
return absl::make_unique<carto::io::StreamFileWriter>(file_path + filename);
|
||||
};
|
||||
return file_writer_factory;
|
||||
}
|
||||
|
|
|
@ -14,8 +14,8 @@
|
|||
* limitations under the License.
|
||||
*/
|
||||
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer/cloud/client/map_builder_stub.h"
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "cartographer_ros/node.h"
|
||||
#include "cartographer_ros/node_options.h"
|
||||
#include "cartographer_ros/ros_log_sink.h"
|
||||
|
@ -59,9 +59,8 @@ void Run() {
|
|||
std::tie(node_options, trajectory_options) =
|
||||
LoadOptions(FLAGS_configuration_directory, FLAGS_configuration_basename);
|
||||
|
||||
auto map_builder =
|
||||
cartographer::common::make_unique<::cartographer::cloud::MapBuilderStub>(
|
||||
FLAGS_server_address, FLAGS_client_id);
|
||||
auto map_builder = absl::make_unique<::cartographer::cloud::MapBuilderStub>(
|
||||
FLAGS_server_address, FLAGS_client_id);
|
||||
Node node(node_options, std::move(map_builder), &tf_buffer,
|
||||
FLAGS_collect_metrics);
|
||||
|
||||
|
|
|
@ -39,9 +39,8 @@ int main(int argc, char** argv) {
|
|||
|
||||
const cartographer_ros::MapBuilderFactory map_builder_factory =
|
||||
[](const ::cartographer::mapping::proto::MapBuilderOptions&) {
|
||||
return ::cartographer::common::make_unique<
|
||||
::cartographer::cloud::MapBuilderStub>(FLAGS_server_address,
|
||||
FLAGS_client_id);
|
||||
return absl::make_unique< ::cartographer::cloud::MapBuilderStub>(
|
||||
FLAGS_server_address, FLAGS_client_id);
|
||||
};
|
||||
|
||||
cartographer_ros::RunOfflineNode(map_builder_factory);
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
|
||||
#include "cartographer_ros/map_builder_bridge.h"
|
||||
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer/io/color.h"
|
||||
#include "cartographer/io/proto_stream.h"
|
||||
#include "cartographer/mapping/pose_graph.h"
|
||||
|
@ -135,12 +135,11 @@ int MapBuilderBridge::AddTrajectory(
|
|||
|
||||
// Make sure there is no trajectory with 'trajectory_id' yet.
|
||||
CHECK_EQ(sensor_bridges_.count(trajectory_id), 0);
|
||||
sensor_bridges_[trajectory_id] =
|
||||
cartographer::common::make_unique<SensorBridge>(
|
||||
trajectory_options.num_subdivisions_per_laser_scan,
|
||||
trajectory_options.tracking_frame,
|
||||
node_options_.lookup_transform_timeout_sec, tf_buffer_,
|
||||
map_builder_->GetTrajectoryBuilder(trajectory_id));
|
||||
sensor_bridges_[trajectory_id] = absl::make_unique<SensorBridge>(
|
||||
trajectory_options.num_subdivisions_per_laser_scan,
|
||||
trajectory_options.tracking_frame,
|
||||
node_options_.lookup_transform_timeout_sec, tf_buffer_,
|
||||
map_builder_->GetTrajectoryBuilder(trajectory_id));
|
||||
auto emplace_result =
|
||||
trajectory_options_.emplace(trajectory_id, trajectory_options);
|
||||
CHECK(emplace_result.second == true);
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
|
||||
#include "cartographer_ros/metrics/family_factory.h"
|
||||
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "absl/memory/memory.h"
|
||||
|
||||
namespace cartographer_ros {
|
||||
namespace metrics {
|
||||
|
@ -26,8 +26,7 @@ using BucketBoundaries = ::cartographer::metrics::Histogram::BucketBoundaries;
|
|||
::cartographer::metrics::Family<::cartographer::metrics::Counter>*
|
||||
FamilyFactory::NewCounterFamily(const std::string& name,
|
||||
const std::string& description) {
|
||||
auto wrapper =
|
||||
::cartographer::common::make_unique<CounterFamily>(name, description);
|
||||
auto wrapper = absl::make_unique<CounterFamily>(name, description);
|
||||
auto* ptr = wrapper.get();
|
||||
counter_families_.emplace_back(std::move(wrapper));
|
||||
return ptr;
|
||||
|
@ -36,8 +35,7 @@ FamilyFactory::NewCounterFamily(const std::string& name,
|
|||
::cartographer::metrics::Family<::cartographer::metrics::Gauge>*
|
||||
FamilyFactory::NewGaugeFamily(const std::string& name,
|
||||
const std::string& description) {
|
||||
auto wrapper =
|
||||
::cartographer::common::make_unique<GaugeFamily>(name, description);
|
||||
auto wrapper = absl::make_unique<GaugeFamily>(name, description);
|
||||
auto* ptr = wrapper.get();
|
||||
gauge_families_.emplace_back(std::move(wrapper));
|
||||
return ptr;
|
||||
|
@ -47,8 +45,8 @@ FamilyFactory::NewGaugeFamily(const std::string& name,
|
|||
FamilyFactory::NewHistogramFamily(const std::string& name,
|
||||
const std::string& description,
|
||||
const BucketBoundaries& boundaries) {
|
||||
auto wrapper = ::cartographer::common::make_unique<HistogramFamily>(
|
||||
name, description, boundaries);
|
||||
auto wrapper =
|
||||
absl::make_unique<HistogramFamily>(name, description, boundaries);
|
||||
auto* ptr = wrapper.get();
|
||||
histogram_families_.emplace_back(std::move(wrapper));
|
||||
return ptr;
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
|
||||
#include "cartographer_ros/metrics/internal/family.h"
|
||||
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer_ros/metrics/internal/counter.h"
|
||||
#include "cartographer_ros/metrics/internal/gauge.h"
|
||||
#include "cartographer_ros/metrics/internal/histogram.h"
|
||||
|
@ -27,7 +27,7 @@ namespace metrics {
|
|||
using BucketBoundaries = ::cartographer::metrics::Histogram::BucketBoundaries;
|
||||
|
||||
Counter* CounterFamily::Add(const std::map<std::string, std::string>& labels) {
|
||||
auto wrapper = ::cartographer::common::make_unique<Counter>(labels);
|
||||
auto wrapper = absl::make_unique<Counter>(labels);
|
||||
auto* ptr = wrapper.get();
|
||||
wrappers_.emplace_back(std::move(wrapper));
|
||||
return ptr;
|
||||
|
@ -44,7 +44,7 @@ cartographer_ros_msgs::MetricFamily CounterFamily::ToRosMessage() {
|
|||
}
|
||||
|
||||
Gauge* GaugeFamily::Add(const std::map<std::string, std::string>& labels) {
|
||||
auto wrapper = ::cartographer::common::make_unique<Gauge>(labels);
|
||||
auto wrapper = absl::make_unique<Gauge>(labels);
|
||||
auto* ptr = wrapper.get();
|
||||
wrappers_.emplace_back(std::move(wrapper));
|
||||
return ptr;
|
||||
|
@ -62,8 +62,7 @@ cartographer_ros_msgs::MetricFamily GaugeFamily::ToRosMessage() {
|
|||
|
||||
Histogram* HistogramFamily::Add(
|
||||
const std::map<std::string, std::string>& labels) {
|
||||
auto wrapper =
|
||||
::cartographer::common::make_unique<Histogram>(labels, boundaries_);
|
||||
auto wrapper = absl::make_unique<Histogram>(labels, boundaries_);
|
||||
auto* ptr = wrapper.get();
|
||||
wrappers_.emplace_back(std::move(wrapper));
|
||||
return ptr;
|
||||
|
|
|
@ -369,8 +369,7 @@ std::unique_ptr<nav_msgs::OccupancyGrid> CreateOccupancyGridMsg(
|
|||
const cartographer::io::PaintSubmapSlicesResult& painted_slices,
|
||||
const double resolution, const std::string& frame_id,
|
||||
const ros::Time& time) {
|
||||
auto occupancy_grid =
|
||||
::cartographer::common::make_unique<nav_msgs::OccupancyGrid>();
|
||||
auto occupancy_grid = absl::make_unique<nav_msgs::OccupancyGrid>();
|
||||
|
||||
const int width = cairo_image_surface_get_width(painted_slices.surface.get());
|
||||
const int height =
|
||||
|
|
|
@ -21,9 +21,9 @@
|
|||
#include <vector>
|
||||
|
||||
#include "Eigen/Core"
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer/common/configuration_file_resolver.h"
|
||||
#include "cartographer/common/lua_parameter_dictionary.h"
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "cartographer/common/port.h"
|
||||
#include "cartographer/common/time.h"
|
||||
#include "cartographer/mapping/pose_graph_interface.h"
|
||||
|
@ -95,7 +95,7 @@ Node::Node(
|
|||
map_builder_bridge_(node_options_, std::move(map_builder), tf_buffer) {
|
||||
carto::common::MutexLocker lock(&mutex_);
|
||||
if (collect_metrics) {
|
||||
metrics_registry_ = carto::common::make_unique<metrics::FamilyFactory>();
|
||||
metrics_registry_ = absl::make_unique<metrics::FamilyFactory>();
|
||||
carto::metrics::RegisterAllMetrics(metrics_registry_.get());
|
||||
}
|
||||
|
||||
|
|
|
@ -14,7 +14,7 @@
|
|||
* limitations under the License.
|
||||
*/
|
||||
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer/mapping/map_builder.h"
|
||||
#include "cartographer_ros/node.h"
|
||||
#include "cartographer_ros/node_options.h"
|
||||
|
@ -56,9 +56,8 @@ void Run() {
|
|||
std::tie(node_options, trajectory_options) =
|
||||
LoadOptions(FLAGS_configuration_directory, FLAGS_configuration_basename);
|
||||
|
||||
auto map_builder =
|
||||
::cartographer::common::make_unique<cartographer::mapping::MapBuilder>(
|
||||
node_options.map_builder_options);
|
||||
auto map_builder = absl::make_unique<cartographer::mapping::MapBuilder>(
|
||||
node_options.map_builder_options);
|
||||
Node node(node_options, std::move(map_builder), &tf_buffer,
|
||||
FLAGS_collect_metrics);
|
||||
if (!FLAGS_load_state_filename.empty()) {
|
||||
|
|
|
@ -50,9 +50,9 @@ NodeOptions CreateNodeOptions(
|
|||
std::tuple<NodeOptions, TrajectoryOptions> LoadOptions(
|
||||
const std::string& configuration_directory,
|
||||
const std::string& configuration_basename) {
|
||||
auto file_resolver = cartographer::common::make_unique<
|
||||
cartographer::common::ConfigurationFileResolver>(
|
||||
std::vector<std::string>{configuration_directory});
|
||||
auto file_resolver =
|
||||
absl::make_unique<cartographer::common::ConfigurationFileResolver>(
|
||||
std::vector<std::string>{configuration_directory});
|
||||
const std::string code =
|
||||
file_resolver->GetFileContentOrDie(configuration_basename);
|
||||
cartographer::common::LuaParameterDictionary lua_parameter_dictionary(
|
||||
|
|
|
@ -32,8 +32,8 @@ int main(int argc, char** argv) {
|
|||
const cartographer_ros::MapBuilderFactory map_builder_factory =
|
||||
[](const ::cartographer::mapping::proto::MapBuilderOptions&
|
||||
map_builder_options) {
|
||||
return ::cartographer::common::make_unique<
|
||||
::cartographer::mapping::MapBuilder>(map_builder_options);
|
||||
return absl::make_unique< ::cartographer::mapping::MapBuilder>(
|
||||
map_builder_options);
|
||||
};
|
||||
|
||||
cartographer_ros::RunOfflineNode(map_builder_factory);
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
|
||||
#include "cartographer_ros/playable_bag.h"
|
||||
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer_ros/node_constants.h"
|
||||
#include "glog/logging.h"
|
||||
#include "tf2_msgs/TFMessage.h"
|
||||
|
@ -28,10 +28,8 @@ PlayableBag::PlayableBag(
|
|||
const ros::Time start_time, const ros::Time end_time,
|
||||
const ros::Duration buffer_delay,
|
||||
FilteringEarlyMessageHandler filtering_early_message_handler)
|
||||
: bag_(cartographer::common::make_unique<rosbag::Bag>(
|
||||
bag_filename, rosbag::bagmode::Read)),
|
||||
view_(cartographer::common::make_unique<rosbag::View>(*bag_, start_time,
|
||||
end_time)),
|
||||
: bag_(absl::make_unique<rosbag::Bag>(bag_filename, rosbag::bagmode::Read)),
|
||||
view_(absl::make_unique<rosbag::View>(*bag_, start_time, end_time)),
|
||||
view_iterator_(view_->begin()),
|
||||
finished_(false),
|
||||
bag_id_(bag_id),
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
|
||||
#include "cartographer_ros/ros_map_writing_points_processor.h"
|
||||
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer/io/image.h"
|
||||
#include "cartographer/io/probability_grid_points_processor.h"
|
||||
#include "cartographer_ros/ros_map.h"
|
||||
|
@ -42,7 +42,7 @@ RosMapWritingPointsProcessor::FromDictionary(
|
|||
::cartographer::io::FileWriterFactory file_writer_factory,
|
||||
::cartographer::common::LuaParameterDictionary* const dictionary,
|
||||
::cartographer::io::PointsProcessor* const next) {
|
||||
return ::cartographer::common::make_unique<RosMapWritingPointsProcessor>(
|
||||
return absl::make_unique<RosMapWritingPointsProcessor>(
|
||||
dictionary->GetDouble("resolution"),
|
||||
::cartographer::mapping::CreateProbabilityGridRangeDataInserterOptions2D(
|
||||
dictionary->GetDictionary("range_data_inserter").get()),
|
||||
|
|
|
@ -20,8 +20,8 @@
|
|||
#include <set>
|
||||
#include <string>
|
||||
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer/common/histogram.h"
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "cartographer_ros/msg_conversion.h"
|
||||
#include "gflags/gflags.h"
|
||||
#include "glog/logging.h"
|
||||
|
@ -72,7 +72,7 @@ const std::set<std::string> kPointDataTypes = {
|
|||
ros::message_traits::DataType<sensor_msgs::LaserScan>::value())};
|
||||
|
||||
std::unique_ptr<std::ofstream> CreateTimingFile(const std::string& frame_id) {
|
||||
auto timing_file = ::cartographer::common::make_unique<std::ofstream>(
|
||||
auto timing_file = absl::make_unique<std::ofstream>(
|
||||
std::string("timing_") + frame_id + ".csv", std::ios_base::out);
|
||||
|
||||
(*timing_file)
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
|
||||
#include "cartographer_ros/sensor_bridge.h"
|
||||
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer_ros/msg_conversion.h"
|
||||
#include "cartographer_ros/time_conversion.h"
|
||||
|
||||
|
@ -56,7 +56,7 @@ std::unique_ptr<carto::sensor::OdometryData> SensorBridge::ToOdometryData(
|
|||
if (sensor_to_tracking == nullptr) {
|
||||
return nullptr;
|
||||
}
|
||||
return carto::common::make_unique<carto::sensor::OdometryData>(
|
||||
return absl::make_unique<carto::sensor::OdometryData>(
|
||||
carto::sensor::OdometryData{
|
||||
time, ToRigid3d(msg->pose.pose) * sensor_to_tracking->inverse()});
|
||||
}
|
||||
|
@ -77,8 +77,8 @@ void SensorBridge::HandleNavSatFixMessage(
|
|||
const carto::common::Time time = FromRos(msg->header.stamp);
|
||||
if (msg->status.status == sensor_msgs::NavSatStatus::STATUS_NO_FIX) {
|
||||
trajectory_builder_->AddSensorData(
|
||||
sensor_id, carto::sensor::FixedFramePoseData{
|
||||
time, carto::common::optional<Rigid3d>()});
|
||||
sensor_id,
|
||||
carto::sensor::FixedFramePoseData{time, absl::optional<Rigid3d>()});
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -90,12 +90,11 @@ void SensorBridge::HandleNavSatFixMessage(
|
|||
}
|
||||
|
||||
trajectory_builder_->AddSensorData(
|
||||
sensor_id,
|
||||
carto::sensor::FixedFramePoseData{
|
||||
time, carto::common::optional<Rigid3d>(Rigid3d::Translation(
|
||||
ecef_to_local_frame_.value() *
|
||||
LatLongAltToEcef(msg->latitude, msg->longitude,
|
||||
msg->altitude)))});
|
||||
sensor_id, carto::sensor::FixedFramePoseData{
|
||||
time, absl::optional<Rigid3d>(Rigid3d::Translation(
|
||||
ecef_to_local_frame_.value() *
|
||||
LatLongAltToEcef(msg->latitude, msg->longitude,
|
||||
msg->altitude)))});
|
||||
}
|
||||
|
||||
void SensorBridge::HandleLandmarkMessage(
|
||||
|
@ -127,11 +126,9 @@ std::unique_ptr<carto::sensor::ImuData> SensorBridge::ToImuData(
|
|||
<< "The IMU frame must be colocated with the tracking frame. "
|
||||
"Transforming linear acceleration into the tracking frame will "
|
||||
"otherwise be imprecise.";
|
||||
return carto::common::make_unique<carto::sensor::ImuData>(
|
||||
carto::sensor::ImuData{
|
||||
time,
|
||||
sensor_to_tracking->rotation() * ToEigen(msg->linear_acceleration),
|
||||
sensor_to_tracking->rotation() * ToEigen(msg->angular_velocity)});
|
||||
return absl::make_unique<carto::sensor::ImuData>(carto::sensor::ImuData{
|
||||
time, sensor_to_tracking->rotation() * ToEigen(msg->linear_acceleration),
|
||||
sensor_to_tracking->rotation() * ToEigen(msg->angular_velocity)});
|
||||
}
|
||||
|
||||
void SensorBridge::HandleImuMessage(const std::string& sensor_id,
|
||||
|
|
|
@ -19,7 +19,7 @@
|
|||
|
||||
#include <memory>
|
||||
|
||||
#include "cartographer/common/optional.h"
|
||||
#include "absl/types/optional.h"
|
||||
#include "cartographer/mapping/trajectory_builder_interface.h"
|
||||
#include "cartographer/sensor/imu_data.h"
|
||||
#include "cartographer/sensor/odometry_data.h"
|
||||
|
@ -91,8 +91,7 @@ class SensorBridge {
|
|||
::cartographer::mapping::TrajectoryBuilderInterface* const
|
||||
trajectory_builder_;
|
||||
|
||||
::cartographer::common::optional<::cartographer::transform::Rigid3d>
|
||||
ecef_to_local_frame_;
|
||||
absl::optional<::cartographer::transform::Rigid3d> ecef_to_local_frame_;
|
||||
};
|
||||
|
||||
} // namespace cartographer_ros
|
||||
|
|
|
@ -17,9 +17,9 @@
|
|||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer/common/configuration_file_resolver.h"
|
||||
#include "cartographer/common/lua_parameter_dictionary.h"
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "cartographer/common/port.h"
|
||||
#include "cartographer_ros/node_constants.h"
|
||||
#include "cartographer_ros/ros_log_sink.h"
|
||||
|
@ -44,9 +44,9 @@ namespace cartographer_ros {
|
|||
namespace {
|
||||
|
||||
TrajectoryOptions LoadOptions() {
|
||||
auto file_resolver = cartographer::common::make_unique<
|
||||
cartographer::common::ConfigurationFileResolver>(
|
||||
std::vector<std::string>{FLAGS_configuration_directory});
|
||||
auto file_resolver =
|
||||
absl::make_unique<cartographer::common::ConfigurationFileResolver>(
|
||||
std::vector<std::string>{FLAGS_configuration_directory});
|
||||
const std::string code =
|
||||
file_resolver->GetFileContentOrDie(FLAGS_configuration_basename);
|
||||
auto lua_parameter_dictionary =
|
||||
|
@ -54,8 +54,7 @@ TrajectoryOptions LoadOptions() {
|
|||
code, std::move(file_resolver));
|
||||
if (!FLAGS_initial_pose.empty()) {
|
||||
auto initial_trajectory_pose_file_resolver =
|
||||
cartographer::common::make_unique<
|
||||
cartographer::common::ConfigurationFileResolver>(
|
||||
absl::make_unique<cartographer::common::ConfigurationFileResolver>(
|
||||
std::vector<std::string>{FLAGS_configuration_directory});
|
||||
auto initial_trajectory_pose =
|
||||
cartographer::common::LuaParameterDictionary::NonReferenceCounted(
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
|
||||
#include "cartographer_ros/submap.h"
|
||||
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer/common/port.h"
|
||||
#include "cartographer/transform/transform.h"
|
||||
#include "cartographer_ros/msg_conversion.h"
|
||||
|
@ -38,8 +38,7 @@ std::unique_ptr<::cartographer::io::SubmapTextures> FetchSubmapTextures(
|
|||
if (srv.response.textures.empty()) {
|
||||
return nullptr;
|
||||
}
|
||||
auto response =
|
||||
::cartographer::common::make_unique<::cartographer::io::SubmapTextures>();
|
||||
auto response = absl::make_unique<::cartographer::io::SubmapTextures>();
|
||||
response->version = srv.response.submap_version;
|
||||
for (const auto& texture : srv.response.textures) {
|
||||
const std::string compressed_cells(texture.cells.begin(),
|
||||
|
|
|
@ -14,7 +14,7 @@
|
|||
* limitations under the License.
|
||||
*/
|
||||
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "absl/memory/memory.h"
|
||||
|
||||
#include "cartographer_ros/msg_conversion.h"
|
||||
#include "cartographer_ros/tf_bridge.h"
|
||||
|
@ -45,9 +45,9 @@ std::unique_ptr<::cartographer::transform::Rigid3d> TfBridge::LookupToTracking(
|
|||
// for the full 'timeout' even if we ask for data that is too old.
|
||||
timeout = ::ros::Duration(0.);
|
||||
}
|
||||
return ::cartographer::common::make_unique<
|
||||
::cartographer::transform::Rigid3d>(ToRigid3d(buffer_->lookupTransform(
|
||||
tracking_frame_, frame_id, requested_time, timeout)));
|
||||
return absl::make_unique<::cartographer::transform::Rigid3d>(
|
||||
ToRigid3d(buffer_->lookupTransform(tracking_frame_, frame_id,
|
||||
requested_time, timeout)));
|
||||
} catch (const tf2::TransformException& ex) {
|
||||
LOG(WARNING) << ex.what();
|
||||
}
|
||||
|
|
|
@ -30,6 +30,7 @@ find_package(cartographer REQUIRED)
|
|||
include("${CARTOGRAPHER_CMAKE_DIR}/functions.cmake")
|
||||
google_initialize_cartographer_project()
|
||||
|
||||
find_package(Abseil REQUIRED)
|
||||
find_package(Eigen3 REQUIRED)
|
||||
find_package(Boost REQUIRED COMPONENTS system iostreams)
|
||||
find_package(catkin REQUIRED COMPONENTS ${PACKAGE_DEPENDENCIES})
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
|
||||
#include "Eigen/Core"
|
||||
#include "Eigen/Geometry"
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer/common/port.h"
|
||||
#include "cartographer_ros/msg_conversion.h"
|
||||
#include "cartographer_ros_msgs/SubmapQuery.h"
|
||||
|
@ -63,14 +63,14 @@ DrawableSubmap::DrawableSubmap(const ::cartographer::mapping::SubmapId& id,
|
|||
last_query_timestamp_(0) {
|
||||
for (int slice_index = 0; slice_index < kNumberOfSlicesPerSubmap;
|
||||
++slice_index) {
|
||||
ogre_slices_.emplace_back(::cartographer::common::make_unique<OgreSlice>(
|
||||
ogre_slices_.emplace_back(absl::make_unique<OgreSlice>(
|
||||
id, slice_index, display_context->getSceneManager(), submap_node_));
|
||||
}
|
||||
// DrawableSubmap creates and manages its visibility property object
|
||||
// (a unique_ptr is needed because the Qt parent of the visibility
|
||||
// property is the submap_category object - the BoolProperty needs
|
||||
// to be destroyed along with the DrawableSubmap)
|
||||
visibility_ = ::cartographer::common::make_unique<::rviz::BoolProperty>(
|
||||
visibility_ = absl::make_unique<::rviz::BoolProperty>(
|
||||
"" /* title */, visible, "" /* description */, submap_category,
|
||||
SLOT(ToggleVisibility()), this);
|
||||
submap_id_text_.setCharacterHeight(kSubmapIdCharHeight);
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
#include "cartographer_rviz/submaps_display.h"
|
||||
|
||||
#include "OgreResourceGroupManager.h"
|
||||
#include "cartographer/common/make_unique.h"
|
||||
#include "absl/memory/memory.h"
|
||||
#include "cartographer/common/mutex.h"
|
||||
#include "cartographer/mapping/id.h"
|
||||
#include "cartographer_ros_msgs/SubmapList.h"
|
||||
|
@ -112,8 +112,7 @@ void SubmapsDisplay::reset() {
|
|||
void SubmapsDisplay::processMessage(
|
||||
const ::cartographer_ros_msgs::SubmapList::ConstPtr& msg) {
|
||||
::cartographer::common::MutexLocker locker(&mutex_);
|
||||
map_frame_ =
|
||||
::cartographer::common::make_unique<std::string>(msg->header.frame_id);
|
||||
map_frame_ = absl::make_unique<std::string>(msg->header.frame_id);
|
||||
// In case Cartographer node is relaunched, destroy trajectories from the
|
||||
// previous instance.
|
||||
for (const ::cartographer_ros_msgs::SubmapEntry& submap_entry : msg->submap) {
|
||||
|
@ -136,8 +135,8 @@ void SubmapsDisplay::processMessage(
|
|||
const SubmapId id{submap_entry.trajectory_id, submap_entry.submap_index};
|
||||
listed_submaps.insert(id);
|
||||
while (id.trajectory_id >= static_cast<int>(trajectories_.size())) {
|
||||
trajectories_.push_back(::cartographer::common::make_unique<Trajectory>(
|
||||
::cartographer::common::make_unique<::rviz::BoolProperty>(
|
||||
trajectories_.push_back(
|
||||
absl::make_unique<Trajectory>(absl::make_unique<::rviz::BoolProperty>(
|
||||
QString("Trajectory %1").arg(id.trajectory_id),
|
||||
visibility_all_enabled_->getBool(),
|
||||
QString("List of all submaps in Trajectory %1. The checkbox "
|
||||
|
@ -154,7 +153,7 @@ void SubmapsDisplay::processMessage(
|
|||
constexpr float kSubmapPoseAxesRadius = 0.06f;
|
||||
trajectory_submaps.emplace(
|
||||
id.submap_index,
|
||||
::cartographer::common::make_unique<DrawableSubmap>(
|
||||
absl::make_unique<DrawableSubmap>(
|
||||
id, context_, map_node_, trajectory_visibility.get(),
|
||||
trajectory_visibility->getBool(), kSubmapPoseAxesLength,
|
||||
kSubmapPoseAxesRadius));
|
||||
|
|
Loading…
Reference in New Issue