trajectory_options.h
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 
17 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TRAJECTORY_OPTIONS_H
18 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TRAJECTORY_OPTIONS_H
19 
20 #include <string>
21 
24 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h"
25 #include "cartographer_ros_msgs/TrajectoryOptions.h"
26 
27 namespace cartographer_ros {
28 
30  ::cartographer::mapping::proto::TrajectoryBuilderOptions
32  std::string tracking_frame;
33  std::string published_frame;
34  std::string odom_frame;
49 };
50 
51 ::cartographer::mapping::proto::InitialTrajectoryPose
53  ::cartographer::common::LuaParameterDictionary* lua_parameter_dictionary);
54 
56  ::cartographer::common::LuaParameterDictionary* lua_parameter_dictionary);
57 
59  ::cartographer::common::LuaParameterDictionary* lua_parameter_dictionary,
60  ::cartographer::common::LuaParameterDictionary* initial_trajectory_pose);
61 
62 // Try to convert 'msg' into 'options'. Returns false on failure.
63 bool FromRosMessage(const cartographer_ros_msgs::TrajectoryOptions& msg,
64  TrajectoryOptions* options);
65 
66 // Converts 'trajectory_options' into a ROS message.
67 cartographer_ros_msgs::TrajectoryOptions ToRosMessage(
68  const TrajectoryOptions& trajectory_options);
69 
70 } // namespace cartographer_ros
71 
72 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TRAJECTORY_OPTIONS_H
::cartographer::mapping::proto::TrajectoryBuilderOptions trajectory_builder_options
TrajectoryOptions CreateTrajectoryOptions(::cartographer::common::LuaParameterDictionary *const lua_parameter_dictionary)
bool FromRosMessage(const cartographer_ros_msgs::TrajectoryOptions &msg, TrajectoryOptions *options)
cartographer_ros_msgs::TrajectoryOptions ToRosMessage(const TrajectoryOptions &options)
::cartographer::mapping::proto::InitialTrajectoryPose CreateInitialTrajectoryPose(::cartographer::common::LuaParameterDictionary *lua_parameter_dictionary)


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