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 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_NODE_OPTIONS_H 00018 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_NODE_OPTIONS_H 00019 00020 #include <string> 00021 #include <tuple> 00022 00023 #include "cartographer/common/lua_parameter_dictionary.h" 00024 #include "cartographer/common/port.h" 00025 #include "cartographer/mapping/proto/map_builder_options.pb.h" 00026 #include "cartographer_ros/trajectory_options.h" 00027 00028 namespace cartographer_ros { 00029 00030 // Top-level options of Cartographer's ROS integration. 00031 struct NodeOptions { 00032 ::cartographer::mapping::proto::MapBuilderOptions map_builder_options; 00033 std::string map_frame; 00034 double lookup_transform_timeout_sec; 00035 double submap_publish_period_sec; 00036 double pose_publish_period_sec; 00037 double trajectory_publish_period_sec; 00038 bool use_pose_extrapolator = true; 00039 }; 00040 00041 NodeOptions CreateNodeOptions( 00042 ::cartographer::common::LuaParameterDictionary* lua_parameter_dictionary); 00043 00044 std::tuple<NodeOptions, TrajectoryOptions> LoadOptions( 00045 const std::string& configuration_directory, 00046 const std::string& configuration_basename); 00047 } // namespace cartographer_ros 00048 00049 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_NODE_OPTIONS_H