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_TRAJECTORY_OPTIONS_H 00018 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TRAJECTORY_OPTIONS_H 00019 00020 #include <string> 00021 00022 #include "cartographer/common/lua_parameter_dictionary.h" 00023 #include "cartographer/common/port.h" 00024 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h" 00025 00026 namespace cartographer_ros { 00027 00028 struct TrajectoryOptions { 00029 ::cartographer::mapping::proto::TrajectoryBuilderOptions 00030 trajectory_builder_options; 00031 std::string tracking_frame; 00032 std::string published_frame; 00033 std::string odom_frame; 00034 bool provide_odom_frame; 00035 bool use_odometry; 00036 bool use_nav_sat; 00037 bool use_landmarks; 00038 bool publish_frame_projected_to_2d; 00039 int num_laser_scans; 00040 int num_multi_echo_laser_scans; 00041 int num_subdivisions_per_laser_scan; 00042 int num_point_clouds; 00043 double rangefinder_sampling_ratio; 00044 double odometry_sampling_ratio; 00045 double fixed_frame_pose_sampling_ratio; 00046 double imu_sampling_ratio; 00047 double landmarks_sampling_ratio; 00048 }; 00049 00050 TrajectoryOptions CreateTrajectoryOptions( 00051 ::cartographer::common::LuaParameterDictionary* lua_parameter_dictionary); 00052 00053 } // namespace cartographer_ros 00054 00055 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TRAJECTORY_OPTIONS_H