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 
23 #include "glog/logging.h"
24 
25 namespace cartographer_ros {
26 
27 namespace {
28 
29 void CheckTrajectoryOptions(const TrajectoryOptions& options) {
30  CHECK_GE(options.num_subdivisions_per_laser_scan, 1);
31  CHECK_GE(options.num_laser_scans + options.num_multi_echo_laser_scans +
32  options.num_point_clouds,
33  1)
34  << "Configuration error: 'num_laser_scans', "
35  "'num_multi_echo_laser_scans' and 'num_point_clouds' are "
36  "all zero, but at least one is required.";
37 }
38 
39 } // namespace
40 
43  lua_parameter_dictionary) {
46  ::cartographer::mapping::CreateTrajectoryBuilderOptions(
47  lua_parameter_dictionary->GetDictionary("trajectory_builder").get());
48  options.tracking_frame =
49  lua_parameter_dictionary->GetString("tracking_frame");
50  options.published_frame =
51  lua_parameter_dictionary->GetString("published_frame");
52  options.odom_frame = lua_parameter_dictionary->GetString("odom_frame");
53  options.provide_odom_frame =
54  lua_parameter_dictionary->GetBool("provide_odom_frame");
55  options.use_odometry = lua_parameter_dictionary->GetBool("use_odometry");
56  options.use_nav_sat = lua_parameter_dictionary->GetBool("use_nav_sat");
57  options.use_landmarks = lua_parameter_dictionary->GetBool("use_landmarks");
59  lua_parameter_dictionary->GetBool("publish_frame_projected_to_2d");
60  options.num_laser_scans =
61  lua_parameter_dictionary->GetNonNegativeInt("num_laser_scans");
63  lua_parameter_dictionary->GetNonNegativeInt("num_multi_echo_laser_scans");
65  lua_parameter_dictionary->GetNonNegativeInt(
66  "num_subdivisions_per_laser_scan");
67  options.num_point_clouds =
68  lua_parameter_dictionary->GetNonNegativeInt("num_point_clouds");
70  lua_parameter_dictionary->GetDouble("rangefinder_sampling_ratio");
71  options.odometry_sampling_ratio =
72  lua_parameter_dictionary->GetDouble("odometry_sampling_ratio");
74  lua_parameter_dictionary->GetDouble("fixed_frame_pose_sampling_ratio");
75  options.imu_sampling_ratio =
76  lua_parameter_dictionary->GetDouble("imu_sampling_ratio");
77  options.landmarks_sampling_ratio =
78  lua_parameter_dictionary->GetDouble("landmarks_sampling_ratio");
79  CheckTrajectoryOptions(options);
80  return options;
81 }
82 
84  ::cartographer::common::LuaParameterDictionary* lua_parameter_dictionary,
85  ::cartographer::common::LuaParameterDictionary* initial_trajectory_pose) {
86  TrajectoryOptions options = CreateTrajectoryOptions(lua_parameter_dictionary);
87  *options.trajectory_builder_options.mutable_initial_trajectory_pose() =
88  CreateInitialTrajectoryPose(initial_trajectory_pose);
89  return options;
90 }
91 
92 ::cartographer::mapping::proto::InitialTrajectoryPose
94  ::cartographer::common::LuaParameterDictionary* lua_parameter_dictionary) {
95  ::cartographer::mapping::proto::InitialTrajectoryPose pose;
96  pose.set_to_trajectory_id(
97  lua_parameter_dictionary->GetNonNegativeInt("to_trajectory_id"));
98  *pose.mutable_relative_pose() =
100  lua_parameter_dictionary->GetDictionary("relative_pose").get()));
101  pose.set_timestamp(
102  lua_parameter_dictionary->HasKey("timestamp")
103  ? lua_parameter_dictionary->GetNonNegativeInt("timestamp")
105  return pose;
106 }
107 
108 bool FromRosMessage(const cartographer_ros_msgs::TrajectoryOptions& msg,
109  TrajectoryOptions* options) {
110  options->tracking_frame = msg.tracking_frame;
111  options->published_frame = msg.published_frame;
112  options->odom_frame = msg.odom_frame;
113  options->provide_odom_frame = msg.provide_odom_frame;
114  options->use_odometry = msg.use_odometry;
115  options->use_nav_sat = msg.use_nav_sat;
116  options->use_landmarks = msg.use_landmarks;
117  options->publish_frame_projected_to_2d = msg.publish_frame_projected_to_2d;
118  options->num_laser_scans = msg.num_laser_scans;
119  options->num_multi_echo_laser_scans = msg.num_multi_echo_laser_scans;
121  msg.num_subdivisions_per_laser_scan;
122  options->num_point_clouds = msg.num_point_clouds;
123  options->rangefinder_sampling_ratio = msg.rangefinder_sampling_ratio;
124  options->odometry_sampling_ratio = msg.odometry_sampling_ratio;
126  msg.fixed_frame_pose_sampling_ratio;
127  options->imu_sampling_ratio = msg.imu_sampling_ratio;
128  options->landmarks_sampling_ratio = msg.landmarks_sampling_ratio;
129  if (!options->trajectory_builder_options.ParseFromString(
130  msg.trajectory_builder_options_proto)) {
131  LOG(ERROR) << "Failed to parse protobuf";
132  return false;
133  }
134  CheckTrajectoryOptions(*options);
135  return true;
136 }
137 
138 cartographer_ros_msgs::TrajectoryOptions ToRosMessage(
139  const TrajectoryOptions& options) {
140  cartographer_ros_msgs::TrajectoryOptions msg;
141  msg.tracking_frame = options.tracking_frame;
142  msg.published_frame = options.published_frame;
143  msg.odom_frame = options.odom_frame;
144  msg.provide_odom_frame = options.provide_odom_frame;
145  msg.use_odometry = options.use_odometry;
146  msg.use_nav_sat = options.use_nav_sat;
147  msg.use_landmarks = options.use_landmarks;
148  msg.publish_frame_projected_to_2d = options.publish_frame_projected_to_2d;
149  msg.num_laser_scans = options.num_laser_scans;
150  msg.num_multi_echo_laser_scans = options.num_multi_echo_laser_scans;
151  msg.num_subdivisions_per_laser_scan = options.num_subdivisions_per_laser_scan;
152  msg.num_point_clouds = options.num_point_clouds;
153  msg.rangefinder_sampling_ratio = options.rangefinder_sampling_ratio;
154  msg.odometry_sampling_ratio = options.odometry_sampling_ratio;
155  msg.fixed_frame_pose_sampling_ratio = options.fixed_frame_pose_sampling_ratio;
156  msg.imu_sampling_ratio = options.imu_sampling_ratio;
157  msg.landmarks_sampling_ratio = options.landmarks_sampling_ratio;
158  options.trajectory_builder_options.SerializeToString(
159  &msg.trajectory_builder_options_proto);
160  return msg;
161 }
162 
163 } // namespace cartographer_ros
std::string GetString(const std::string &key)
int GetNonNegativeInt(const std::string &key)
double GetDouble(const std::string &key)
proto::Rigid2d ToProto(const transform::Rigid2d &transform)
options
int64 ToUniversal(const Time time)
::cartographer::mapping::proto::TrajectoryBuilderOptions trajectory_builder_options
transform::Rigid3d FromDictionary(common::LuaParameterDictionary *dictionary)
::cartographer::common::Time FromRos(const ::ros::Time &time)
TrajectoryOptions CreateTrajectoryOptions(::cartographer::common::LuaParameterDictionary *const lua_parameter_dictionary)
bool FromRosMessage(const cartographer_ros_msgs::TrajectoryOptions &msg, TrajectoryOptions *options)
std::unique_ptr< LuaParameterDictionary > GetDictionary(const std::string &key)
static Time now()
transform::Rigid3d pose
cartographer_ros_msgs::TrajectoryOptions ToRosMessage(const TrajectoryOptions &options)
::cartographer::mapping::proto::InitialTrajectoryPose CreateInitialTrajectoryPose(::cartographer::common::LuaParameterDictionary *lua_parameter_dictionary)
bool GetBool(const std::string &key)
bool HasKey(const std::string &key) const


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