Adds configuration files test. (#172)
parent
12ea8386bb
commit
965490f611
|
@ -22,8 +22,9 @@ set(PACKAGE_DEPENDENCIES
|
|||
geometry_msgs
|
||||
nav_msgs
|
||||
pcl_conversions
|
||||
roscpp
|
||||
rosbag
|
||||
roscpp
|
||||
roslib
|
||||
sensor_msgs
|
||||
tf2
|
||||
tf2_eigen
|
||||
|
|
|
@ -93,6 +93,14 @@ google_library(time_conversion
|
|||
time_conversion.h
|
||||
)
|
||||
|
||||
google_test(configuration_files_test
|
||||
USES_CARTOGRAPHER
|
||||
SRCS
|
||||
configuration_files_test.cc
|
||||
DEPENDS
|
||||
node_options
|
||||
)
|
||||
|
||||
google_test(time_conversion_test
|
||||
USES_CARTOGRAPHER
|
||||
SRCS
|
||||
|
|
|
@ -0,0 +1,48 @@
|
|||
/*
|
||||
* Copyright 2016 The Cartographer Authors
|
||||
*
|
||||
* Licensed under the Apache License, Version 2.0 (the "License");
|
||||
* you may not use this file except in compliance with the License.
|
||||
* You may obtain a copy of the License at
|
||||
*
|
||||
* http://www.apache.org/licenses/LICENSE-2.0
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*/
|
||||
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#include "cartographer/common/configuration_file_resolver.h"
|
||||
#include "cartographer/common/lua_parameter_dictionary.h"
|
||||
#include "cartographer_ros/node_options.h"
|
||||
#include "gtest/gtest.h"
|
||||
#include "ros/package.h"
|
||||
|
||||
namespace cartographer_ros {
|
||||
namespace {
|
||||
|
||||
class ConfigurationFilesTest : public ::testing::TestWithParam<const char*> {};
|
||||
|
||||
TEST_P(ConfigurationFilesTest, ValidateNodeOptions) {
|
||||
EXPECT_NO_FATAL_FAILURE({
|
||||
auto file_resolver = ::cartographer::common::make_unique<
|
||||
::cartographer::common::ConfigurationFileResolver>(std::vector<string>{
|
||||
::ros::package::getPath("cartographer_ros") + "/configuration_files"});
|
||||
const string code = file_resolver->GetFileContentOrDie(GetParam());
|
||||
::cartographer::common::LuaParameterDictionary lua_parameter_dictionary(
|
||||
code, std::move(file_resolver), nullptr);
|
||||
::cartographer_ros::CreateNodeOptions(&lua_parameter_dictionary);
|
||||
});
|
||||
}
|
||||
|
||||
INSTANTIATE_TEST_CASE_P(ValidateAllNodeOptions, ConfigurationFilesTest,
|
||||
::testing::Values("backpack_2d.lua", "backpack_3d.lua",
|
||||
"pr2.lua", "revo_lds.lua"));
|
||||
|
||||
} // namespace
|
||||
} // namespace cartographer_ros
|
|
@ -22,7 +22,6 @@
|
|||
#include "cartographer/common/lua_parameter_dictionary.h"
|
||||
#include "cartographer/common/port.h"
|
||||
#include "cartographer/mapping/map_builder.h"
|
||||
|
||||
#include "cartographer_ros/sensor_bridge.h"
|
||||
|
||||
namespace cartographer_ros {
|
||||
|
|
|
@ -36,9 +36,9 @@ options = {
|
|||
|
||||
MAP_BUILDER.use_trajectory_builder_2d = true
|
||||
|
||||
TRAJECTORY_BUILDER_2D.laser_min_range = 0.3,
|
||||
TRAJECTORY_BUILDER_2D.laser_max_range = 8.,
|
||||
TRAJECTORY_BUILDER_2D.laser_missing_echo_ray_length = 1.,
|
||||
TRAJECTORY_BUILDER_2D.laser_min_range = 0.3
|
||||
TRAJECTORY_BUILDER_2D.laser_max_range = 8.
|
||||
TRAJECTORY_BUILDER_2D.laser_missing_echo_ray_length = 1.
|
||||
TRAJECTORY_BUILDER_2D.use_imu_data = false
|
||||
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
|
||||
|
||||
|
|
Loading…
Reference in New Issue