27 #include "gtest/gtest.h" 31 namespace scan_matching {
34 class CeresScanMatcher3DTest :
public ::testing::Test {
36 CeresScanMatcher3DTest()
39 transform::
Rigid3d::Translation(
Eigen::Vector3d(-1., 0., 0.))) {
40 for (
const Eigen::Vector3f& point :
41 {Eigen::Vector3f(-3.f, 2.f, 0.f), Eigen::Vector3f(-4.f, 2.f, 0.f),
42 Eigen::Vector3f(-5.f, 2.f, 0.f), Eigen::Vector3f(-6.f, 2.f, 0.f),
43 Eigen::Vector3f(-6.f, 3.f, 1.f), Eigen::Vector3f(-6.f, 4.f, 2.f),
44 Eigen::Vector3f(-7.f, 3.f, 1.f)}) {
52 occupied_space_weight_0 = 1., 53 translation_weight = 0.01, 54 rotation_weight = 0.1, 55 only_optimize_yaw = false, 56 ceres_solver_options = { 57 use_nonmonotonic_steps = true, 58 max_num_iterations = 10, 69 ceres::Solver::Summary summary;
73 EXPECT_NEAR(0., summary.final_cost, 1e-2) << summary.FullReport();
84 TEST_F(CeresScanMatcher3DTest, PerfectEstimate) {
89 TEST_F(CeresScanMatcher3DTest, AlongX) {
95 TEST_F(CeresScanMatcher3DTest, AlongZ) {
100 TEST_F(CeresScanMatcher3DTest, AlongXYZ) {
105 TEST_F(CeresScanMatcher3DTest, FullPoseCorrection) {
108 Eigen::AngleAxisd(0.05, Eigen::Vector3d(0., 0., 1.)));
115 Eigen::AngleAxisd(0.05, Eigen::Vector3d(1., 0., 0.))));
PointCloud TransformPointCloud(const PointCloud &point_cloud, const transform::Rigid3f &transform)
proto::CeresScanMatcherOptions3D CreateCeresScanMatcherOptions3D(common::LuaParameterDictionary *const parameter_dictionary)
std::unique_ptr< LuaParameterDictionary > MakeDictionary(const std::string &code)
transform::Rigid3d expected_pose_
std::unique_ptr< CeresScanMatcher3D > ceres_scan_matcher_
proto::CeresScanMatcherOptions3D options_
std::vector< Eigen::Vector3f > PointCloud
sensor::PointCloud point_cloud_