#ifdef BUILD_WITH_FAST_GICP #include #include #include #include #include #include #include #include #include namespace small_gicp { class FastVGICPOdometryEstimation : public OnlineOdometryEstimation { public: FastVGICPOdometryEstimation(const OdometryEstimationParams& params) : OnlineOdometryEstimation(params), T(Eigen::Isometry3d::Identity()) { vgicp.setCorrespondenceRandomness(params.num_neighbors); vgicp.setResolution(params.voxel_resolution); vgicp.setMaxCorrespondenceDistance(params.max_correspondence_distance); vgicp.setNumThreads(params.num_threads); } Eigen::Isometry3d estimate(const PointCloud::Ptr& points) override { auto points_pcl = pcl::make_shared>(); points_pcl->resize(points->size()); for (size_t i = 0; i < points->size(); i++) { points_pcl->at(i).getVector4fMap() = points->point(i).template cast(); } Stopwatch sw; sw.start(); if (!vgicp.getInputTarget()) { vgicp.setInputTarget(points_pcl); return T; } vgicp.setInputSource(points_pcl); pcl::PointCloud aligned; vgicp.align(aligned); sw.stop(); reg_times.push(sw.msec()); T = T * Eigen::Isometry3d(vgicp.getFinalTransformation().cast()); vgicp.swapSourceAndTarget(); return T; } void report() override { // std::cout << "registration_time_stats=" << reg_times.str() << " [msec/scan] total_throughput=" << total_times.str() << " [msec/scan]" << std::endl; } private: Summarizer reg_times; fast_gicp::FastVGICP vgicp; Eigen::Isometry3d T; }; static auto fast_vgicp_registry = register_odometry("fast_vgicp", [](const OdometryEstimationParams& params) { return std::make_shared(params); }); } // namespace small_gicp #endif