Main Page
Namespaces
Classes
Files
File List
File Members
cartographer_ros
node_main.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
17
#include <string>
18
#include <vector>
19
20
#include "
cartographer/common/configuration_file_resolver.h
"
21
#include "
cartographer/common/lua_parameter_dictionary.h
"
22
#include "
cartographer/common/make_unique.h
"
23
#include "
cartographer/common/port.h
"
24
#include "
cartographer_ros/node.h
"
25
#include "
cartographer_ros/node_options.h
"
26
#include "
cartographer_ros/ros_log_sink.h
"
27
#include "gflags/gflags.h"
28
#include "
tf2_ros/transform_listener.h
"
29
30
DEFINE_string
(configuration_directory,
""
,
31
"First directory in which configuration files are searched, "
32
"second is always the Cartographer installation to allow "
33
"including files from there."
);
34
DEFINE_string
(configuration_basename,
""
,
35
"Basename, i.e. not containing any directory prefix, of the "
36
"configuration file."
);
37
38
namespace
cartographer_ros
{
39
namespace
{
40
41
std::tuple<NodeOptions, TrajectoryOptions> LoadOptions() {
42
auto
file_resolver =
cartographer::common::make_unique
<
43
cartographer::common::ConfigurationFileResolver
>(
44
std::vector<string>{FLAGS_configuration_directory});
45
const
string
code =
46
file_resolver->
GetFileContentOrDie
(FLAGS_configuration_basename);
47
cartographer::common::LuaParameterDictionary
lua_parameter_dictionary(
48
code, std::move(file_resolver));
49
50
return
std::make_tuple(
CreateNodeOptions
(&lua_parameter_dictionary),
51
CreateTrajectoryOptions
(&lua_parameter_dictionary));
52
}
53
54
void
Run
() {
55
constexpr
double
kTfBufferCacheTimeInSeconds = 1e6;
56
tf2_ros::Buffer
tf_buffer
{
::ros::Duration
(kTfBufferCacheTimeInSeconds)};
57
tf2_ros::TransformListener
tf
(tf_buffer);
58
NodeOptions node_options;
59
TrajectoryOptions trajectory_options;
60
std::tie(node_options, trajectory_options) = LoadOptions();
61
62
Node node(node_options, &tf_buffer);
63
node.StartTrajectoryWithDefaultTopics(trajectory_options);
64
65
::ros::spin();
66
67
node.FinishAllTrajectories();
68
}
69
70
}
// namespace
71
}
// namespace cartographer_ros
72
73
int
main
(
int
argc,
char
** argv) {
74
google::InitGoogleLogging(argv[0]);
75
google::ParseCommandLineFlags(&argc, &argv,
true
);
76
77
CHECK(!FLAGS_configuration_directory.empty())
78
<<
"-configuration_directory is missing."
;
79
CHECK(!FLAGS_configuration_basename.empty())
80
<<
"-configuration_basename is missing."
;
81
82
::ros::init(argc, argv,
"cartographer_node"
);
83
::ros::start();
84
85
cartographer_ros::ScopedRosLogSink
ros_log_sink;
86
cartographer_ros::Run();
87
::ros::shutdown();
88
}
transform_listener.h
node.h
cartographer::common::ConfigurationFileResolver
tf
tf2_ros::Buffer
ros_log_sink.h
main
int main(int argc, char **argv)
Definition:
node_main.cc:73
lua_parameter_dictionary.h
cartographer_ros::ScopedRosLogSink
Definition:
ros_log_sink.h:28
cartographer_ros::CreateNodeOptions
NodeOptions CreateNodeOptions(::cartographer::common::LuaParameterDictionary *const lua_parameter_dictionary)
Definition:
node_options.cc:23
cartographer::common::ConfigurationFileResolver::GetFileContentOrDie
std::string GetFileContentOrDie(const std::string &basename) override
cartographer_ros::CreateTrajectoryOptions
TrajectoryOptions CreateTrajectoryOptions(::cartographer::common::LuaParameterDictionary *const lua_parameter_dictionary)
Definition:
trajectory_options.cc:23
cartographer::common::LuaParameterDictionary
port.h
tf2_ros::TransformListener
make_unique.h
ros::Duration
DEFINE_string
DEFINE_string(configuration_directory,"","First directory in which configuration files are searched, ""second is always the Cartographer installation to allow ""including files from there.")
Run
void Run(const std::string &configuration_directory, const std::string &configuration_basename)
node_options.h
tf_buffer
tf2_ros::Buffer * tf_buffer
cartographer::common::make_unique
_Unique_if< T >::_Single_object make_unique(Args &&...args)
cartographer_ros
Definition:
assets_writer.cc:32
configuration_file_resolver.h
cartographer_ros
Author(s):
autogenerated on Mon Jun 10 2019 12:59:40