Fix configuration checks during start up. (#258)

We now destroy the LuaParameterDictionary directly after
constructing the NodeOptions, so that it is verified
whether all mentioned parameters are understood.
Before, this was checked when shutting down the node.
master
Wolfgang Hess 2017-01-25 13:54:35 +01:00 committed by GitHub
parent 2a2286deb0
commit f7057fc5a3
3 changed files with 16 additions and 7 deletions

View File

@ -52,9 +52,9 @@ std::unique_ptr<tf2_ros::Buffer> ReadTransformsFromBag(
}
}
}
LOG_EVERY_N(INFO, 100000) << "Processed "
<< (msg.getTime() - begin_time).toSec() << " of "
<< duration_in_seconds << " bag time seconds...";
LOG_EVERY_N(INFO, 100000)
<< "Processed " << (msg.getTime() - begin_time).toSec() << " of "
<< duration_in_seconds << " bag time seconds...";
}
bag.close();

View File

@ -39,7 +39,7 @@ namespace {
constexpr int kInfiniteSubscriberQueueSize = 0;
void Run() {
NodeOptions LoadOptions() {
auto file_resolver = cartographer::common::make_unique<
cartographer::common::ConfigurationFileResolver>(
std::vector<string>{FLAGS_configuration_directory});
@ -48,7 +48,11 @@ void Run() {
cartographer::common::LuaParameterDictionary lua_parameter_dictionary(
code, std::move(file_resolver));
const auto options = CreateNodeOptions(&lua_parameter_dictionary);
return CreateNodeOptions(&lua_parameter_dictionary);
}
void Run() {
const auto options = LoadOptions();
constexpr double kTfBufferCacheTimeInSeconds = 1e6;
tf2_ros::Buffer tf_buffer{::ros::Duration(kTfBufferCacheTimeInSeconds)};
tf2_ros::TransformListener tf(tf_buffer);

View File

@ -67,7 +67,7 @@ std::vector<string> SplitString(const string& input, const char delimiter) {
return tokens;
}
void Run(std::vector<string> bag_filenames) {
NodeOptions LoadOptions() {
auto file_resolver = cartographer::common::make_unique<
cartographer::common::ConfigurationFileResolver>(
std::vector<string>{FLAGS_configuration_directory});
@ -76,6 +76,12 @@ void Run(std::vector<string> bag_filenames) {
cartographer::common::LuaParameterDictionary lua_parameter_dictionary(
code, std::move(file_resolver));
return CreateNodeOptions(&lua_parameter_dictionary);
}
void Run(const std::vector<string>& bag_filenames) {
auto options = LoadOptions();
auto tf_buffer = ::cartographer::common::make_unique<tf2_ros::Buffer>();
if (!FLAGS_urdf_filename.empty()) {
ReadStaticTransformsFromUrdf(FLAGS_urdf_filename, tf_buffer.get());
@ -87,7 +93,6 @@ void Run(std::vector<string> bag_filenames) {
}
tf_buffer->setUsingDedicatedThread(true);
auto options = CreateNodeOptions(&lua_parameter_dictionary);
// Since we preload the transform buffer, we should never have to wait for a
// transform. When we finish processing the bag, we will simply drop any
// remaining sensor data that cannot be transformed due to missing transforms.