Deduplicate LoadOptions(). (#471)
parent
2042b73010
commit
4034f4f801
|
@ -17,10 +17,7 @@
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
#include "cartographer/common/configuration_file_resolver.h"
|
|
||||||
#include "cartographer/common/lua_parameter_dictionary.h"
|
|
||||||
#include "cartographer_ros/node_options.h"
|
#include "cartographer_ros/node_options.h"
|
||||||
#include "cartographer_ros/trajectory_options.h"
|
|
||||||
#include "gtest/gtest.h"
|
#include "gtest/gtest.h"
|
||||||
#include "ros/package.h"
|
#include "ros/package.h"
|
||||||
|
|
||||||
|
@ -31,14 +28,9 @@ class ConfigurationFilesTest : public ::testing::TestWithParam<const char*> {};
|
||||||
|
|
||||||
TEST_P(ConfigurationFilesTest, ValidateNodeOptions) {
|
TEST_P(ConfigurationFilesTest, ValidateNodeOptions) {
|
||||||
EXPECT_NO_FATAL_FAILURE({
|
EXPECT_NO_FATAL_FAILURE({
|
||||||
auto file_resolver = ::cartographer::common::make_unique<
|
LoadOptions(
|
||||||
::cartographer::common::ConfigurationFileResolver>(std::vector<string>{
|
::ros::package::getPath("cartographer_ros") + "/configuration_files",
|
||||||
::ros::package::getPath("cartographer_ros") + "/configuration_files"});
|
GetParam());
|
||||||
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);
|
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -14,13 +14,6 @@
|
||||||
* limitations under the License.
|
* limitations under the License.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <string>
|
|
||||||
#include <vector>
|
|
||||||
|
|
||||||
#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.h"
|
||||||
#include "cartographer_ros/node_options.h"
|
#include "cartographer_ros/node_options.h"
|
||||||
#include "cartographer_ros/ros_log_sink.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 cartographer_ros {
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
std::tuple<NodeOptions, TrajectoryOptions> LoadOptions() {
|
|
||||||
auto file_resolver = cartographer::common::make_unique<
|
|
||||||
cartographer::common::ConfigurationFileResolver>(
|
|
||||||
std::vector<string>{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() {
|
void Run() {
|
||||||
constexpr double kTfBufferCacheTimeInSeconds = 1e6;
|
constexpr double kTfBufferCacheTimeInSeconds = 1e6;
|
||||||
tf2_ros::Buffer tf_buffer{::ros::Duration(kTfBufferCacheTimeInSeconds)};
|
tf2_ros::Buffer tf_buffer{::ros::Duration(kTfBufferCacheTimeInSeconds)};
|
||||||
tf2_ros::TransformListener tf(tf_buffer);
|
tf2_ros::TransformListener tf(tf_buffer);
|
||||||
NodeOptions node_options;
|
NodeOptions node_options;
|
||||||
TrajectoryOptions trajectory_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);
|
Node node(node_options, &tf_buffer);
|
||||||
if (!FLAGS_map_filename.empty()) {
|
if (!FLAGS_map_filename.empty()) {
|
||||||
|
|
|
@ -16,6 +16,10 @@
|
||||||
|
|
||||||
#include "cartographer_ros/node_options.h"
|
#include "cartographer_ros/node_options.h"
|
||||||
|
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
#include "cartographer/common/configuration_file_resolver.h"
|
||||||
|
#include "cartographer/mapping/map_builder.h"
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
|
|
||||||
namespace cartographer_ros {
|
namespace cartographer_ros {
|
||||||
|
@ -36,8 +40,22 @@ NodeOptions CreateNodeOptions(
|
||||||
lua_parameter_dictionary->GetDouble("pose_publish_period_sec");
|
lua_parameter_dictionary->GetDouble("pose_publish_period_sec");
|
||||||
options.trajectory_publish_period_sec =
|
options.trajectory_publish_period_sec =
|
||||||
lua_parameter_dictionary->GetDouble("trajectory_publish_period_sec");
|
lua_parameter_dictionary->GetDouble("trajectory_publish_period_sec");
|
||||||
|
|
||||||
return options;
|
return options;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
std::tuple<NodeOptions, TrajectoryOptions> LoadOptions(
|
||||||
|
const string& configuration_directory,
|
||||||
|
const string& configuration_basename) {
|
||||||
|
auto file_resolver = cartographer::common::make_unique<
|
||||||
|
cartographer::common::ConfigurationFileResolver>(
|
||||||
|
std::vector<string>{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
|
} // namespace cartographer_ros
|
||||||
|
|
|
@ -18,9 +18,12 @@
|
||||||
#define CARTOGRAPHER_ROS_NODE_OPTIONS_H_
|
#define CARTOGRAPHER_ROS_NODE_OPTIONS_H_
|
||||||
|
|
||||||
#include <string>
|
#include <string>
|
||||||
|
#include <tuple>
|
||||||
|
|
||||||
#include "cartographer/common/lua_parameter_dictionary.h"
|
#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 {
|
namespace cartographer_ros {
|
||||||
|
|
||||||
|
@ -37,6 +40,10 @@ struct NodeOptions {
|
||||||
NodeOptions CreateNodeOptions(
|
NodeOptions CreateNodeOptions(
|
||||||
::cartographer::common::LuaParameterDictionary* lua_parameter_dictionary);
|
::cartographer::common::LuaParameterDictionary* lua_parameter_dictionary);
|
||||||
|
|
||||||
|
std::tuple<NodeOptions, TrajectoryOptions> LoadOptions(
|
||||||
|
const string& configuration_directory,
|
||||||
|
const string& configuration_basename);
|
||||||
|
|
||||||
} // namespace cartographer_ros
|
} // namespace cartographer_ros
|
||||||
|
|
||||||
#endif // CARTOGRAPHER_ROS_NODE_OPTIONS_H_
|
#endif // CARTOGRAPHER_ROS_NODE_OPTIONS_H_
|
||||||
|
|
|
@ -20,8 +20,6 @@
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
#include "cartographer/common/configuration_file_resolver.h"
|
|
||||||
#include "cartographer/common/lua_parameter_dictionary.h"
|
|
||||||
#include "cartographer/common/make_unique.h"
|
#include "cartographer/common/make_unique.h"
|
||||||
#include "cartographer/common/port.h"
|
#include "cartographer/common/port.h"
|
||||||
#include "cartographer_ros/node.h"
|
#include "cartographer_ros/node.h"
|
||||||
|
@ -61,27 +59,13 @@ constexpr char kClockTopic[] = "clock";
|
||||||
constexpr char kTfStaticTopic[] = "/tf_static";
|
constexpr char kTfStaticTopic[] = "/tf_static";
|
||||||
constexpr char kTfTopic[] = "tf";
|
constexpr char kTfTopic[] = "tf";
|
||||||
|
|
||||||
// TODO(hrapp): This is duplicated in node_main.cc. Pull out into a config
|
|
||||||
// unit.
|
|
||||||
std::tuple<NodeOptions, TrajectoryOptions> LoadOptions() {
|
|
||||||
auto file_resolver = cartographer::common::make_unique<
|
|
||||||
cartographer::common::ConfigurationFileResolver>(
|
|
||||||
std::vector<string>{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<string>& bag_filenames) {
|
void Run(const std::vector<string>& bag_filenames) {
|
||||||
const std::chrono::time_point<std::chrono::steady_clock> start_time =
|
const std::chrono::time_point<std::chrono::steady_clock> start_time =
|
||||||
std::chrono::steady_clock::now();
|
std::chrono::steady_clock::now();
|
||||||
NodeOptions node_options;
|
NodeOptions node_options;
|
||||||
TrajectoryOptions trajectory_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;
|
tf2_ros::Buffer tf_buffer;
|
||||||
|
|
||||||
|
|
|
@ -16,6 +16,7 @@
|
||||||
|
|
||||||
#include "cartographer_ros/trajectory_options.h"
|
#include "cartographer_ros/trajectory_options.h"
|
||||||
|
|
||||||
|
#include "cartographer/mapping/trajectory_builder.h"
|
||||||
#include "glog/logging.h"
|
#include "glog/logging.h"
|
||||||
|
|
||||||
namespace cartographer_ros {
|
namespace cartographer_ros {
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
#include "cartographer/common/lua_parameter_dictionary.h"
|
#include "cartographer/common/lua_parameter_dictionary.h"
|
||||||
#include "cartographer/common/port.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"
|
#include "cartographer_ros_msgs/TrajectoryOptions.h"
|
||||||
|
|
||||||
namespace cartographer_ros {
|
namespace cartographer_ros {
|
||||||
|
|
Loading…
Reference in New Issue