From 4034f4f8017f51c86a1111a21621fd7ffb120d2e Mon Sep 17 00:00:00 2001 From: Wolfgang Hess Date: Thu, 3 Aug 2017 15:47:17 +0200 Subject: [PATCH] Deduplicate LoadOptions(). (#471) --- .../configuration_files_test.cc | 14 +++-------- .../cartographer_ros/node_main.cc | 23 ++----------------- .../cartographer_ros/node_options.cc | 20 +++++++++++++++- .../cartographer_ros/node_options.h | 9 +++++++- .../cartographer_ros/offline_node_main.cc | 20 ++-------------- .../cartographer_ros/trajectory_options.cc | 1 + .../cartographer_ros/trajectory_options.h | 2 +- 7 files changed, 36 insertions(+), 53 deletions(-) diff --git a/cartographer_ros/cartographer_ros/configuration_files_test.cc b/cartographer_ros/cartographer_ros/configuration_files_test.cc index 82a7917..e327e8a 100644 --- a/cartographer_ros/cartographer_ros/configuration_files_test.cc +++ b/cartographer_ros/cartographer_ros/configuration_files_test.cc @@ -17,10 +17,7 @@ #include #include -#include "cartographer/common/configuration_file_resolver.h" -#include "cartographer/common/lua_parameter_dictionary.h" #include "cartographer_ros/node_options.h" -#include "cartographer_ros/trajectory_options.h" #include "gtest/gtest.h" #include "ros/package.h" @@ -31,14 +28,9 @@ class ConfigurationFilesTest : public ::testing::TestWithParam {}; TEST_P(ConfigurationFilesTest, ValidateNodeOptions) { EXPECT_NO_FATAL_FAILURE({ - auto file_resolver = ::cartographer::common::make_unique< - ::cartographer::common::ConfigurationFileResolver>(std::vector{ - ::ros::package::getPath("cartographer_ros") + "/configuration_files"}); - const string code = file_resolver->GetFileContentOrDie(GetParam()); - ::cartographer::common::LuaParameterDictionary lua_parameter_dictionary( - code, std::move(file_resolver)); - ::cartographer_ros::CreateNodeOptions(&lua_parameter_dictionary); - ::cartographer_ros::CreateTrajectoryOptions(&lua_parameter_dictionary); + LoadOptions( + ::ros::package::getPath("cartographer_ros") + "/configuration_files", + GetParam()); }); } diff --git a/cartographer_ros/cartographer_ros/node_main.cc b/cartographer_ros/cartographer_ros/node_main.cc index 5821cc1..b3930a4 100644 --- a/cartographer_ros/cartographer_ros/node_main.cc +++ b/cartographer_ros/cartographer_ros/node_main.cc @@ -14,13 +14,6 @@ * limitations under the License. */ -#include -#include - -#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.h" #include "cartographer_ros/node_options.h" #include "cartographer_ros/ros_log_sink.h" @@ -39,26 +32,14 @@ DEFINE_string(map_filename, "", "If non-empty, filename of a map to load."); namespace cartographer_ros { namespace { -std::tuple LoadOptions() { - auto file_resolver = cartographer::common::make_unique< - cartographer::common::ConfigurationFileResolver>( - std::vector{FLAGS_configuration_directory}); - const string code = - file_resolver->GetFileContentOrDie(FLAGS_configuration_basename); - cartographer::common::LuaParameterDictionary lua_parameter_dictionary( - code, std::move(file_resolver)); - - return std::make_tuple(CreateNodeOptions(&lua_parameter_dictionary), - CreateTrajectoryOptions(&lua_parameter_dictionary)); -} - void Run() { constexpr double kTfBufferCacheTimeInSeconds = 1e6; tf2_ros::Buffer tf_buffer{::ros::Duration(kTfBufferCacheTimeInSeconds)}; tf2_ros::TransformListener tf(tf_buffer); NodeOptions node_options; TrajectoryOptions trajectory_options; - std::tie(node_options, trajectory_options) = LoadOptions(); + std::tie(node_options, trajectory_options) = + LoadOptions(FLAGS_configuration_directory, FLAGS_configuration_basename); Node node(node_options, &tf_buffer); if (!FLAGS_map_filename.empty()) { diff --git a/cartographer_ros/cartographer_ros/node_options.cc b/cartographer_ros/cartographer_ros/node_options.cc index f487ac9..ae87cb2 100644 --- a/cartographer_ros/cartographer_ros/node_options.cc +++ b/cartographer_ros/cartographer_ros/node_options.cc @@ -16,6 +16,10 @@ #include "cartographer_ros/node_options.h" +#include + +#include "cartographer/common/configuration_file_resolver.h" +#include "cartographer/mapping/map_builder.h" #include "glog/logging.h" namespace cartographer_ros { @@ -36,8 +40,22 @@ NodeOptions CreateNodeOptions( lua_parameter_dictionary->GetDouble("pose_publish_period_sec"); options.trajectory_publish_period_sec = lua_parameter_dictionary->GetDouble("trajectory_publish_period_sec"); - return options; } +std::tuple LoadOptions( + const string& configuration_directory, + const string& configuration_basename) { + auto file_resolver = cartographer::common::make_unique< + cartographer::common::ConfigurationFileResolver>( + std::vector{configuration_directory}); + const string code = + file_resolver->GetFileContentOrDie(configuration_basename); + cartographer::common::LuaParameterDictionary lua_parameter_dictionary( + code, std::move(file_resolver)); + + return std::make_tuple(CreateNodeOptions(&lua_parameter_dictionary), + CreateTrajectoryOptions(&lua_parameter_dictionary)); +} + } // namespace cartographer_ros diff --git a/cartographer_ros/cartographer_ros/node_options.h b/cartographer_ros/cartographer_ros/node_options.h index c695140..1687362 100644 --- a/cartographer_ros/cartographer_ros/node_options.h +++ b/cartographer_ros/cartographer_ros/node_options.h @@ -18,9 +18,12 @@ #define CARTOGRAPHER_ROS_NODE_OPTIONS_H_ #include +#include #include "cartographer/common/lua_parameter_dictionary.h" -#include "cartographer/mapping/map_builder.h" +#include "cartographer/common/port.h" +#include "cartographer/mapping/proto/map_builder_options.pb.h" +#include "cartographer_ros/trajectory_options.h" namespace cartographer_ros { @@ -37,6 +40,10 @@ struct NodeOptions { NodeOptions CreateNodeOptions( ::cartographer::common::LuaParameterDictionary* lua_parameter_dictionary); +std::tuple LoadOptions( + const string& configuration_directory, + const string& configuration_basename); + } // namespace cartographer_ros #endif // CARTOGRAPHER_ROS_NODE_OPTIONS_H_ diff --git a/cartographer_ros/cartographer_ros/offline_node_main.cc b/cartographer_ros/cartographer_ros/offline_node_main.cc index efe13e1..fea3a08 100644 --- a/cartographer_ros/cartographer_ros/offline_node_main.cc +++ b/cartographer_ros/cartographer_ros/offline_node_main.cc @@ -20,8 +20,6 @@ #include #include -#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.h" @@ -61,27 +59,13 @@ constexpr char kClockTopic[] = "clock"; constexpr char kTfStaticTopic[] = "/tf_static"; constexpr char kTfTopic[] = "tf"; -// TODO(hrapp): This is duplicated in node_main.cc. Pull out into a config -// unit. -std::tuple LoadOptions() { - auto file_resolver = cartographer::common::make_unique< - cartographer::common::ConfigurationFileResolver>( - std::vector{FLAGS_configuration_directory}); - const string code = - file_resolver->GetFileContentOrDie(FLAGS_configuration_basename); - cartographer::common::LuaParameterDictionary lua_parameter_dictionary( - code, std::move(file_resolver)); - - return std::make_tuple(CreateNodeOptions(&lua_parameter_dictionary), - CreateTrajectoryOptions(&lua_parameter_dictionary)); -} - void Run(const std::vector& bag_filenames) { const std::chrono::time_point start_time = std::chrono::steady_clock::now(); NodeOptions node_options; TrajectoryOptions trajectory_options; - std::tie(node_options, trajectory_options) = LoadOptions(); + std::tie(node_options, trajectory_options) = + LoadOptions(FLAGS_configuration_directory, FLAGS_configuration_basename); tf2_ros::Buffer tf_buffer; diff --git a/cartographer_ros/cartographer_ros/trajectory_options.cc b/cartographer_ros/cartographer_ros/trajectory_options.cc index 2d423da..4ed8d0f 100644 --- a/cartographer_ros/cartographer_ros/trajectory_options.cc +++ b/cartographer_ros/cartographer_ros/trajectory_options.cc @@ -16,6 +16,7 @@ #include "cartographer_ros/trajectory_options.h" +#include "cartographer/mapping/trajectory_builder.h" #include "glog/logging.h" namespace cartographer_ros { diff --git a/cartographer_ros/cartographer_ros/trajectory_options.h b/cartographer_ros/cartographer_ros/trajectory_options.h index 6590958..25c735d 100644 --- a/cartographer_ros/cartographer_ros/trajectory_options.h +++ b/cartographer_ros/cartographer_ros/trajectory_options.h @@ -21,7 +21,7 @@ #include "cartographer/common/lua_parameter_dictionary.h" #include "cartographer/common/port.h" -#include "cartographer_ros/sensor_bridge.h" +#include "cartographer/mapping/proto/trajectory_builder_options.pb.h" #include "cartographer_ros_msgs/TrajectoryOptions.h" namespace cartographer_ros {