trajectory_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 "glog/logging.h"
20 
21 namespace cartographer_ros {
22 
25  lua_parameter_dictionary) {
28  ::cartographer::mapping::CreateTrajectoryBuilderOptions(
29  lua_parameter_dictionary->GetDictionary("trajectory_builder").get());
30  options.tracking_frame =
31  lua_parameter_dictionary->GetString("tracking_frame");
32  options.published_frame =
33  lua_parameter_dictionary->GetString("published_frame");
34  options.odom_frame = lua_parameter_dictionary->GetString("odom_frame");
35  options.provide_odom_frame =
36  lua_parameter_dictionary->GetBool("provide_odom_frame");
37  options.use_odometry = lua_parameter_dictionary->GetBool("use_odometry");
38  options.use_laser_scan = lua_parameter_dictionary->GetBool("use_laser_scan");
40  lua_parameter_dictionary->GetBool("use_multi_echo_laser_scan");
41  options.num_point_clouds =
42  lua_parameter_dictionary->GetNonNegativeInt("num_point_clouds");
43 
44  CHECK_EQ(options.use_laser_scan + options.use_multi_echo_laser_scan +
45  (options.num_point_clouds > 0),
46  1)
47  << "Configuration error: 'use_laser_scan', "
48  "'use_multi_echo_laser_scan' and 'num_point_clouds' are "
49  "mutually exclusive, but one is required.";
50 
51  return options;
52 }
53 } // namespace cartographer_ros
options
::cartographer::mapping::proto::TrajectoryBuilderOptions trajectory_builder_options
TrajectoryOptions CreateTrajectoryOptions(::cartographer::common::LuaParameterDictionary *const lua_parameter_dictionary)
std::unique_ptr< LuaParameterDictionary > GetDictionary(const string &key)


cartographer_ros
Author(s):
autogenerated on Wed Jun 5 2019 22:35:56