From f6192e4735969ad2e6fa0fc2964f924da47b066d Mon Sep 17 00:00:00 2001 From: catskul Date: Wed, 15 Nov 2017 04:17:59 -0500 Subject: [PATCH] replace implicit use of cartographer::string with explicit use of std::string (#673) Fixes #622. --- .../common/configuration_file_resolver.cc | 16 +++-- .../common/configuration_file_resolver.h | 8 +-- .../common/configuration_files_test.cc | 16 ++--- cartographer/common/fixed_ratio_sampler.cc | 2 +- cartographer/common/fixed_ratio_sampler.h | 2 +- cartographer/common/histogram.cc | 10 +-- cartographer/common/histogram.h | 2 +- .../common/lua_parameter_dictionary.cc | 66 ++++++++++--------- .../common/lua_parameter_dictionary.h | 43 ++++++------ .../common/lua_parameter_dictionary_test.cc | 14 ++-- .../lua_parameter_dictionary_test_helpers.h | 7 +- cartographer/common/port.h | 8 +-- cartographer/common/rate_timer.h | 4 +- .../autogenerate_ground_truth_main.cc | 4 +- .../compute_relations_metrics_main.cc | 9 +-- .../ground_truth/relations_text_file.cc | 3 +- .../ground_truth/relations_text_file.h | 2 +- cartographer/io/coloring_points_processor.cc | 4 +- cartographer/io/coloring_points_processor.h | 4 +- cartographer/io/file_writer.cc | 4 +- cartographer/io/file_writer.h | 10 +-- .../io/frame_id_filtering_points_processor.cc | 12 ++-- .../io/frame_id_filtering_points_processor.h | 9 +-- .../io/hybrid_grid_points_processor.cc | 2 +- .../io/intensity_to_color_points_processor.cc | 4 +- .../io/intensity_to_color_points_processor.h | 4 +- .../io/pcd_writing_points_processor.cc | 10 +-- .../io/ply_writing_points_processor.cc | 10 +-- cartographer/io/points_batch.h | 2 +- .../io/points_processor_pipeline_builder.cc | 2 +- .../points_processor_pipeline_builder_test.cc | 2 +- cartographer/io/proto_stream.cc | 12 ++-- cartographer/io/proto_stream.h | 12 ++-- cartographer/io/proto_stream_test.cc | 6 +- cartographer/io/xray_points_processor.cc | 3 +- cartographer/io/xray_points_processor.h | 5 +- .../io/xyz_writing_points_processor.cc | 2 +- .../mapping/collated_trajectory_builder.cc | 8 +-- .../mapping/collated_trajectory_builder.h | 8 +-- cartographer/mapping/map_builder.cc | 7 +- cartographer/mapping/map_builder.h | 6 +- cartographer/mapping/trajectory_builder.h | 10 +-- cartographer/mapping_2d/submaps.cc | 2 +- .../scan_matching/ceres_scan_matcher.cc | 3 +- cartographer/mapping_3d/submaps.cc | 6 +- cartographer/sensor/collator.cc | 5 +- cartographer/sensor/collator.h | 7 +- cartographer/sensor/collator_test.cc | 8 +-- .../sensor/compressed_point_cloud_test.cc | 2 +- cartographer/sensor/landmark_data.h | 2 +- cartographer/sensor/ordered_multi_queue.h | 2 +- cartographer/transform/rigid_transform.h | 8 +-- .../transform/rigid_transform_test_helpers.h | 4 +- 53 files changed, 220 insertions(+), 203 deletions(-) diff --git a/cartographer/common/configuration_file_resolver.cc b/cartographer/common/configuration_file_resolver.cc index 0b593f8..9774caf 100644 --- a/cartographer/common/configuration_file_resolver.cc +++ b/cartographer/common/configuration_file_resolver.cc @@ -27,14 +27,15 @@ namespace cartographer { namespace common { ConfigurationFileResolver::ConfigurationFileResolver( - const std::vector& configuration_files_directories) + const std::vector& configuration_files_directories) : configuration_files_directories_(configuration_files_directories) { configuration_files_directories_.push_back(kConfigurationFilesDirectory); } -string ConfigurationFileResolver::GetFullPathOrDie(const string& basename) { +std::string ConfigurationFileResolver::GetFullPathOrDie( + const std::string& basename) { for (const auto& path : configuration_files_directories_) { - const string filename = path + "/" + basename; + const std::string filename = path + "/" + basename; std::ifstream stream(filename.c_str()); if (stream.good()) { LOG(INFO) << "Found '" << filename << "' for '" << basename << "'."; @@ -44,11 +45,12 @@ string ConfigurationFileResolver::GetFullPathOrDie(const string& basename) { LOG(FATAL) << "File '" << basename << "' was not found."; } -string ConfigurationFileResolver::GetFileContentOrDie(const string& basename) { - const string filename = GetFullPathOrDie(basename); +std::string ConfigurationFileResolver::GetFileContentOrDie( + const std::string& basename) { + const std::string filename = GetFullPathOrDie(basename); std::ifstream stream(filename.c_str()); - return string((std::istreambuf_iterator(stream)), - std::istreambuf_iterator()); + return std::string((std::istreambuf_iterator(stream)), + std::istreambuf_iterator()); } } // namespace common diff --git a/cartographer/common/configuration_file_resolver.h b/cartographer/common/configuration_file_resolver.h index 346a5d6..5005cdf 100644 --- a/cartographer/common/configuration_file_resolver.h +++ b/cartographer/common/configuration_file_resolver.h @@ -34,13 +34,13 @@ namespace common { class ConfigurationFileResolver : public FileResolver { public: explicit ConfigurationFileResolver( - const std::vector& configuration_files_directories); + const std::vector& configuration_files_directories); - string GetFullPathOrDie(const string& basename) override; - string GetFileContentOrDie(const string& basename) override; + std::string GetFullPathOrDie(const std::string& basename) override; + std::string GetFileContentOrDie(const std::string& basename) override; private: - std::vector configuration_files_directories_; + std::vector configuration_files_directories_; }; } // namespace common diff --git a/cartographer/common/configuration_files_test.cc b/cartographer/common/configuration_files_test.cc index 3aeeeba..8db4b4a 100644 --- a/cartographer/common/configuration_files_test.cc +++ b/cartographer/common/configuration_files_test.cc @@ -23,21 +23,20 @@ #include "cartographer/mapping/map_builder.h" #include "gtest/gtest.h" -using std::string; - namespace cartographer_ros { namespace { TEST(ConfigurationFilesTest, ValidateMapBuilderOptions) { - const string kCode = R"text( + const std::string kCode = R"text( include "map_builder.lua" 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{string(::cartographer::common::kSourceDirectory) + - "/configuration_files"}); + std::vector{ + std::string(::cartographer::common::kSourceDirectory) + + "/configuration_files"}); ::cartographer::common::LuaParameterDictionary lua_parameter_dictionary( kCode, std::move(file_resolver)); ::cartographer::mapping::CreateMapBuilderOptions(&lua_parameter_dictionary); @@ -45,15 +44,16 @@ TEST(ConfigurationFilesTest, ValidateMapBuilderOptions) { } TEST(ConfigurationFilesTest, ValidateTrajectoryBuilderOptions) { - const string kCode = R"text( + const std::string kCode = R"text( include "trajectory_builder.lua" 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{string(::cartographer::common::kSourceDirectory) + - "/configuration_files"}); + std::vector{ + std::string(::cartographer::common::kSourceDirectory) + + "/configuration_files"}); ::cartographer::common::LuaParameterDictionary lua_parameter_dictionary( kCode, std::move(file_resolver)); ::cartographer::mapping::CreateTrajectoryBuilderOptions( diff --git a/cartographer/common/fixed_ratio_sampler.cc b/cartographer/common/fixed_ratio_sampler.cc index 5f466a1..ec164e0 100644 --- a/cartographer/common/fixed_ratio_sampler.cc +++ b/cartographer/common/fixed_ratio_sampler.cc @@ -37,7 +37,7 @@ bool FixedRatioSampler::Pulse() { return false; } -string FixedRatioSampler::DebugString() { +std::string FixedRatioSampler::DebugString() { return std::to_string(num_samples_) + " (" + std::to_string(100. * num_samples_ / num_pulses_) + "%)"; } diff --git a/cartographer/common/fixed_ratio_sampler.h b/cartographer/common/fixed_ratio_sampler.h index f67d5b2..3e00f9e 100644 --- a/cartographer/common/fixed_ratio_sampler.h +++ b/cartographer/common/fixed_ratio_sampler.h @@ -38,7 +38,7 @@ class FixedRatioSampler { bool Pulse(); // Returns a debug string describing the current ratio of samples to pulses. - string DebugString(); + std::string DebugString(); private: // Sampling occurs if the proportion of samples to pulses drops below this diff --git a/cartographer/common/histogram.cc b/cartographer/common/histogram.cc index 4ee6d6f..4a1cd84 100644 --- a/cartographer/common/histogram.cc +++ b/cartographer/common/histogram.cc @@ -28,7 +28,7 @@ namespace common { void Histogram::Add(const float value) { values_.push_back(value); } -string Histogram::ToString(const int buckets) const { +std::string Histogram::ToString(const int buckets) const { CHECK_GE(buckets, 1); if (values_.empty()) { return "Count: 0"; @@ -37,10 +37,10 @@ string Histogram::ToString(const int buckets) const { const float max = *std::max_element(values_.begin(), values_.end()); const float mean = std::accumulate(values_.begin(), values_.end(), 0.f) / values_.size(); - string result = "Count: " + std::to_string(values_.size()) + - " Min: " + std::to_string(min) + - " Max: " + std::to_string(max) + - " Mean: " + std::to_string(mean); + std::string result = "Count: " + std::to_string(values_.size()) + + " Min: " + std::to_string(min) + + " Max: " + std::to_string(max) + + " Mean: " + std::to_string(mean); if (min == max) { return result; } diff --git a/cartographer/common/histogram.h b/cartographer/common/histogram.h index aa41141..59df2f7 100644 --- a/cartographer/common/histogram.h +++ b/cartographer/common/histogram.h @@ -28,7 +28,7 @@ namespace common { class Histogram { public: void Add(float value); - string ToString(int buckets) const; + std::string ToString(int buckets) const; private: std::vector values_; diff --git a/cartographer/common/lua_parameter_dictionary.cc b/cartographer/common/lua_parameter_dictionary.cc index 4db29dd..55c3cc7 100644 --- a/cartographer/common/lua_parameter_dictionary.cc +++ b/cartographer/common/lua_parameter_dictionary.cc @@ -99,7 +99,7 @@ int LuaChoose(lua_State* L) { // Pushes a value to the Lua stack. void PushValue(lua_State* L, const int key) { lua_pushinteger(L, key); } -void PushValue(lua_State* L, const string& key) { +void PushValue(lua_State* L, const std::string& key) { lua_pushstring(L, key.c_str()); } @@ -147,18 +147,18 @@ void GetArrayValues(lua_State* L, const std::function& pop_value) { std::unique_ptr LuaParameterDictionary::NonReferenceCounted( - const string& code, std::unique_ptr file_resolver) { + const std::string& code, std::unique_ptr file_resolver) { return std::unique_ptr(new LuaParameterDictionary( code, ReferenceCount::NO, std::move(file_resolver))); } LuaParameterDictionary::LuaParameterDictionary( - const string& code, std::unique_ptr file_resolver) + const std::string& code, std::unique_ptr file_resolver) : LuaParameterDictionary(code, ReferenceCount::YES, std::move(file_resolver)) {} LuaParameterDictionary::LuaParameterDictionary( - const string& code, ReferenceCount reference_count, + const std::string& code, ReferenceCount reference_count, std::unique_ptr file_resolver) : L_(luaL_newstate()), index_into_reference_table_(-1), @@ -206,9 +206,9 @@ LuaParameterDictionary::~LuaParameterDictionary() { } } -std::vector LuaParameterDictionary::GetKeys() const { +std::vector LuaParameterDictionary::GetKeys() const { CheckTableIsAtTopOfStack(L_); - std::vector keys; + std::vector keys; lua_pushnil(L_); // Push the first key while (lua_next(L_, -2) != 0) { @@ -220,28 +220,28 @@ std::vector LuaParameterDictionary::GetKeys() const { return keys; } -bool LuaParameterDictionary::HasKey(const string& key) const { +bool LuaParameterDictionary::HasKey(const std::string& key) const { return HasKeyOfType(L_, key); } -string LuaParameterDictionary::GetString(const string& key) { +std::string LuaParameterDictionary::GetString(const std::string& key) { CheckHasKeyAndReference(key); GetValueFromLuaTable(L_, key); return PopString(Quoted::NO); } -string LuaParameterDictionary::PopString(Quoted quoted) const { +std::string LuaParameterDictionary::PopString(Quoted quoted) const { CHECK(lua_isstring(L_, -1)) << "Top of stack is not a string value."; if (quoted == Quoted::YES) { QuoteStringOnStack(L_); } - const string value = lua_tostring(L_, -1); + const std::string value = lua_tostring(L_, -1); lua_pop(L_, 1); return value; } -double LuaParameterDictionary::GetDouble(const string& key) { +double LuaParameterDictionary::GetDouble(const std::string& key) { CheckHasKeyAndReference(key); GetValueFromLuaTable(L_, key); return PopDouble(); @@ -254,7 +254,7 @@ double LuaParameterDictionary::PopDouble() const { return value; } -int LuaParameterDictionary::GetInt(const string& key) { +int LuaParameterDictionary::GetInt(const std::string& key) { CheckHasKeyAndReference(key); GetValueFromLuaTable(L_, key); return PopInt(); @@ -267,7 +267,7 @@ int LuaParameterDictionary::PopInt() const { return value; } -bool LuaParameterDictionary::GetBool(const string& key) { +bool LuaParameterDictionary::GetBool(const std::string& key) { CheckHasKeyAndReference(key); GetValueFromLuaTable(L_, key); return PopBool(); @@ -281,7 +281,7 @@ bool LuaParameterDictionary::PopBool() const { } std::unique_ptr LuaParameterDictionary::GetDictionary( - const string& key) { + const std::string& key) { CheckHasKeyAndReference(key); GetValueFromLuaTable(L_, key); return PopDictionary(reference_count_); @@ -297,12 +297,13 @@ std::unique_ptr LuaParameterDictionary::PopDictionary( return value; } -string LuaParameterDictionary::DoToString(const string& indent) const { - string result = "{"; +std::string LuaParameterDictionary::DoToString( + const std::string& indent) const { + std::string result = "{"; bool dictionary_is_empty = true; const auto top_of_stack_to_string = [this, indent, - &dictionary_is_empty]() -> string { + &dictionary_is_empty]() -> std::string { dictionary_is_empty = false; const int value_type = lua_type(L_, -1); @@ -346,10 +347,10 @@ string LuaParameterDictionary::DoToString(const string& indent) const { } // String keys. - std::vector keys = GetKeys(); + std::vector keys = GetKeys(); if (!keys.empty()) { std::sort(keys.begin(), keys.end()); - for (const string& key : keys) { + for (const std::string& key : keys) { GetValueFromLuaTable(L_, key); result.append("\n"); result.append(indent); @@ -370,7 +371,7 @@ string LuaParameterDictionary::DoToString(const string& indent) const { return result; } -string LuaParameterDictionary::ToString() const { return DoToString(""); } +std::string LuaParameterDictionary::ToString() const { return DoToString(""); } std::vector LuaParameterDictionary::GetArrayValuesAsDoubles() { std::vector values; @@ -387,19 +388,19 @@ LuaParameterDictionary::GetArrayValuesAsDictionaries() { return values; } -std::vector LuaParameterDictionary::GetArrayValuesAsStrings() { - std::vector values; +std::vector LuaParameterDictionary::GetArrayValuesAsStrings() { + std::vector values; GetArrayValues(L_, [&values, this] { values.push_back(PopString(Quoted::NO)); }); return values; } -void LuaParameterDictionary::CheckHasKey(const string& key) const { +void LuaParameterDictionary::CheckHasKey(const std::string& key) const { CHECK(HasKey(key)) << "Key '" << key << "' not in dictionary:\n" << ToString(); } -void LuaParameterDictionary::CheckHasKeyAndReference(const string& key) { +void LuaParameterDictionary::CheckHasKeyAndReference(const std::string& key) { CheckHasKey(key); reference_counts_[key]++; } @@ -414,7 +415,7 @@ void LuaParameterDictionary::CheckAllKeysWereUsedExactlyOnceAndReset() { reference_counts_.clear(); } -int LuaParameterDictionary::GetNonNegativeInt(const string& key) { +int LuaParameterDictionary::GetNonNegativeInt(const std::string& key) { const int temp = GetInt(key); // Will increase reference count. CHECK_GE(temp, 0) << temp << " is negative."; return temp; @@ -427,15 +428,16 @@ int LuaParameterDictionary::LuaInclude(lua_State* L) { CHECK(lua_isstring(L, -1)) << "include takes a filename."; LuaParameterDictionary* parameter_dictionary = GetDictionaryFromRegistry(L); - const string basename = lua_tostring(L, -1); - const string filename = + const std::string basename = lua_tostring(L, -1); + const std::string filename = parameter_dictionary->file_resolver_->GetFullPathOrDie(basename); if (std::find(parameter_dictionary->included_files_.begin(), parameter_dictionary->included_files_.end(), filename) != parameter_dictionary->included_files_.end()) { - string error_msg = "Tried to include " + filename + - " twice. Already included files in order of inclusion: "; - for (const string& filename : parameter_dictionary->included_files_) { + std::string error_msg = + "Tried to include " + filename + + " twice. Already included files in order of inclusion: "; + for (const std::string& filename : parameter_dictionary->included_files_) { error_msg.append(filename); error_msg.append("\n"); } @@ -445,7 +447,7 @@ int LuaParameterDictionary::LuaInclude(lua_State* L) { lua_pop(L, 1); CHECK_EQ(lua_gettop(L), 0); - const string content = + const std::string content = parameter_dictionary->file_resolver_->GetFileContentOrDie(basename); CheckForLuaErrors( L, luaL_loadbuffer(L, content.c_str(), content.size(), filename.c_str())); @@ -460,7 +462,7 @@ int LuaParameterDictionary::LuaRead(lua_State* L) { CHECK(lua_isstring(L, -1)) << "read takes a filename."; LuaParameterDictionary* parameter_dictionary = GetDictionaryFromRegistry(L); - const string file_content = + const std::string file_content = parameter_dictionary->file_resolver_->GetFileContentOrDie( lua_tostring(L, -1)); lua_pushstring(L, file_content.c_str()); diff --git a/cartographer/common/lua_parameter_dictionary.h b/cartographer/common/lua_parameter_dictionary.h index 871a687..52eaf87 100644 --- a/cartographer/common/lua_parameter_dictionary.h +++ b/cartographer/common/lua_parameter_dictionary.h @@ -34,15 +34,15 @@ namespace common { class FileResolver { public: virtual ~FileResolver() {} - virtual string GetFullPathOrDie(const string& basename) = 0; - virtual string GetFileContentOrDie(const string& basename) = 0; + virtual std::string GetFullPathOrDie(const std::string& basename) = 0; + virtual std::string GetFileContentOrDie(const std::string& basename) = 0; }; // A parameter dictionary that gets loaded from Lua code. class LuaParameterDictionary { public: // Constructs the dictionary from a Lua Table specification. - LuaParameterDictionary(const string& code, + LuaParameterDictionary(const std::string& code, std::unique_ptr file_resolver); LuaParameterDictionary(const LuaParameterDictionary&) = delete; @@ -50,38 +50,39 @@ class LuaParameterDictionary { // Constructs a LuaParameterDictionary without reference counting. static std::unique_ptr NonReferenceCounted( - const string& code, std::unique_ptr file_resolver); + const std::string& code, std::unique_ptr file_resolver); ~LuaParameterDictionary(); // Returns all available keys. - std::vector GetKeys() const; + std::vector GetKeys() const; // Returns true if the key is in this dictionary. - bool HasKey(const string& key) const; + bool HasKey(const std::string& key) const; // These methods CHECK() that the 'key' exists. - string GetString(const string& key); - double GetDouble(const string& key); - int GetInt(const string& key); - bool GetBool(const string& key); - std::unique_ptr GetDictionary(const string& key); + std::string GetString(const std::string& key); + double GetDouble(const std::string& key); + int GetInt(const std::string& key); + bool GetBool(const std::string& key); + std::unique_ptr GetDictionary(const std::string& key); // Gets an int from the dictionary and CHECK()s that it is non-negative. - int GetNonNegativeInt(const string& key); + int GetNonNegativeInt(const std::string& key); // Returns a string representation for this LuaParameterDictionary. - string ToString() const; + std::string ToString() const; // Returns the values of the keys '1', '2', '3' as the given types. std::vector GetArrayValuesAsDoubles(); - std::vector GetArrayValuesAsStrings(); + std::vector GetArrayValuesAsStrings(); std::vector> GetArrayValuesAsDictionaries(); private: enum class ReferenceCount { YES, NO }; - LuaParameterDictionary(const string& code, ReferenceCount reference_count, + LuaParameterDictionary(const std::string& code, + ReferenceCount reference_count, std::unique_ptr file_resolver); // For GetDictionary(). @@ -89,7 +90,7 @@ class LuaParameterDictionary { std::shared_ptr file_resolver); // Function that recurses to keep track of indent for ToString(). - string DoToString(const string& indent) const; + std::string DoToString(const std::string& indent) const; // Pop the top of the stack and CHECKs that the type is correct. double PopDouble() const; @@ -100,7 +101,7 @@ class LuaParameterDictionary { // is either quoted to be suitable to be read back by a Lua interpretor or // not. enum class Quoted { YES, NO }; - string PopString(Quoted quoted) const; + std::string PopString(Quoted quoted) const; // Creates a LuaParameterDictionary from the Lua table at the top of the // stack, either with or without reference counting. @@ -108,10 +109,10 @@ class LuaParameterDictionary { ReferenceCount reference_count) const; // CHECK() that 'key' is in the dictionary. - void CheckHasKey(const string& key) const; + void CheckHasKey(const std::string& key) const; // CHECK() that 'key' is in this dictionary and reference it as being used. - void CheckHasKeyAndReference(const string& key); + void CheckHasKeyAndReference(const std::string& key); // If desired, this can be called in the destructor of a derived class. It // will CHECK() that all keys defined in the configuration have been used @@ -135,11 +136,11 @@ class LuaParameterDictionary { // This is modified with every call to Get* in order to verify that all // parameters are read exactly once. - std::map reference_counts_; + std::map reference_counts_; // List of all included files in order of inclusion. Used to prevent double // inclusion. - std::vector included_files_; + std::vector included_files_; }; } // namespace common diff --git a/cartographer/common/lua_parameter_dictionary_test.cc b/cartographer/common/lua_parameter_dictionary_test.cc index 7d1493c..1862ae6 100644 --- a/cartographer/common/lua_parameter_dictionary_test.cc +++ b/cartographer/common/lua_parameter_dictionary_test.cc @@ -29,7 +29,7 @@ namespace common { namespace { std::unique_ptr MakeNonReferenceCounted( - const string& code) { + const std::string& code) { return LuaParameterDictionary::NonReferenceCounted( code, common::make_unique()); } @@ -37,7 +37,7 @@ std::unique_ptr MakeNonReferenceCounted( class LuaParameterDictionaryTest : public ::testing::Test { protected: void ReferenceAllKeysAsIntegers(LuaParameterDictionary* dict) { - for (const string& key : dict->GetKeys()) { + for (const std::string& key : dict->GetKeys()) { dict->GetInt(key); } } @@ -73,7 +73,7 @@ TEST_F(LuaParameterDictionaryTest, GetDictionary) { MakeDictionary("return { blah = { blue = 100, red = 200 }, fasel = 10 }"); std::unique_ptr sub_dict(dict->GetDictionary("blah")); - std::vector keys = sub_dict->GetKeys(); + std::vector keys = sub_dict->GetKeys(); ASSERT_EQ(keys.size(), 2); std::sort(keys.begin(), keys.end()); ASSERT_EQ(keys[0], "blue"); @@ -89,7 +89,7 @@ TEST_F(LuaParameterDictionaryTest, GetDictionary) { TEST_F(LuaParameterDictionaryTest, GetKeys) { auto dict = MakeDictionary("return { blah = 100, blah1 = 200}"); - std::vector keys = dict->GetKeys(); + std::vector keys = dict->GetKeys(); ASSERT_EQ(keys.size(), 2); std::sort(keys.begin(), keys.end()); ASSERT_EQ(keys[0], "blah"); @@ -122,7 +122,7 @@ TEST_F(LuaParameterDictionaryTest, ToString) { alpha1 = false, })"); - const string golden = R"({ + const std::string golden = R"({ alpha = true, alpha1 = false, blub = "hello", @@ -164,7 +164,7 @@ TEST_F(LuaParameterDictionaryTest, ToStringForArrays) { foo = "ups", })"); - const string golden = R"({ + const std::string golden = R"({ "blub", 3.000000, 3.100000, @@ -176,7 +176,7 @@ TEST_F(LuaParameterDictionaryTest, ToStringForArrays) { TEST_F(LuaParameterDictionaryTest, GetArrayValuesAsStrings) { auto dict = MakeDictionary("return { 'a', 'b', 'c' }"); EXPECT_EQ(0, dict->GetKeys().size()); - const std::vector values = dict->GetArrayValuesAsStrings(); + const std::vector values = dict->GetArrayValuesAsStrings(); EXPECT_EQ(3, values.size()); EXPECT_EQ("a", values[0]); EXPECT_EQ("b", values[1]); diff --git a/cartographer/common/lua_parameter_dictionary_test_helpers.h b/cartographer/common/lua_parameter_dictionary_test_helpers.h index 278b139..f395f25 100644 --- a/cartographer/common/lua_parameter_dictionary_test_helpers.h +++ b/cartographer/common/lua_parameter_dictionary_test_helpers.h @@ -37,16 +37,17 @@ class DummyFileResolver : public FileResolver { ~DummyFileResolver() override {} - string GetFileContentOrDie(const string& unused_basename) override { + std::string GetFileContentOrDie(const std::string& unused_basename) override { LOG(FATAL) << "Not implemented"; } - string GetFullPathOrDie(const string& unused_basename) override { + std::string GetFullPathOrDie(const std::string& unused_basename) override { LOG(FATAL) << "Not implemented"; } }; -std::unique_ptr MakeDictionary(const string& code) { +std::unique_ptr MakeDictionary( + const std::string& code) { return common::make_unique( code, common::make_unique()); } diff --git a/cartographer/common/port.h b/cartographer/common/port.h index 3bc90ad..338861f 100644 --- a/cartographer/common/port.h +++ b/cartographer/common/port.h @@ -36,8 +36,6 @@ using uint16 = uint16_t; using uint32 = uint32_t; using uint64 = uint64_t; -using std::string; - namespace common { inline int RoundToInt(const float x) { return std::lround(x); } @@ -48,7 +46,8 @@ inline int64 RoundToInt64(const float x) { return std::lround(x); } inline int64 RoundToInt64(const double x) { return std::lround(x); } -inline void FastGzipString(const string& uncompressed, string* compressed) { +inline void FastGzipString(const std::string& uncompressed, + std::string* compressed) { boost::iostreams::filtering_ostream out; out.push( boost::iostreams::gzip_compressor(boost::iostreams::zlib::best_speed)); @@ -58,7 +57,8 @@ inline void FastGzipString(const string& uncompressed, string* compressed) { uncompressed.size()); } -inline void FastGunzipString(const string& compressed, string* decompressed) { +inline void FastGunzipString(const std::string& compressed, + std::string* decompressed) { boost::iostreams::filtering_ostream out; out.push(boost::iostreams::gzip_decompressor()); out.push(boost::iostreams::back_inserter(*decompressed)); diff --git a/cartographer/common/rate_timer.h b/cartographer/common/rate_timer.h index b578dc3..bb39e98 100644 --- a/cartographer/common/rate_timer.h +++ b/cartographer/common/rate_timer.h @@ -78,7 +78,7 @@ class RateTimer { } // Returns a debug string representation. - string DebugString() const { + std::string DebugString() const { if (events_.size() < 2) { return "unknown"; } @@ -109,7 +109,7 @@ class RateTimer { } // Returns the average and standard deviation of the deltas. - string DeltasDebugString() const { + std::string DeltasDebugString() const { const auto deltas = ComputeDeltasInSeconds(); const double sum = std::accumulate(deltas.begin(), deltas.end(), 0.); const double mean = sum / deltas.size(); diff --git a/cartographer/ground_truth/autogenerate_ground_truth_main.cc b/cartographer/ground_truth/autogenerate_ground_truth_main.cc index 3fa6120..eba70a5 100644 --- a/cartographer/ground_truth/autogenerate_ground_truth_main.cc +++ b/cartographer/ground_truth/autogenerate_ground_truth_main.cc @@ -163,8 +163,8 @@ proto::GroundTruth GenerateGroundTruth( return ground_truth; } -void Run(const string& pose_graph_filename, const string& output_filename, - const double min_covered_distance, +void Run(const std::string& pose_graph_filename, + const std::string& output_filename, const double min_covered_distance, const double outlier_threshold_meters, const double outlier_threshold_radians) { LOG(INFO) << "Reading pose graph from '" << pose_graph_filename << "'..."; diff --git a/cartographer/ground_truth/compute_relations_metrics_main.cc b/cartographer/ground_truth/compute_relations_metrics_main.cc index 5278e60..d41d8bb 100644 --- a/cartographer/ground_truth/compute_relations_metrics_main.cc +++ b/cartographer/ground_truth/compute_relations_metrics_main.cc @@ -67,7 +67,7 @@ Error ComputeError(const transform::Rigid3d& pose1, common::Pow2(transform::GetAngle(error))}; } -string MeanAndStdDevString(const std::vector& values) { +std::string MeanAndStdDevString(const std::vector& values) { CHECK_GE(values.size(), 2); const double mean = std::accumulate(values.begin(), values.end(), 0.) / values.size(); @@ -80,10 +80,10 @@ string MeanAndStdDevString(const std::vector& values) { std::ostringstream out; out << std::fixed << std::setprecision(5) << mean << " +/- " << standard_deviation; - return string(out.str()); + return std::string(out.str()); } -string StatisticsString(const std::vector& errors) { +std::string StatisticsString(const std::vector& errors) { std::vector translational_errors; std::vector squared_translational_errors; std::vector rotational_errors_degrees; @@ -109,7 +109,8 @@ string StatisticsString(const std::vector& errors) { MeanAndStdDevString(squared_rotational_errors_degrees) + " deg^2\n"; } -void Run(const string& pose_graph_filename, const string& relations_filename, +void Run(const std::string& pose_graph_filename, + const std::string& relations_filename, const bool read_text_file_with_unix_timestamps) { LOG(INFO) << "Reading pose graph from '" << pose_graph_filename << "'..."; mapping::proto::SparsePoseGraph pose_graph; diff --git a/cartographer/ground_truth/relations_text_file.cc b/cartographer/ground_truth/relations_text_file.cc index 60ccdf8..50161fb 100644 --- a/cartographer/ground_truth/relations_text_file.cc +++ b/cartographer/ground_truth/relations_text_file.cc @@ -37,7 +37,8 @@ common::Time UnixToCommonTime(double unix_time) { } // namespace -proto::GroundTruth ReadRelationsTextFile(const string& relations_filename) { +proto::GroundTruth ReadRelationsTextFile( + const std::string& relations_filename) { proto::GroundTruth ground_truth; std::ifstream relations_stream(relations_filename.c_str()); double unix_time_1, unix_time_2, x, y, z, roll, pitch, yaw; diff --git a/cartographer/ground_truth/relations_text_file.h b/cartographer/ground_truth/relations_text_file.h index 1ffe89c..a05033e 100644 --- a/cartographer/ground_truth/relations_text_file.h +++ b/cartographer/ground_truth/relations_text_file.h @@ -33,7 +33,7 @@ namespace ground_truth { // R. Kuemmerle, B. Steder, C. Dornhege, M. Ruhnke, G. Grisetti, C. Stachniss, // and A. Kleiner, "On measuring the accuracy of SLAM algorithms," Autonomous // Robots, vol. 27, no. 4, pp. 387–407, 2009. -proto::GroundTruth ReadRelationsTextFile(const string& relations_filename); +proto::GroundTruth ReadRelationsTextFile(const std::string& relations_filename); } // namespace ground_truth } // namespace cartographer diff --git a/cartographer/io/coloring_points_processor.cc b/cartographer/io/coloring_points_processor.cc index f236836..a11e6b9 100644 --- a/cartographer/io/coloring_points_processor.cc +++ b/cartographer/io/coloring_points_processor.cc @@ -27,7 +27,7 @@ std::unique_ptr ColoringPointsProcessor::FromDictionary( common::LuaParameterDictionary* const dictionary, PointsProcessor* const next) { - const string frame_id = dictionary->GetString("frame_id"); + const std::string frame_id = dictionary->GetString("frame_id"); const std::vector color_values = dictionary->GetDictionary("color")->GetArrayValuesAsDoubles(); const Uint8Color color = {{static_cast(color_values[0]), @@ -38,7 +38,7 @@ ColoringPointsProcessor::FromDictionary( } ColoringPointsProcessor::ColoringPointsProcessor(const FloatColor& color, - const string& frame_id, + const std::string& frame_id, PointsProcessor* const next) : color_(color), frame_id_(frame_id), next_(next) {} diff --git a/cartographer/io/coloring_points_processor.h b/cartographer/io/coloring_points_processor.h index 7627b80..4df4dd6 100644 --- a/cartographer/io/coloring_points_processor.h +++ b/cartographer/io/coloring_points_processor.h @@ -31,7 +31,7 @@ class ColoringPointsProcessor : public PointsProcessor { public: constexpr static const char* kConfigurationFileActionName = "color_points"; - ColoringPointsProcessor(const FloatColor& color, const string& frame_id, + ColoringPointsProcessor(const FloatColor& color, const std::string& frame_id, PointsProcessor* next); static std::unique_ptr FromDictionary( @@ -47,7 +47,7 @@ class ColoringPointsProcessor : public PointsProcessor { private: const FloatColor color_; - const string frame_id_; + const std::string frame_id_; PointsProcessor* const next_; }; diff --git a/cartographer/io/file_writer.cc b/cartographer/io/file_writer.cc index 4b68c40..97d4481 100644 --- a/cartographer/io/file_writer.cc +++ b/cartographer/io/file_writer.cc @@ -19,7 +19,7 @@ namespace cartographer { namespace io { -StreamFileWriter::StreamFileWriter(const string& filename) +StreamFileWriter::StreamFileWriter(const std::string& filename) : filename_(filename), out_(filename, std::ios::out | std::ios::binary) {} StreamFileWriter::~StreamFileWriter() {} @@ -49,7 +49,7 @@ bool StreamFileWriter::WriteHeader(const char* const data, const size_t len) { return Write(data, len); } -string StreamFileWriter::GetFilename() { return filename_; } +std::string StreamFileWriter::GetFilename() { return filename_; } } // namespace io } // namespace cartographer diff --git a/cartographer/io/file_writer.h b/cartographer/io/file_writer.h index 96b7dc2..cba60da 100644 --- a/cartographer/io/file_writer.h +++ b/cartographer/io/file_writer.h @@ -42,7 +42,7 @@ class FileWriter { virtual bool Write(const char* data, size_t len) = 0; virtual bool Close() = 0; - virtual string GetFilename() = 0; + virtual std::string GetFilename() = 0; }; // An Implementation of file using std::ofstream. @@ -50,20 +50,20 @@ class StreamFileWriter : public FileWriter { public: ~StreamFileWriter() override; - StreamFileWriter(const string& filename); + StreamFileWriter(const std::string& filename); bool Write(const char* data, size_t len) override; bool WriteHeader(const char* data, size_t len) override; bool Close() override; - string GetFilename() override; + std::string GetFilename() override; private: - const string filename_; + const std::string filename_; std::ofstream out_; }; using FileWriterFactory = - std::function(const string& filename)>; + std::function(const std::string& filename)>; } // namespace io } // namespace cartographer diff --git a/cartographer/io/frame_id_filtering_points_processor.cc b/cartographer/io/frame_id_filtering_points_processor.cc index 56aea17..2b2ae47 100644 --- a/cartographer/io/frame_id_filtering_points_processor.cc +++ b/cartographer/io/frame_id_filtering_points_processor.cc @@ -27,7 +27,7 @@ namespace io { std::unique_ptr FrameIdFilteringPointsProcessor::FromDictionary( common::LuaParameterDictionary* dictionary, PointsProcessor* next) { - std::vector keep_frames, drop_frames; + std::vector keep_frames, drop_frames; if (dictionary->HasKey("keep_frames")) { keep_frames = dictionary->GetDictionary("keep_frames")->GetArrayValuesAsStrings(); @@ -37,13 +37,15 @@ FrameIdFilteringPointsProcessor::FromDictionary( dictionary->GetDictionary("drop_frames")->GetArrayValuesAsStrings(); } return common::make_unique( - std::unordered_set(keep_frames.begin(), keep_frames.end()), - std::unordered_set(drop_frames.begin(), drop_frames.end()), next); + std::unordered_set(keep_frames.begin(), keep_frames.end()), + std::unordered_set(drop_frames.begin(), drop_frames.end()), + next); } FrameIdFilteringPointsProcessor::FrameIdFilteringPointsProcessor( - const std::unordered_set& keep_frame_ids, - const std::unordered_set& drop_frame_ids, PointsProcessor* next) + const std::unordered_set& keep_frame_ids, + const std::unordered_set& drop_frame_ids, + PointsProcessor* next) : keep_frame_ids_(keep_frame_ids), drop_frame_ids_(drop_frame_ids), next_(next) { diff --git a/cartographer/io/frame_id_filtering_points_processor.h b/cartographer/io/frame_id_filtering_points_processor.h index 1563e60..598b832 100644 --- a/cartographer/io/frame_id_filtering_points_processor.h +++ b/cartographer/io/frame_id_filtering_points_processor.h @@ -32,8 +32,9 @@ class FrameIdFilteringPointsProcessor : public PointsProcessor { public: constexpr static const char* kConfigurationFileActionName = "frame_id_filter"; FrameIdFilteringPointsProcessor( - const std::unordered_set& keep_frame_ids, - const std::unordered_set& drop_frame_ids, PointsProcessor* next); + const std::unordered_set& keep_frame_ids, + const std::unordered_set& drop_frame_ids, + PointsProcessor* next); static std::unique_ptr FromDictionary( common::LuaParameterDictionary* dictionary, PointsProcessor* next); ~FrameIdFilteringPointsProcessor() override {} @@ -47,8 +48,8 @@ class FrameIdFilteringPointsProcessor : public PointsProcessor { FlushResult Flush() override; private: - const std::unordered_set keep_frame_ids_; - const std::unordered_set drop_frame_ids_; + const std::unordered_set keep_frame_ids_; + const std::unordered_set drop_frame_ids_; PointsProcessor* const next_; }; diff --git a/cartographer/io/hybrid_grid_points_processor.cc b/cartographer/io/hybrid_grid_points_processor.cc index aba503f..77d972a 100644 --- a/cartographer/io/hybrid_grid_points_processor.cc +++ b/cartographer/io/hybrid_grid_points_processor.cc @@ -47,7 +47,7 @@ void HybridGridPointsProcessor::Process(std::unique_ptr batch) { PointsProcessor::FlushResult HybridGridPointsProcessor::Flush() { const mapping_3d::proto::HybridGrid hybrid_grid_proto = hybrid_grid_.ToProto(); - string serialized; + std::string serialized; hybrid_grid_proto.SerializeToString(&serialized); file_writer_->Write(serialized.data(), serialized.size()); CHECK(file_writer_->Close()); diff --git a/cartographer/io/intensity_to_color_points_processor.cc b/cartographer/io/intensity_to_color_points_processor.cc index 7b16390..0bceb64 100644 --- a/cartographer/io/intensity_to_color_points_processor.cc +++ b/cartographer/io/intensity_to_color_points_processor.cc @@ -28,7 +28,7 @@ std::unique_ptr IntensityToColorPointsProcessor::FromDictionary( common::LuaParameterDictionary* const dictionary, PointsProcessor* const next) { - const string frame_id = + const std::string frame_id = dictionary->HasKey("frame_id") ? dictionary->GetString("frame_id") : ""; const float min_intensity = dictionary->GetDouble("min_intensity"); const float max_intensity = dictionary->GetDouble("max_intensity"); @@ -38,7 +38,7 @@ IntensityToColorPointsProcessor::FromDictionary( IntensityToColorPointsProcessor::IntensityToColorPointsProcessor( const float min_intensity, const float max_intensity, - const string& frame_id, PointsProcessor* const next) + const std::string& frame_id, PointsProcessor* const next) : min_intensity_(min_intensity), max_intensity_(max_intensity), frame_id_(frame_id), diff --git a/cartographer/io/intensity_to_color_points_processor.h b/cartographer/io/intensity_to_color_points_processor.h index f3d3346..342a376 100644 --- a/cartographer/io/intensity_to_color_points_processor.h +++ b/cartographer/io/intensity_to_color_points_processor.h @@ -35,7 +35,7 @@ class IntensityToColorPointsProcessor : public PointsProcessor { // with this value for each point that comes from the sensor with 'frame_id'. // If 'frame_id' is empty, this applies to all points. IntensityToColorPointsProcessor(float min_intensity, float max_intensity, - const string& frame_id, + const std::string& frame_id, PointsProcessor* next); static std::unique_ptr FromDictionary( @@ -54,7 +54,7 @@ class IntensityToColorPointsProcessor : public PointsProcessor { private: const float min_intensity_; const float max_intensity_; - const string frame_id_; + const std::string frame_id_; PointsProcessor* const next_; }; diff --git a/cartographer/io/pcd_writing_points_processor.cc b/cartographer/io/pcd_writing_points_processor.cc index 871e127..bbfb618 100644 --- a/cartographer/io/pcd_writing_points_processor.cc +++ b/cartographer/io/pcd_writing_points_processor.cc @@ -34,10 +34,10 @@ namespace { // 'output_file'. void WriteBinaryPcdHeader(const bool has_color, const int64 num_points, FileWriter* const file_writer) { - string color_header_field = !has_color ? "" : " rgb"; - string color_header_type = !has_color ? "" : " U"; - string color_header_size = !has_color ? "" : " 4"; - string color_header_count = !has_color ? "" : " 1"; + std::string color_header_field = !has_color ? "" : " rgb"; + std::string color_header_type = !has_color ? "" : " U"; + std::string color_header_size = !has_color ? "" : " 4"; + std::string color_header_count = !has_color ? "" : " 1"; std::ostringstream stream; stream << "# generated by Cartographer\n" @@ -52,7 +52,7 @@ void WriteBinaryPcdHeader(const bool has_color, const int64 num_points, << "POINTS " << std::setw(15) << std::setfill('0') << num_points << "\n" << "DATA binary\n"; - const string out = stream.str(); + const std::string out = stream.str(); file_writer->WriteHeader(out.data(), out.size()); } diff --git a/cartographer/io/ply_writing_points_processor.cc b/cartographer/io/ply_writing_points_processor.cc index cd63b05..aa03f5f 100644 --- a/cartographer/io/ply_writing_points_processor.cc +++ b/cartographer/io/ply_writing_points_processor.cc @@ -34,10 +34,10 @@ namespace { // 'output_file'. void WriteBinaryPlyHeader(const bool has_color, const int64 num_points, FileWriter* const file_writer) { - string color_header = !has_color ? "" - : "property uchar red\n" - "property uchar green\n" - "property uchar blue\n"; + std::string color_header = !has_color ? "" + : "property uchar red\n" + "property uchar green\n" + "property uchar blue\n"; std::ostringstream stream; stream << "ply\n" << "format binary_little_endian 1.0\n" @@ -48,7 +48,7 @@ void WriteBinaryPlyHeader(const bool has_color, const int64 num_points, << "property float y\n" << "property float z\n" << color_header << "end_header\n"; - const string out = stream.str(); + const std::string out = stream.str(); CHECK(file_writer->WriteHeader(out.data(), out.size())); } diff --git a/cartographer/io/points_batch.h b/cartographer/io/points_batch.h index 9060d2a..5bdbd0b 100644 --- a/cartographer/io/points_batch.h +++ b/cartographer/io/points_batch.h @@ -46,7 +46,7 @@ struct PointsBatch { // Sensor that generated this data's 'frame_id' or empty if this information // is unknown. - string frame_id; + std::string frame_id; // Trajectory ID that produced this point. int trajectory_id; diff --git a/cartographer/io/points_processor_pipeline_builder.cc b/cartographer/io/points_processor_pipeline_builder.cc index f7a4f31..f348f84 100644 --- a/cartographer/io/points_processor_pipeline_builder.cc +++ b/cartographer/io/points_processor_pipeline_builder.cc @@ -125,7 +125,7 @@ PointsProcessorPipelineBuilder::CreatePipeline( // We construct the pipeline starting at the back. for (auto it = configurations.rbegin(); it != configurations.rend(); it++) { - const string action = (*it)->GetString("action"); + const std::string action = (*it)->GetString("action"); auto factory_it = factories_.find(action); CHECK(factory_it != factories_.end()) << "Unknown action '" << action diff --git a/cartographer/io/points_processor_pipeline_builder_test.cc b/cartographer/io/points_processor_pipeline_builder_test.cc index 942b009..da55241 100644 --- a/cartographer/io/points_processor_pipeline_builder_test.cc +++ b/cartographer/io/points_processor_pipeline_builder_test.cc @@ -29,7 +29,7 @@ namespace { TEST(PointsProcessorPipelineBuilderTest, RegisterBuiltInPointsProcessors) { PointsProcessorPipelineBuilder builder; FileWriterFactory dummy_factory = - [](const string& filename) -> std::unique_ptr { + [](const std::string& filename) -> std::unique_ptr { return nullptr; }; RegisterBuiltInPointsProcessors({}, dummy_factory, &builder); diff --git a/cartographer/io/proto_stream.cc b/cartographer/io/proto_stream.cc index 1f8e3f5..fda65ae 100644 --- a/cartographer/io/proto_stream.cc +++ b/cartographer/io/proto_stream.cc @@ -42,15 +42,15 @@ bool ReadSizeAsLittleEndian(std::istream* in, uint64* size) { } // namespace -ProtoStreamWriter::ProtoStreamWriter(const string& filename) +ProtoStreamWriter::ProtoStreamWriter(const std::string& filename) : out_(filename, std::ios::out | std::ios::binary) { WriteSizeAsLittleEndian(kMagic, &out_); } ProtoStreamWriter::~ProtoStreamWriter() {} -void ProtoStreamWriter::Write(const string& uncompressed_data) { - string compressed_data; +void ProtoStreamWriter::Write(const std::string& uncompressed_data) { + std::string compressed_data; common::FastGzipString(uncompressed_data, &compressed_data); WriteSizeAsLittleEndian(compressed_data.size(), &out_); out_.write(compressed_data.data(), compressed_data.size()); @@ -61,7 +61,7 @@ bool ProtoStreamWriter::Close() { return !out_.fail(); } -ProtoStreamReader::ProtoStreamReader(const string& filename) +ProtoStreamReader::ProtoStreamReader(const std::string& filename) : in_(filename, std::ios::in | std::ios::binary) { uint64 magic; if (!ReadSizeAsLittleEndian(&in_, &magic) || magic != kMagic) { @@ -71,12 +71,12 @@ ProtoStreamReader::ProtoStreamReader(const string& filename) ProtoStreamReader::~ProtoStreamReader() {} -bool ProtoStreamReader::Read(string* decompressed_data) { +bool ProtoStreamReader::Read(std::string* decompressed_data) { uint64 compressed_size; if (!ReadSizeAsLittleEndian(&in_, &compressed_size)) { return false; } - string compressed_data(compressed_size, '\0'); + std::string compressed_data(compressed_size, '\0'); if (!in_.read(&compressed_data.front(), compressed_size)) { return false; } diff --git a/cartographer/io/proto_stream.h b/cartographer/io/proto_stream.h index ddc43b2..aef09c5 100644 --- a/cartographer/io/proto_stream.h +++ b/cartographer/io/proto_stream.h @@ -32,7 +32,7 @@ namespace io { // compression performance? Should we use LZ4? class ProtoStreamWriter { public: - ProtoStreamWriter(const string& filename); + ProtoStreamWriter(const std::string& filename); ~ProtoStreamWriter(); ProtoStreamWriter(const ProtoStreamWriter&) = delete; @@ -41,7 +41,7 @@ class ProtoStreamWriter { // Serializes, compressed and writes the 'proto' to the file. template void WriteProto(const MessageType& proto) { - string uncompressed_data; + std::string uncompressed_data; proto.SerializeToString(&uncompressed_data); Write(uncompressed_data); } @@ -50,7 +50,7 @@ class ProtoStreamWriter { bool Close(); private: - void Write(const string& uncompressed_data); + void Write(const std::string& uncompressed_data); std::ofstream out_; }; @@ -58,7 +58,7 @@ class ProtoStreamWriter { // A reader of the format produced by ProtoStreamWriter. class ProtoStreamReader { public: - ProtoStreamReader(const string& filename); + ProtoStreamReader(const std::string& filename); ~ProtoStreamReader(); ProtoStreamReader(const ProtoStreamReader&) = delete; @@ -66,7 +66,7 @@ class ProtoStreamReader { template bool ReadProto(MessageType* proto) { - string decompressed_data; + std::string decompressed_data; return Read(&decompressed_data) && proto->ParseFromString(decompressed_data); } @@ -74,7 +74,7 @@ class ProtoStreamReader { bool eof() const; private: - bool Read(string* decompressed_data); + bool Read(std::string* decompressed_data); std::ifstream in_; }; diff --git a/cartographer/io/proto_stream_test.cc b/cartographer/io/proto_stream_test.cc index a849ba6..0a89d45 100644 --- a/cartographer/io/proto_stream_test.cc +++ b/cartographer/io/proto_stream_test.cc @@ -32,18 +32,18 @@ namespace { class ProtoStreamTest : public ::testing::Test { protected: void SetUp() override { - const string tmpdir = P_tmpdir; + const std::string tmpdir = P_tmpdir; test_directory_ = tmpdir + "/proto_stream_test_XXXXXX"; ASSERT_NE(mkdtemp(&test_directory_[0]), nullptr) << strerror(errno); } void TearDown() override { remove(test_directory_.c_str()); } - string test_directory_; + std::string test_directory_; }; TEST_F(ProtoStreamTest, WriteAndReadBack) { - const string test_file = test_directory_ + "/test_trajectory.pbstream"; + const std::string test_file = test_directory_ + "/test_trajectory.pbstream"; { ProtoStreamWriter writer(test_file); for (int i = 0; i != 10; ++i) { diff --git a/cartographer/io/xray_points_processor.cc b/cartographer/io/xray_points_processor.cc index 8b8dcc3..efaff35 100644 --- a/cartographer/io/xray_points_processor.cc +++ b/cartographer/io/xray_points_processor.cc @@ -98,7 +98,8 @@ bool ContainedIn(const common::Time& time, XRayPointsProcessor::XRayPointsProcessor( const double voxel_size, const transform::Rigid3f& transform, const std::vector& floors, - const DrawTrajectories& draw_trajectories, const string& output_filename, + const DrawTrajectories& draw_trajectories, + const std::string& output_filename, const std::vector& trajectories, FileWriterFactory file_writer_factory, PointsProcessor* const next) : draw_trajectories_(draw_trajectories), diff --git a/cartographer/io/xray_points_processor.h b/cartographer/io/xray_points_processor.h index bdd2364..99bc49b 100644 --- a/cartographer/io/xray_points_processor.h +++ b/cartographer/io/xray_points_processor.h @@ -40,7 +40,8 @@ class XRayPointsProcessor : public PointsProcessor { XRayPointsProcessor( double voxel_size, const transform::Rigid3f& transform, const std::vector& floors, - const DrawTrajectories& draw_trajectories, const string& output_filename, + const DrawTrajectories& draw_trajectories, + const std::string& output_filename, const std::vector& trajectories, FileWriterFactory file_writer_factory, PointsProcessor* next); @@ -81,7 +82,7 @@ class XRayPointsProcessor : public PointsProcessor { // If empty, we do not separate into floors. std::vector floors_; - const string output_filename_; + const std::string output_filename_; const transform::Rigid3f transform_; // Only has one entry if we do not separate into floors. diff --git a/cartographer/io/xyz_writing_points_processor.cc b/cartographer/io/xyz_writing_points_processor.cc index f23f0e4..f89ac32 100644 --- a/cartographer/io/xyz_writing_points_processor.cc +++ b/cartographer/io/xyz_writing_points_processor.cc @@ -15,7 +15,7 @@ void WriteXyzPoint(const Eigen::Vector3f& point, std::ostringstream stream; stream << std::setprecision(6); stream << point.x() << " " << point.y() << " " << point.z() << "\n"; - const string out = stream.str(); + const std::string out = stream.str(); CHECK(file_writer->Write(out.data(), out.size())); } diff --git a/cartographer/mapping/collated_trajectory_builder.cc b/cartographer/mapping/collated_trajectory_builder.cc index c6efabd..beecb09 100644 --- a/cartographer/mapping/collated_trajectory_builder.cc +++ b/cartographer/mapping/collated_trajectory_builder.cc @@ -30,7 +30,7 @@ constexpr double kSensorDataRatesLoggingPeriodSeconds = 15.; CollatedTrajectoryBuilder::CollatedTrajectoryBuilder( sensor::Collator* const sensor_collator, const int trajectory_id, - const std::unordered_set& expected_sensor_ids, + const std::unordered_set& expected_sensor_ids, std::unique_ptr wrapped_trajectory_builder) : sensor_collator_(sensor_collator), @@ -39,7 +39,7 @@ CollatedTrajectoryBuilder::CollatedTrajectoryBuilder( last_logging_time_(std::chrono::steady_clock::now()) { sensor_collator_->AddTrajectory( trajectory_id, expected_sensor_ids, - [this](const string& sensor_id, std::unique_ptr data) { + [this](const std::string& sensor_id, std::unique_ptr data) { HandleCollatedSensorData(sensor_id, std::move(data)); }); } @@ -51,12 +51,12 @@ const PoseEstimate& CollatedTrajectoryBuilder::pose_estimate() const { } void CollatedTrajectoryBuilder::AddSensorData( - const string& sensor_id, std::unique_ptr data) { + const std::string& sensor_id, std::unique_ptr data) { sensor_collator_->AddSensorData(trajectory_id_, sensor_id, std::move(data)); } void CollatedTrajectoryBuilder::HandleCollatedSensorData( - const string& sensor_id, std::unique_ptr data) { + const std::string& sensor_id, std::unique_ptr data) { auto it = rate_timers_.find(sensor_id); if (it == rate_timers_.end()) { it = rate_timers_ diff --git a/cartographer/mapping/collated_trajectory_builder.h b/cartographer/mapping/collated_trajectory_builder.h index 1f14ea6..5117781 100644 --- a/cartographer/mapping/collated_trajectory_builder.h +++ b/cartographer/mapping/collated_trajectory_builder.h @@ -40,7 +40,7 @@ class CollatedTrajectoryBuilder : public TrajectoryBuilder { public: CollatedTrajectoryBuilder( sensor::Collator* sensor_collator, int trajectory_id, - const std::unordered_set& expected_sensor_ids, + const std::unordered_set& expected_sensor_ids, std::unique_ptr wrapped_trajectory_builder); ~CollatedTrajectoryBuilder() override; @@ -51,11 +51,11 @@ class CollatedTrajectoryBuilder : public TrajectoryBuilder { const PoseEstimate& pose_estimate() const override; - void AddSensorData(const string& sensor_id, + void AddSensorData(const std::string& sensor_id, std::unique_ptr data) override; private: - void HandleCollatedSensorData(const string& sensor_id, + void HandleCollatedSensorData(const std::string& sensor_id, std::unique_ptr data); sensor::Collator* const sensor_collator_; @@ -64,7 +64,7 @@ class CollatedTrajectoryBuilder : public TrajectoryBuilder { // Time at which we last logged the rates of incoming sensor data. std::chrono::steady_clock::time_point last_logging_time_; - std::map> rate_timers_; + std::map> rate_timers_; }; } // namespace mapping diff --git a/cartographer/mapping/map_builder.cc b/cartographer/mapping/map_builder.cc index 50a1d0c..70860d6 100644 --- a/cartographer/mapping/map_builder.cc +++ b/cartographer/mapping/map_builder.cc @@ -74,7 +74,7 @@ MapBuilder::MapBuilder( MapBuilder::~MapBuilder() {} int MapBuilder::AddTrajectoryBuilder( - const std::unordered_set& expected_sensor_ids, + const std::unordered_set& expected_sensor_ids, const proto::TrajectoryBuilderOptions& trajectory_options) { const int trajectory_id = trajectory_builders_.size(); if (options_.use_trajectory_builder_3d()) { @@ -138,8 +138,9 @@ int MapBuilder::GetBlockingTrajectoryId() const { return sensor_collator_.GetBlockingTrajectoryId(); } -string MapBuilder::SubmapToProto(const mapping::SubmapId& submap_id, - proto::SubmapQuery::Response* const response) { +std::string MapBuilder::SubmapToProto( + const mapping::SubmapId& submap_id, + proto::SubmapQuery::Response* const response) { if (submap_id.trajectory_id < 0 || submap_id.trajectory_id >= num_trajectory_builders()) { return "Requested submap from trajectory " + diff --git a/cartographer/mapping/map_builder.h b/cartographer/mapping/map_builder.h index 9f90e49..a42b316 100644 --- a/cartographer/mapping/map_builder.h +++ b/cartographer/mapping/map_builder.h @@ -61,7 +61,7 @@ class MapBuilder { // Creates a new trajectory builder and returns its index. int AddTrajectoryBuilder( - const std::unordered_set& expected_sensor_ids, + const std::unordered_set& expected_sensor_ids, const proto::TrajectoryBuilderOptions& trajectory_options); // Creates a new trajectory and returns its index. Querying the trajectory @@ -84,8 +84,8 @@ class MapBuilder { // Fills the SubmapQuery::Response corresponding to 'submap_id'. Returns an // error string on failure, or an empty string on success. - string SubmapToProto(const SubmapId& submap_id, - proto::SubmapQuery::Response* response); + std::string SubmapToProto(const SubmapId& submap_id, + proto::SubmapQuery::Response* response); // Serializes the current state to a proto stream. void SerializeState(io::ProtoStreamWriter* writer); diff --git a/cartographer/mapping/trajectory_builder.h b/cartographer/mapping/trajectory_builder.h index 0d7cb14..75d56e3 100644 --- a/cartographer/mapping/trajectory_builder.h +++ b/cartographer/mapping/trajectory_builder.h @@ -50,10 +50,10 @@ class TrajectoryBuilder { virtual const PoseEstimate& pose_estimate() const = 0; - virtual void AddSensorData(const string& sensor_id, + virtual void AddSensorData(const std::string& sensor_id, std::unique_ptr data) = 0; - void AddRangefinderData(const string& sensor_id, common::Time time, + void AddRangefinderData(const std::string& sensor_id, common::Time time, const Eigen::Vector3f& origin, const sensor::TimedPointCloud& ranges) { AddSensorData(sensor_id, @@ -61,20 +61,20 @@ class TrajectoryBuilder { time, origin, ranges)); } - void AddImuData(const string& sensor_id, common::Time time, + void AddImuData(const std::string& sensor_id, common::Time time, const Eigen::Vector3d& linear_acceleration, const Eigen::Vector3d& angular_velocity) { AddSensorData(sensor_id, sensor::MakeDispatchable(sensor::ImuData{ time, linear_acceleration, angular_velocity})); } - void AddOdometerData(const string& sensor_id, common::Time time, + void AddOdometerData(const std::string& sensor_id, common::Time time, const transform::Rigid3d& odometer_pose) { AddSensorData(sensor_id, sensor::MakeDispatchable( sensor::OdometryData{time, odometer_pose})); } - void AddFixedFramePoseData(const string& sensor_id, common::Time time, + void AddFixedFramePoseData(const std::string& sensor_id, common::Time time, const transform::Rigid3d& fixed_frame_pose) { AddSensorData(sensor_id, sensor::MakeDispatchable( diff --git a/cartographer/mapping_2d/submaps.cc b/cartographer/mapping_2d/submaps.cc index 5dc9af9..73038f0 100644 --- a/cartographer/mapping_2d/submaps.cc +++ b/cartographer/mapping_2d/submaps.cc @@ -91,7 +91,7 @@ void Submap::ToResponseProto( CellLimits limits; probability_grid_.ComputeCroppedLimits(&offset, &limits); - string cells; + std::string cells; for (const Eigen::Array2i& xy_index : XYIndexRangeIterator(limits)) { if (probability_grid_.IsKnown(xy_index + offset)) { // We would like to add 'delta' but this is not possible using a value and diff --git a/cartographer/mapping_3d/scan_matching/ceres_scan_matcher.cc b/cartographer/mapping_3d/scan_matching/ceres_scan_matcher.cc index 0ff4cc3..c7dbd97 100644 --- a/cartographer/mapping_3d/scan_matching/ceres_scan_matcher.cc +++ b/cartographer/mapping_3d/scan_matching/ceres_scan_matcher.cc @@ -40,7 +40,8 @@ proto::CeresScanMatcherOptions CreateCeresScanMatcherOptions( common::LuaParameterDictionary* const parameter_dictionary) { proto::CeresScanMatcherOptions options; for (int i = 0;; ++i) { - const string lua_identifier = "occupied_space_weight_" + std::to_string(i); + const std::string lua_identifier = + "occupied_space_weight_" + std::to_string(i); if (!parameter_dictionary->HasKey(lua_identifier)) { break; } diff --git a/cartographer/mapping_3d/submaps.cc b/cartographer/mapping_3d/submaps.cc index 8437d57..5568f49 100644 --- a/cartographer/mapping_3d/submaps.cc +++ b/cartographer/mapping_3d/submaps.cc @@ -113,9 +113,9 @@ std::vector ExtractVoxelData( // Builds texture data containing interleaved value and alpha for the // visualization from 'accumulated_pixel_data'. -string ComputePixelValues( +std::string ComputePixelValues( const std::vector& accumulated_pixel_data) { - string cell_data; + std::string cell_data; cell_data.reserve(2 * accumulated_pixel_data.size()); constexpr float kMinZDifference = 3.f; constexpr float kFreeSpaceWeight = 0.15f; @@ -168,7 +168,7 @@ void AddToTextureProto( const std::vector accumulated_pixel_data = AccumulatePixelData( width, height, min_index, max_index, voxel_indices_and_probabilities); - const string cell_data = ComputePixelValues(accumulated_pixel_data); + const std::string cell_data = ComputePixelValues(accumulated_pixel_data); common::FastGzipString(cell_data, texture->mutable_cells()); *texture->mutable_slice_pose() = transform::ToProto( diff --git a/cartographer/sensor/collator.cc b/cartographer/sensor/collator.cc index d6f7820..cadc6e2 100644 --- a/cartographer/sensor/collator.cc +++ b/cartographer/sensor/collator.cc @@ -21,7 +21,7 @@ namespace sensor { void Collator::AddTrajectory( const int trajectory_id, - const std::unordered_set& expected_sensor_ids, + const std::unordered_set& expected_sensor_ids, const Callback& callback) { for (const auto& sensor_id : expected_sensor_ids) { const auto queue_key = QueueKey{trajectory_id, sensor_id}; @@ -39,7 +39,8 @@ void Collator::FinishTrajectory(const int trajectory_id) { } } -void Collator::AddSensorData(const int trajectory_id, const string& sensor_id, +void Collator::AddSensorData(const int trajectory_id, + const std::string& sensor_id, std::unique_ptr data) { queue_.Add(QueueKey{trajectory_id, sensor_id}, std::move(data)); } diff --git a/cartographer/sensor/collator.h b/cartographer/sensor/collator.h index 447daaf..f1ef511 100644 --- a/cartographer/sensor/collator.h +++ b/cartographer/sensor/collator.h @@ -31,7 +31,8 @@ namespace sensor { class Collator { public: - using Callback = std::function)>; + using Callback = + std::function)>; Collator() {} @@ -41,7 +42,7 @@ class Collator { // Adds a trajectory to produce sorted sensor output for. Calls 'callback' // for each collated sensor data. void AddTrajectory(int trajectory_id, - const std::unordered_set& expected_sensor_ids, + const std::unordered_set& expected_sensor_ids, const Callback& callback); // Marks 'trajectory_id' as finished. @@ -50,7 +51,7 @@ class Collator { // Adds 'data' for 'trajectory_id' to be collated. 'data' must contain valid // sensor data. Sensor packets with matching 'sensor_id' must be added in time // order. - void AddSensorData(int trajectory_id, const string& sensor_id, + void AddSensorData(int trajectory_id, const std::string& sensor_id, std::unique_ptr data); // Dispatches all queued sensor packets. May only be called once. diff --git a/cartographer/sensor/collator_test.cc b/cartographer/sensor/collator_test.cc index 7202522..59f1c03 100644 --- a/cartographer/sensor/collator_test.cc +++ b/cartographer/sensor/collator_test.cc @@ -30,7 +30,7 @@ namespace sensor { namespace { TEST(Collator, Ordering) { - const std::array kSensorId = { + const std::array kSensorId = { {"horizontal_rangefinder", "vertical_rangefinder", "imu", "odometry"}}; DispatchableRangefinderData zero(common::FromUniversal(0), Eigen::Vector3f::Zero(), {}); @@ -46,11 +46,11 @@ TEST(Collator, Ordering) { OdometryData sixth{common::FromUniversal(600), transform::Rigid3d::Identity()}; - std::vector> received; + std::vector> received; Collator collator; collator.AddTrajectory( - 0, std::unordered_set(kSensorId.begin(), kSensorId.end()), - [&received](const string& sensor_id, std::unique_ptr data) { + 0, std::unordered_set(kSensorId.begin(), kSensorId.end()), + [&received](const std::string& sensor_id, std::unique_ptr data) { received.push_back(std::make_pair(sensor_id, data->GetTime())); }); diff --git a/cartographer/sensor/compressed_point_cloud_test.cc b/cartographer/sensor/compressed_point_cloud_test.cc index d475428..757ba06 100644 --- a/cartographer/sensor/compressed_point_cloud_test.cc +++ b/cartographer/sensor/compressed_point_cloud_test.cc @@ -41,7 +41,7 @@ constexpr float kPrecision = 0.001f; // Matcher for 3-d vectors w.r.t. to the target precision. MATCHER_P(ApproximatelyEquals, expected, - string("is equal to ") + PrintToString(expected)) { + std::string("is equal to ") + PrintToString(expected)) { return (arg - expected).isZero(kPrecision); } diff --git a/cartographer/sensor/landmark_data.h b/cartographer/sensor/landmark_data.h index ec19ac1..93d8db6 100644 --- a/cartographer/sensor/landmark_data.h +++ b/cartographer/sensor/landmark_data.h @@ -30,7 +30,7 @@ namespace cartographer { namespace sensor { struct Landmark { - string id; + std::string id; transform::Rigid3d transform; double translation_weight; double rotation_weight; diff --git a/cartographer/sensor/ordered_multi_queue.h b/cartographer/sensor/ordered_multi_queue.h index 2cf83d2..37f7b09 100644 --- a/cartographer/sensor/ordered_multi_queue.h +++ b/cartographer/sensor/ordered_multi_queue.h @@ -33,7 +33,7 @@ namespace sensor { struct QueueKey { int trajectory_id; - string sensor_id; + std::string sensor_id; bool operator<(const QueueKey& other) const { return std::forward_as_tuple(trajectory_id, sensor_id) < diff --git a/cartographer/transform/rigid_transform.h b/cartographer/transform/rigid_transform.h index fdac1c2..29f0bbc 100644 --- a/cartographer/transform/rigid_transform.h +++ b/cartographer/transform/rigid_transform.h @@ -76,8 +76,8 @@ class Rigid2 { return Rigid2(translation, rotation); } - string DebugString() const { - string out; + std::string DebugString() const { + std::string out; out.append("{ t: ["); out.append(std::to_string(translation().x())); out.append(", "); @@ -161,8 +161,8 @@ class Rigid3 { return Rigid3(translation, rotation); } - string DebugString() const { - string out; + std::string DebugString() const { + std::string out; out.append("{ t: ["); out.append(std::to_string(translation().x())); out.append(", "); diff --git a/cartographer/transform/rigid_transform_test_helpers.h b/cartographer/transform/rigid_transform_test_helpers.h index 203e29a..877c752 100644 --- a/cartographer/transform/rigid_transform_test_helpers.h +++ b/cartographer/transform/rigid_transform_test_helpers.h @@ -40,8 +40,8 @@ Eigen::Transform ToEigen(const Rigid3& rigid3) { } MATCHER_P2(IsNearly, rigid, epsilon, - string(string(negation ? "isn't" : "is", " nearly ") + - rigid.DebugString())) { + std::string(std::string(negation ? "isn't" : "is", " nearly ") + + rigid.DebugString())) { return ToEigen(arg).isApprox(ToEigen(rigid), epsilon); }