Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer_ros/trajectory_options.h"
00018
00019 #include "cartographer/mapping/trajectory_builder_interface.h"
00020 #include "cartographer/transform/rigid_transform.h"
00021 #include "cartographer/transform/transform.h"
00022 #include "cartographer_ros/time_conversion.h"
00023 #include "glog/logging.h"
00024
00025 namespace cartographer_ros {
00026
00027 namespace {
00028
00029 void CheckTrajectoryOptions(const TrajectoryOptions& options) {
00030 CHECK_GE(options.num_subdivisions_per_laser_scan, 1);
00031 CHECK_GE(options.num_laser_scans + options.num_multi_echo_laser_scans +
00032 options.num_point_clouds,
00033 1)
00034 << "Configuration error: 'num_laser_scans', "
00035 "'num_multi_echo_laser_scans' and 'num_point_clouds' are "
00036 "all zero, but at least one is required.";
00037 }
00038
00039 }
00040
00041 TrajectoryOptions CreateTrajectoryOptions(
00042 ::cartographer::common::LuaParameterDictionary* const
00043 lua_parameter_dictionary) {
00044 TrajectoryOptions options;
00045 options.trajectory_builder_options =
00046 ::cartographer::mapping::CreateTrajectoryBuilderOptions(
00047 lua_parameter_dictionary->GetDictionary("trajectory_builder").get());
00048 options.tracking_frame =
00049 lua_parameter_dictionary->GetString("tracking_frame");
00050 options.published_frame =
00051 lua_parameter_dictionary->GetString("published_frame");
00052 options.odom_frame = lua_parameter_dictionary->GetString("odom_frame");
00053 options.provide_odom_frame =
00054 lua_parameter_dictionary->GetBool("provide_odom_frame");
00055 options.use_odometry = lua_parameter_dictionary->GetBool("use_odometry");
00056 options.use_nav_sat = lua_parameter_dictionary->GetBool("use_nav_sat");
00057 options.use_landmarks = lua_parameter_dictionary->GetBool("use_landmarks");
00058 options.publish_frame_projected_to_2d =
00059 lua_parameter_dictionary->GetBool("publish_frame_projected_to_2d");
00060 options.num_laser_scans =
00061 lua_parameter_dictionary->GetNonNegativeInt("num_laser_scans");
00062 options.num_multi_echo_laser_scans =
00063 lua_parameter_dictionary->GetNonNegativeInt("num_multi_echo_laser_scans");
00064 options.num_subdivisions_per_laser_scan =
00065 lua_parameter_dictionary->GetNonNegativeInt(
00066 "num_subdivisions_per_laser_scan");
00067 options.num_point_clouds =
00068 lua_parameter_dictionary->GetNonNegativeInt("num_point_clouds");
00069 options.rangefinder_sampling_ratio =
00070 lua_parameter_dictionary->GetDouble("rangefinder_sampling_ratio");
00071 options.odometry_sampling_ratio =
00072 lua_parameter_dictionary->GetDouble("odometry_sampling_ratio");
00073 options.fixed_frame_pose_sampling_ratio =
00074 lua_parameter_dictionary->GetDouble("fixed_frame_pose_sampling_ratio");
00075 options.imu_sampling_ratio =
00076 lua_parameter_dictionary->GetDouble("imu_sampling_ratio");
00077 options.landmarks_sampling_ratio =
00078 lua_parameter_dictionary->GetDouble("landmarks_sampling_ratio");
00079 CheckTrajectoryOptions(options);
00080 return options;
00081 }
00082 }