28 #include "gtest/gtest.h" 32 namespace scan_matching {
35 class CeresScanMatcherTest :
public ::testing::Test {
37 CeresScanMatcherTest()
39 MapLimits(1.,
Eigen::Vector2d(10., 10.), CellLimits(20, 20))) {
48 occupied_space_weight = 1., 49 translation_weight = 0.1, 50 rotation_weight = 1.5, 51 ceres_solver_options = { 52 use_nonmonotonic_steps = true, 53 max_num_iterations = 50, 57 const proto::CeresScanMatcherOptions2D options =
66 ceres::Solver::Summary summary;
70 EXPECT_NEAR(0., summary.final_cost, 1e-2) << summary.FullReport();
71 EXPECT_THAT(pose, transform::IsNearly(expected_pose, 1e-2))
81 TEST_F(CeresScanMatcherTest, testPerfectEstimate) {
85 TEST_F(CeresScanMatcherTest, testOptimizeAlongX) {
89 TEST_F(CeresScanMatcherTest, testOptimizeAlongY) {
93 TEST_F(CeresScanMatcherTest, testOptimizeAlongXY) {
std::unique_ptr< CeresScanMatcher2D > ceres_scan_matcher_
std::unique_ptr< LuaParameterDictionary > MakeDictionary(const std::string &code)
constexpr float kMaxProbability
proto::CeresScanMatcherOptions2D CreateCeresScanMatcherOptions2D(common::LuaParameterDictionary *const parameter_dictionary)
std::vector< Eigen::Vector3f > PointCloud
sensor::PointCloud point_cloud_
ProbabilityGrid probability_grid_