node_options.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer_ros/node_options.h"
00018 
00019 #include <vector>
00020 
00021 #include "cartographer/common/configuration_file_resolver.h"
00022 #include "cartographer/mapping/map_builder.h"
00023 #include "glog/logging.h"
00024 
00025 namespace cartographer_ros {
00026 
00027 NodeOptions CreateNodeOptions(
00028     ::cartographer::common::LuaParameterDictionary* const
00029         lua_parameter_dictionary) {
00030   NodeOptions options;
00031   options.map_builder_options =
00032       ::cartographer::mapping::CreateMapBuilderOptions(
00033           lua_parameter_dictionary->GetDictionary("map_builder").get());
00034   options.map_frame = lua_parameter_dictionary->GetString("map_frame");
00035   options.lookup_transform_timeout_sec =
00036       lua_parameter_dictionary->GetDouble("lookup_transform_timeout_sec");
00037   options.submap_publish_period_sec =
00038       lua_parameter_dictionary->GetDouble("submap_publish_period_sec");
00039   options.pose_publish_period_sec =
00040       lua_parameter_dictionary->GetDouble("pose_publish_period_sec");
00041   options.trajectory_publish_period_sec =
00042       lua_parameter_dictionary->GetDouble("trajectory_publish_period_sec");
00043   if (lua_parameter_dictionary->HasKey("use_pose_extrapolator")) {
00044     options.use_pose_extrapolator =
00045         lua_parameter_dictionary->GetBool("use_pose_extrapolator");
00046   }
00047   return options;
00048 }
00049 
00050 std::tuple<NodeOptions, TrajectoryOptions> LoadOptions(
00051     const std::string& configuration_directory,
00052     const std::string& configuration_basename) {
00053   auto file_resolver =
00054       absl::make_unique<cartographer::common::ConfigurationFileResolver>(
00055           std::vector<std::string>{configuration_directory});
00056   const std::string code =
00057       file_resolver->GetFileContentOrDie(configuration_basename);
00058   cartographer::common::LuaParameterDictionary lua_parameter_dictionary(
00059       code, std::move(file_resolver));
00060 
00061   return std::make_tuple(CreateNodeOptions(&lua_parameter_dictionary),
00062                          CreateTrajectoryOptions(&lua_parameter_dictionary));
00063 }
00064 
00065 }  // namespace cartographer_ros


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Wed Jul 10 2019 04:10:28