node_options.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
19 #include <vector>
20 
23 #include "glog/logging.h"
24 
25 namespace cartographer_ros {
26 
29  lua_parameter_dictionary) {
31  options.map_builder_options =
32  ::cartographer::mapping::CreateMapBuilderOptions(
33  lua_parameter_dictionary->GetDictionary("map_builder").get());
34  options.map_frame = lua_parameter_dictionary->GetString("map_frame");
36  lua_parameter_dictionary->GetDouble("lookup_transform_timeout_sec");
38  lua_parameter_dictionary->GetDouble("submap_publish_period_sec");
39  options.pose_publish_period_sec =
40  lua_parameter_dictionary->GetDouble("pose_publish_period_sec");
42  lua_parameter_dictionary->GetDouble("trajectory_publish_period_sec");
43  return options;
44 }
45 
46 std::tuple<NodeOptions, TrajectoryOptions> LoadOptions(
47  const std::string& configuration_directory,
48  const std::string& configuration_basename) {
49  auto file_resolver = cartographer::common::make_unique<
51  std::vector<std::string>{configuration_directory});
52  const std::string code =
53  file_resolver->GetFileContentOrDie(configuration_basename);
54  cartographer::common::LuaParameterDictionary lua_parameter_dictionary(
55  code, std::move(file_resolver));
56 
57  return std::make_tuple(CreateNodeOptions(&lua_parameter_dictionary),
58  CreateTrajectoryOptions(&lua_parameter_dictionary));
59 }
60 
61 } // namespace cartographer_ros
::cartographer::mapping::proto::MapBuilderOptions map_builder_options
Definition: node_options.h:32
std::string GetString(const std::string &key)
_Unique_if< T >::_Single_object make_unique(Args &&... args)
double GetDouble(const std::string &key)
std::tuple< NodeOptions, TrajectoryOptions > LoadOptions(const std::string &configuration_directory, const std::string &configuration_basename)
Definition: node_options.cc:46
options
NodeOptions CreateNodeOptions(::cartographer::common::LuaParameterDictionary *const lua_parameter_dictionary)
Definition: node_options.cc:27
std::string GetFileContentOrDie(const std::string &basename) override
TrajectoryOptions CreateTrajectoryOptions(::cartographer::common::LuaParameterDictionary *const lua_parameter_dictionary)
std::unique_ptr< LuaParameterDictionary > GetDictionary(const std::string &key)


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:06:05