diff --git a/.gitignore b/.gitignore index bbd868a..068e55e 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,3 @@ /.vscode -/.log +/.log/* /build \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt index 71efcad..057ce19 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -44,13 +44,16 @@ catkin_package( add_subdirectory(common) add_subdirectory(src) -add_executable(oh_my_loam main.cc) -target_link_libraries(oh_my_loam +add_executable(main main.cc) +target_link_libraries(main ${catkin_LIBRARIES} ${PCL_LIBRARIES} ${CERES_LIBRARIES} ${G3LOG_LIBRARIES} ${YAML_CPP_LIBRARIES} g3log - OhMyLoam + common + oh_my_loam + feature_points_extractor + visualizer ) diff --git a/common/CMakeLists.txt b/common/CMakeLists.txt index e69de29..fdcd1c9 100644 --- a/common/CMakeLists.txt +++ b/common/CMakeLists.txt @@ -0,0 +1,3 @@ +aux_source_directory(. SRC_FILES) + +add_library(common SHARED ${SRC_FILES}) diff --git a/common/common.h b/common/common.h index 70168ce..f588bcb 100644 --- a/common/common.h +++ b/common/common.h @@ -1,8 +1,9 @@ #pragma once -#include "filter.h" +#include "config.h" #include "log.h" +#include "macros.h" #include "tic_toc.h" #include "types.h" #include "utils.h" -#include "yaml-cpp/yaml.h" \ No newline at end of file +#include "yaml-cpp/yaml.h" diff --git a/common/config.h b/common/config.h index 8157dd5..63e00b5 100644 --- a/common/config.h +++ b/common/config.h @@ -5,9 +5,9 @@ #include #include "log.h" -#include "micros.h" +#include "macros.h" -namespace oh_my_slam { +namespace oh_my_loam { class Config { public: @@ -17,7 +17,7 @@ class Config { } template - const T& Get(const std::string& key) const { + const T Get(const std::string& key) const { AFATAL_IF(!config_) << "No config exists: please call SetConfigFile."; return (*config_)[key].as(); } @@ -30,7 +30,7 @@ class Config { private: std::shared_ptr config_{nullptr}; - DECLARE_SINGLETON(Config); + DECLARE_SINGLETON(Config) }; -} // namespace oh_my_slam \ No newline at end of file +} // namespace oh_my_loam \ No newline at end of file diff --git a/common/filter.h b/common/filter.h deleted file mode 100644 index 27334b7..0000000 --- a/common/filter.h +++ /dev/null @@ -1,44 +0,0 @@ -#pragma once - -#include "utils.h" - -namespace oh_my_loam { - -template -void RemovePointsIf(const pcl::PointCloud& cloud_in, - pcl::PointCloud* const cloud_out, - std::function cond) { - if (&cloud_in != cloud_out) { - cloud_out->header = cloud_in.header; - cloud_out->points.resize(cloud_in.size()); - } - size_t j = 0; - for (size_t i = 0; i < cloud_in.size(); ++i) { - const auto pt = cloud_in.points[i]; - if (cond(pt)) continue; - cloud_out->points[j++] = pt; - } - - cloud_out->points.resize(j); - cloud_out->height = 1; - cloud_out->width = static_cast(j); - cloud_out->is_dense = true; -} - -template -void RemoveNaNPoint(const pcl::PointCloud& cloud_in, - pcl::PointCloud* const cloud_out) { - RemovePointsIf(cloud_in, cloud_out, - [](const PointT& pt) { return !IsFinite(pt); }); -} - -template -void RemoveClosedPoints(const pcl::PointCloud& cloud_in, - pcl::PointCloud* const cloud_out, - double min_dist = 0.1) { - RemovePointsIf(cloud_in, cloud_out, [&](const PointT& pt) { - return DistanceSqure(pt) < min_dist * min_dist; - }); -} - -} // namespace oh_my_loam \ No newline at end of file diff --git a/common/log.cc b/common/log.cc new file mode 100644 index 0000000..2ffcadc --- /dev/null +++ b/common/log.cc @@ -0,0 +1,25 @@ +#include "log.h" + +namespace g3 { +void InitG3Logging(bool log_to_file, const std::string& prefix, + const std::string& path) { + static std::unique_ptr worker; + if (worker != nullptr) return; + worker = std::move(g3::LogWorker::createLogWorker()); + worker->addSink(std::make_unique(), + &g3::CustomSink::StdLogMessage); + if (log_to_file) { + std::ostringstream oss; + oss << path; + if (*path.rbegin() != '/') oss << '/'; + if (prefix.empty()) oss << "g3log"; + oss << prefix << "."; + auto now = std::chrono::system_clock::now(); + oss << g3::localtime_formatted(now, "%Y%m%d-%H%M%S"); + oss << ".log"; + worker->addSink(std::make_unique(oss.str()), + &g3::CustomSink::FileLogMessage); + } + g3::initializeLogging(worker.get()); +} +} \ No newline at end of file diff --git a/common/log.h b/common/log.h index 19bfc1c..1dc762e 100644 --- a/common/log.h +++ b/common/log.h @@ -1,17 +1,23 @@ #pragma once #include +#include #include #include +#include + +const LEVELS ERROR{WARNING.value + 100, "ERROR"}; #define ADEBUG LOG(DEBUG) << "[DEBUG] " #define AINFO LOG(INFO) #define AWARN LOG(WARNING) +#define AERROR LOG(ERROR) #define AFATAL LOG(FATAL) // LOG_IF #define AINFO_IF(cond) LOG_IF(INFO, cond) #define AWARN_IF(cond) LOG_IF(WARNING, cond) +#define AERROR_IF(cond) LOG_IF(ERROR, cond) #define AFATAL_IF(cond) LOG_IF(FATAL, cond) #define ACHECK(cond) CHECK(cond) @@ -19,10 +25,12 @@ namespace g3 { class CustomSink { public: CustomSink() = default; + explicit CustomSink(const std::string& log_file_name) : log_file_name_(log_file_name), log_to_file_(true) { ofs_.reset(new std::ofstream(log_file_name)); } + ~CustomSink() { std::ostringstream oss; oss << "\ng3log " << (log_to_file_ ? "FileSink" : "StdSink") @@ -71,6 +79,9 @@ class CustomSink { if (level.value == DEBUG.value) { return 32; // green } + if (level.value == ERROR.value) { + return 31; // red + } if (g3::internal::wasFatal(level)) { return 31; // red } @@ -78,25 +89,7 @@ class CustomSink { } }; -template -void InitG3Logging(const std::string& prefix, const std::string& path) { - static std::unique_ptr worker; - if (worker != nullptr) return; - worker = std::move(g3::LogWorker::createLogWorker()); - worker->addSink(std::make_unique(), - &g3::CustomSink::StdLogMessage); - if (LogToFile) { - std::ostringstream oss; - oss << path; - if (*path.rbegin() != '/') oss << '/'; - oss << prefix << "."; - auto now = std::chrono::system_clock::now(); - oss << g3::localtime_formatted(now, "%Y%m%d-%H%M%S"); - oss << ".log"; - worker->addSink(std::make_unique(oss.str()), - &g3::CustomSink::FileLogMessage); - } - g3::initializeLogging(worker.get()); -} +void InitG3Logging(bool log_to_file = false, const std::string& prefix = "", + const std::string& path = "./"); } // namespace g3 \ No newline at end of file diff --git a/common/micros.h b/common/macros.h similarity index 82% rename from common/micros.h rename to common/macros.h index d3de164..f1b5bc6 100644 --- a/common/micros.h +++ b/common/macros.h @@ -3,10 +3,14 @@ #include #include +#define DISALLOW_COPY_AND_ASSIGN(classname) \ + classname(const classname &) = delete; \ + classname &operator=(const classname &) = delete; + // adapted form baidu apollo cyber/common/macros.h, it is thread safe #define DECLARE_SINGLETON(classname) \ public: \ - static classname* Instance() { \ + static classname *Instance() { \ static std::unique_ptr instance = nullptr; \ if (!instance) { \ static std::once_flag flag; \ @@ -18,5 +22,4 @@ \ private: \ classname() = default; \ - classname(const classname&) = delete; \ - classname& operator=(const classname&) = delete; \ No newline at end of file + DISALLOW_COPY_AND_ASSIGN(classname) diff --git a/common/utils.cc b/common/utils.cc new file mode 100644 index 0000000..b148574 --- /dev/null +++ b/common/utils.cc @@ -0,0 +1,10 @@ +#include "utils.h" + +namespace oh_my_loam { + +double NormalizeAngle(double ang) { + const double& two_pi = 2 * M_PI; + return ang - two_pi * std::floor((ang + M_PI) / two_pi); +} + +} // oh_my_loam \ No newline at end of file diff --git a/common/utils.h b/common/utils.h index 31696e9..85e0cfd 100644 --- a/common/utils.h +++ b/common/utils.h @@ -20,10 +20,7 @@ inline double IsFinite(const PointT& pt) { } // normalize an angle to [-pi, pi) -inline double NormalizeAngle(double ang) { - const double& two_pi = 2 * M_PI; - return ang - two_pi * std::floor((ang + M_PI) / two_pi); -} +double NormalizeAngle(double ang); template void DrawPointCloud(const pcl::PointCloud& cloud, const Color& color, @@ -46,4 +43,41 @@ void DrawPointCloud(const pcl::PointCloud& cloud, pcl::visualization::PCL_VISUALIZER_POINT_SIZE, pt_size, id); } +template +void RemovePointsIf(const pcl::PointCloud& cloud_in, + pcl::PointCloud* const cloud_out, + std::function cond) { + if (&cloud_in != cloud_out) { + cloud_out->header = cloud_in.header; + cloud_out->points.resize(cloud_in.size()); + } + size_t j = 0; + for (size_t i = 0; i < cloud_in.size(); ++i) { + const auto pt = cloud_in.points[i]; + if (cond(pt)) continue; + cloud_out->points[j++] = pt; + } + + cloud_out->points.resize(j); + cloud_out->height = 1; + cloud_out->width = static_cast(j); + cloud_out->is_dense = true; +} + +template +void RemoveNaNPoint(const pcl::PointCloud& cloud_in, + pcl::PointCloud* const cloud_out) { + RemovePointsIf(cloud_in, cloud_out, + [](const PointT& pt) { return !IsFinite(pt); }); +} + +template +void RemoveClosedPoints(const pcl::PointCloud& cloud_in, + pcl::PointCloud* const cloud_out, + double min_dist = 0.1) { + RemovePointsIf(cloud_in, cloud_out, [&](const PointT& pt) { + return DistanceSqure(pt) < min_dist * min_dist; + }); +} + } // namespace oh_my_loam \ No newline at end of file diff --git a/config/config.yaml b/config/config.yaml deleted file mode 100644 index 26a33f2..0000000 --- a/config/config.yaml +++ /dev/null @@ -1,4 +0,0 @@ -lidar: VPL16 - -feature_points_extractor_config: - min_scan_point_num: 66 \ No newline at end of file diff --git a/configs/config.yaml b/configs/config.yaml new file mode 100644 index 0000000..d609a76 --- /dev/null +++ b/configs/config.yaml @@ -0,0 +1,10 @@ +# global configs +lidar: VPL16 +log_to_file: true +log_path: /home/liufei/catkin_ws/src/oh_my_loam/.log +vis: false + +# configs for feature points extractor +feature_extractor_config: + min_scan_point_num: 66 + vis: true \ No newline at end of file diff --git a/main.cc b/main.cc index 31f9eb4..769ec4e 100644 --- a/main.cc +++ b/main.cc @@ -1,27 +1,38 @@ #include #include #include -#include #include -#include "log.h" -#include "oh_my_loam.h" +#include "common/common.h" +#include "src/oh_my_loam.h" + +using namespace oh_my_loam; void PointCloudHandler(const sensor_msgs::PointCloud2ConstPtr& msg, - oh_my_loam::OhMyLoam* const slam); + OhMyLoam* const slam); int main(int argc, char* argv[]) { - // configurations - YAML::Node config = YAML::LoadFile("./config/config.yaml"); + // config + Config::Instance()->SetConfigFile("configs/config.yaml"); + bool log_to_file = Config::Instance()->Get("log_to_file"); + std::string log_path = Config::Instance()->Get("log_path"); + std::string lidar = Config::Instance()->Get("lidar"); // logging - g3::InitG3Logging("oh_my_loam", ".log"); - AWARN << config["lidar"].as(); + g3::InitG3Logging(log_to_file, "oh_my_loam_" + lidar, log_path); + AINFO << "Lidar: " << lidar; // SLAM system - oh_my_loam::OhMyLoam slam; - slam.Init(config["feature_points_extractor_config"]); + OhMyLoam slam; + if (!slam.Init()) { + AFATAL << "Failed to initilize slam system."; + } + ADEBUG << "DEBUG"; + AINFO << "INFO"; + AWARN << "WARN"; + AERROR << "ERROR"; + AFATAL << "FATAL"; // ros ros::init(argc, argv, "oh_my_loam"); @@ -35,8 +46,8 @@ int main(int argc, char* argv[]) { } void PointCloudHandler(const sensor_msgs::PointCloud2ConstPtr& msg, - oh_my_loam::OhMyLoam* const slam) { - oh_my_loam::PointCloud cloud; + OhMyLoam* const slam) { + PointCloud cloud; pcl::fromROSMsg(*msg, cloud); AINFO << "Point num = " << cloud.size() << ", ts = " << msg->header.stamp.toSec(); diff --git a/oh_my_loam b/oh_my_loam new file mode 100755 index 0000000..b528e08 Binary files /dev/null and b/oh_my_loam differ diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 2b3852c..2fdff23 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -1,7 +1,7 @@ -include_directories( - ${PROJECT_SOURCE_DIR}/common -) +add_subdirectory(feature_points_extractor) +add_subdirectory(visualizer) aux_source_directory(. SRC_FILES) -add_library(OhMyLoam SHARED ${SRC_FILES}) +add_library(oh_my_loam SHARED ${SRC_FILES}) + diff --git a/src/feature_extractor_VLP16.h b/src/feature_extractor_VLP16.h deleted file mode 100644 index ced9b14..0000000 --- a/src/feature_extractor_VLP16.h +++ /dev/null @@ -1,26 +0,0 @@ -#pragma once - -#include "feature_extractor_base.h" - -namespace oh_my_loam { - -// for VLP-16 -class FeatureExtractorVLP16 : public FeaturePointsExtractor { - public: - FeatureExtractorVLP16() { num_scans_ = 16; } - - protected: - int GetScanID(const Point& pt) const override final { - static int i = 0; - double omega = std::atan2(pt.z, Distance(pt)) * 180 * M_1_PI + 15.0; - if (i++ < 10) { - AWARN << "OMEGA: " << std::atan2(pt.z, Distance(pt)) * 180 * M_1_PI + 15.0 - << " id = " << static_cast(std::round(omega / 2.0) + 0.01) - << " z = " << pt.z << " " - << " d = " << Distance(pt) << std::endl; - } - return static_cast(std::round(omega / 2.0) + 1.e-5); - } -}; - -} // namespace oh_my_loam \ No newline at end of file diff --git a/src/feature_points_extractor/CMakeLists.txt b/src/feature_points_extractor/CMakeLists.txt new file mode 100644 index 0000000..568211a --- /dev/null +++ b/src/feature_points_extractor/CMakeLists.txt @@ -0,0 +1,3 @@ +aux_source_directory(. SRC_FILES) + +add_library(feature_points_extractor SHARED ${SRC_FILES}) diff --git a/src/feature_extractor_base.cc b/src/feature_points_extractor/base_feature_points_extractor.cc similarity index 71% rename from src/feature_extractor_base.cc rename to src/feature_points_extractor/base_feature_points_extractor.cc index 2462329..4918f16 100644 --- a/src/feature_extractor_base.cc +++ b/src/feature_points_extractor/base_feature_points_extractor.cc @@ -1,9 +1,7 @@ -#include "feature_extractor_base.h" +#include "base_feature_points_extractor.h" #include -#include "filter.h" - namespace oh_my_loam { namespace { @@ -15,11 +13,14 @@ const int kMinPtsNum = 100; bool FeaturePointsExtractor::Init(const YAML::Node& config) { config_ = config; + is_vis_ = Config::Instance()->Get("vis") && config_["vis"].as(); + AINFO << "Feature points visualization: " << (is_vis_ ? "ON" : "OFF"); + if (is_vis_) visualizer_.reset(new FeaturePointsVisualizer); return true; } void FeaturePointsExtractor::Extract(const PointCloud& cloud_in, - FeaturePoints* const feature) const { + FeaturePoints* const feature) { PointCloudPtr cloud(new PointCloud); AINFO << "BEFORE REMOVE, num = " << cloud_in.size(); RemoveNaNPoint(cloud_in, cloud.get()); @@ -42,26 +43,27 @@ void FeaturePointsExtractor::Extract(const PointCloud& cloud_in, } AWARN << oss.str(); for (const auto& scan : scans) { - feature->feature_pts += scan; + *feature->feature_pts += scan; for (const auto& pt : scan.points) { switch (pt.Type()) { case PointType::FLAT: - feature->flat_surf_pts.points.emplace_back(pt); + feature->flat_surf_pts->points.emplace_back(pt); break; case PointType::LESS_FLAT: - feature->less_flat_surf_pts.points.emplace_back(pt); + feature->less_flat_surf_pts->points.emplace_back(pt); break; case PointType::LESS_SHARP: - feature->less_sharp_corner_pts.points.emplace_back(pt); + feature->less_sharp_corner_pts->points.emplace_back(pt); break; case PointType::SHARP: - feature->sharp_corner_pts.points.emplace_back(pt); + feature->sharp_corner_pts->points.emplace_back(pt); break; default: break; } } } + if (is_vis_) Visualize(cloud_in, *feature); } void FeaturePointsExtractor::SplitScan( @@ -104,13 +106,23 @@ void FeaturePointsExtractor::ComputePointCurvature( } void FeaturePointsExtractor::AssignPointType(IPointCloud* const scan) const { - int pt_num = scan->size(); - int pt_num_seg = (pt_num - 1) / kScanSegNum + 1; - std::vector picked(pt_num, false); - for (int i = 0; i < kScanSegNum; ++i) { - int begin = i * pt_num_seg; - int end = std::max((i + 1) * pt_num_seg, pt_num); - } + // int pt_num = scan->size(); + // int pt_num_seg = (pt_num - 1) / kScanSegNum + 1; + // std::vector picked(pt_num, false); + // for (int i = 0; i < kScanSegNum; ++i) { + // int begin = i * pt_num_seg; + // int end = std::max((i + 1) * pt_num_seg, pt_num); + // } +} + +void FeaturePointsExtractor::Visualize(const PointCloud& cloud, + const FeaturePoints& feature_pts, + double timestamp) { + std::shared_ptr frame(new FeaturePointsVisFrame); + frame->timestamp = timestamp; + frame->cloud = cloud.makeShared(); + frame->feature_pts = feature_pts; + visualizer_->Render(frame); } } // namespace oh_my_loam diff --git a/src/feature_extractor_base.h b/src/feature_points_extractor/base_feature_points_extractor.h similarity index 61% rename from src/feature_extractor_base.h rename to src/feature_points_extractor/base_feature_points_extractor.h index af90eef..2dfd94c 100644 --- a/src/feature_extractor_base.h +++ b/src/feature_points_extractor/base_feature_points_extractor.h @@ -1,32 +1,26 @@ #pragma once -#include "common.h" +#include "feature_points.h" +#include "visualizer/feature_points_visualizer.h" namespace oh_my_loam { -struct FeaturePoints { - IPointCloud feature_pts; // all feature points - IPointCloud sharp_corner_pts; - IPointCloud less_sharp_corner_pts; - IPointCloud flat_surf_pts; - IPointCloud less_flat_surf_pts; -}; - class FeaturePointsExtractor { public: FeaturePointsExtractor() = default; virtual ~FeaturePointsExtractor() = default; - FeaturePointsExtractor(const FeaturePointsExtractor&) = delete; - FeaturePointsExtractor& operator=(const FeaturePointsExtractor&) = delete; bool Init(const YAML::Node& config); - void Extract(const PointCloud& cloud_in, FeaturePoints* const feature) const; + void Extract(const PointCloud& cloud_in, FeaturePoints* const feature); int num_scans() const { return num_scans_; } protected: virtual int GetScanID(const Point& pt) const = 0; + void Visualize(const PointCloud& cloud, const FeaturePoints& feature_pts, + double timestamp = std::nan("")); + void SplitScan(const PointCloud& cloud, std::vector* const scans) const; @@ -35,7 +29,14 @@ class FeaturePointsExtractor { void AssignPointType(IPointCloud* const scan) const; int num_scans_ = 0; + + bool is_vis_ = false; + + std::unique_ptr visualizer_{nullptr}; + YAML::Node config_; + + DISALLOW_COPY_AND_ASSIGN(FeaturePointsExtractor); }; } // namespace oh_my_loam \ No newline at end of file diff --git a/src/feature_points_extractor/feature_points.h b/src/feature_points_extractor/feature_points.h new file mode 100644 index 0000000..ca733a4 --- /dev/null +++ b/src/feature_points_extractor/feature_points.h @@ -0,0 +1,23 @@ +#pragma once + +#include "common.h" + +namespace oh_my_loam { + +struct FeaturePoints { + IPointCloudPtr feature_pts; // all feature points + IPointCloudPtr sharp_corner_pts; + IPointCloudPtr less_sharp_corner_pts; + IPointCloudPtr flat_surf_pts; + IPointCloudPtr less_flat_surf_pts; + + FeaturePoints() { + feature_pts.reset(new IPointCloud); + sharp_corner_pts.reset(new IPointCloud); + less_sharp_corner_pts.reset(new IPointCloud); + flat_surf_pts.reset(new IPointCloud); + less_flat_surf_pts.reset(new IPointCloud); + } +}; + +} // namespace oh_my_loam diff --git a/src/feature_points_extractor/feature_points_extractor_VLP16.cc b/src/feature_points_extractor/feature_points_extractor_VLP16.cc new file mode 100644 index 0000000..2b85322 --- /dev/null +++ b/src/feature_points_extractor/feature_points_extractor_VLP16.cc @@ -0,0 +1,17 @@ +#include "feature_points_extractor_VLP16.h" + +namespace oh_my_loam { + +int FeaturePointsExtractorVLP16::GetScanID(const Point& pt) const { + static int i = 0; + double omega = std::atan2(pt.z, Distance(pt)) * 180 * M_1_PI + 15.0; + if (i++ < 10) { + AWARN << "OMEGA: " << std::atan2(pt.z, Distance(pt)) * 180 * M_1_PI + 15.0 + << " id = " << static_cast(std::round(omega / 2.0) + 0.01) + << " z = " << pt.z << " " + << " d = " << Distance(pt) << std::endl; + } + return static_cast(std::round(omega / 2.0) + 1.e-5); +}; + +} // namespace oh_my_loam \ No newline at end of file diff --git a/src/feature_points_extractor/feature_points_extractor_VLP16.h b/src/feature_points_extractor/feature_points_extractor_VLP16.h new file mode 100644 index 0000000..59ad972 --- /dev/null +++ b/src/feature_points_extractor/feature_points_extractor_VLP16.h @@ -0,0 +1,16 @@ +#pragma once + +#include "base_feature_points_extractor.h" + +namespace oh_my_loam { + +// for VLP-16 +class FeaturePointsExtractorVLP16 : public FeaturePointsExtractor { + public: + FeaturePointsExtractorVLP16() { num_scans_ = 16; } + + private: + int GetScanID(const Point& pt) const override; +}; + +} // namespace oh_my_loam \ No newline at end of file diff --git a/src/oh_my_loam.cc b/src/oh_my_loam.cc index 4569347..5333f06 100644 --- a/src/oh_my_loam.cc +++ b/src/oh_my_loam.cc @@ -1,31 +1,21 @@ #include "oh_my_loam.h" +#include "feature_points_extractor/feature_points_extractor_VLP16.h" namespace oh_my_loam { -bool OhMyLoam::Init(const YAML::Node& config) { - is_vis_ = true; - config_ = config; - feature_extractor_.reset(new FeatureExtractorVLP16); - if (is_vis_) { - visualizer_.reset(new FeaturePointsVisualizer); +bool OhMyLoam::Init() { + YAML::Node config = Config::Instance()->config(); + feature_extractor_.reset(new FeaturePointsExtractorVLP16); + if (!feature_extractor_->Init(config["feature_extractor_config"])) { + AERROR << "Failed to initialize feature points extractor"; + return false; } return true; } void OhMyLoam::Run(const PointCloud& cloud, double timestamp) { - std::shared_ptr feature_pts(new FeaturePoints); - feature_extractor_->Extract(cloud, feature_pts.get()); - if (is_vis_) Visualize(cloud, feature_pts, timestamp); -} - -void OhMyLoam::Visualize( - const PointCloud& cloud, - const std::shared_ptr& feature_pts, double timestamp) { - std::shared_ptr frame(new FeaturePointsVisFrame); - frame->timestamp = timestamp; - frame->cloud = cloud.makeShared(); - frame->feature_pts = feature_pts; - visualizer_->Render(frame); + FeaturePoints feature_pts; + feature_extractor_->Extract(cloud, &feature_pts); } } // namespace oh_my_loam \ No newline at end of file diff --git a/src/oh_my_loam.h b/src/oh_my_loam.h index e31af52..f0f76fc 100644 --- a/src/oh_my_loam.h +++ b/src/oh_my_loam.h @@ -3,31 +3,22 @@ #include #include "common.h" -#include "feature_extractor_VLP16.h" -#include "visualizer_feature_points.h" +#include "feature_points_extractor/base_feature_points_extractor.h" namespace oh_my_loam { class OhMyLoam { public: OhMyLoam() = default; - ~OhMyLoam() = default; - OhMyLoam(const OhMyLoam&) = delete; - OhMyLoam& operator=(const OhMyLoam&) = delete; - bool Init(const YAML::Node& config); + bool Init(); void Run(const PointCloud& cloud, double timestamp); private: - void Visualize(const PointCloud& cloud, - const std::shared_ptr& feature_pts, - double timestamp = std::nanf("")); + std::unique_ptr feature_extractor_{nullptr}; - bool is_vis_ = false; - std::unique_ptr feature_extractor_ = nullptr; - std::unique_ptr visualizer_ = nullptr; - YAML::Node config_; + DISALLOW_COPY_AND_ASSIGN(OhMyLoam) }; } // namespace oh_my_loam \ No newline at end of file diff --git a/src/visualizer/CMakeLists.txt b/src/visualizer/CMakeLists.txt new file mode 100644 index 0000000..f0e963b --- /dev/null +++ b/src/visualizer/CMakeLists.txt @@ -0,0 +1,3 @@ +aux_source_directory(. SRC_FILES) + +add_library(visualizer SHARED ${SRC_FILES}) diff --git a/src/visualizer_base.h b/src/visualizer/base_visualizer.h similarity index 100% rename from src/visualizer_base.h rename to src/visualizer/base_visualizer.h diff --git a/src/visualizer/feature_points_visualizer.cc b/src/visualizer/feature_points_visualizer.cc new file mode 100644 index 0000000..30ba9a6 --- /dev/null +++ b/src/visualizer/feature_points_visualizer.cc @@ -0,0 +1,43 @@ +#include "feature_points_visualizer.h" + +namespace oh_my_loam { + +void FeaturePointsVisualizer::Draw() { + auto frame = GetCurrentFrame(); + { // add raw point cloud + std::string id = "raw point cloud"; + DrawPointCloud(*frame.cloud, WHITE, id, viewer_.get()); + rendered_cloud_ids_.push_back(id); + } + { // add all feature_pts + std::string id = "feature_pts"; + DrawPointCloud(*frame.feature_pts.feature_pts, "curvature", id, + viewer_.get()); + rendered_cloud_ids_.push_back(id); + } + { // add flat_surf_pts + std::string id = "flat_surf_pts"; + DrawPointCloud(*frame.feature_pts.flat_surf_pts, CYAN, id, viewer_.get()); + rendered_cloud_ids_.push_back(id); + } + { // add less_flat_surf_pts + std::string id = "less_flat_surf_pts"; + DrawPointCloud(*frame.feature_pts.less_flat_surf_pts, GREEN, id, + viewer_.get()); + rendered_cloud_ids_.push_back(id); + } + { // add less_sharp_corner_pts + std::string id = "less_sharp_corner_pts"; + DrawPointCloud(*frame.feature_pts.less_sharp_corner_pts, ORANGE, id, + viewer_.get()); + rendered_cloud_ids_.push_back(id); + } + { // add sharp_corner_pts + std::string id = "sharp_corner_pts"; + DrawPointCloud(*frame.feature_pts.sharp_corner_pts, ORANGE, id, + viewer_.get()); + rendered_cloud_ids_.push_back(id); + } +}; + +} // namespace oh_my_loam diff --git a/src/visualizer/feature_points_visualizer.h b/src/visualizer/feature_points_visualizer.h new file mode 100644 index 0000000..59f2039 --- /dev/null +++ b/src/visualizer/feature_points_visualizer.h @@ -0,0 +1,23 @@ +#pragma once + +#include "base_visualizer.h" +#include "feature_points_extractor/feature_points.h" + +namespace oh_my_loam { + +struct FeaturePointsVisFrame : public VisFrame { + FeaturePoints feature_pts; +}; + +class FeaturePointsVisualizer : public Visualizer { + public: + explicit FeaturePointsVisualizer( + const std::string &name = "FeaturePointsVisualizer", + size_t max_history_size = 10) + : Visualizer(name, max_history_size) {} + + private: + void Draw() override; +}; + +} // namespace oh_my_loam diff --git a/src/visualizer_feature_points.h b/src/visualizer_feature_points.h deleted file mode 100644 index 3fa361f..0000000 --- a/src/visualizer_feature_points.h +++ /dev/null @@ -1,59 +0,0 @@ -#pragma once - -#include "feature_extractor_base.h" -#include "visualizer_base.h" - -namespace oh_my_loam { - -struct FeaturePointsVisFrame : public VisFrame { - std::shared_ptr feature_pts; -}; - -class FeaturePointsVisualizer : public Visualizer { - public: - explicit FeaturePointsVisualizer( - const std::string &name = "FeaturePointsVisFrame", - size_t max_history_size = 10) - : Visualizer(name, max_history_size) {} - - protected: - void Draw() override final { - auto frame = GetCurrentFrame(); - { // add raw point cloud - std::string id = "raw point cloud"; - DrawPointCloud(*frame.cloud, WHITE, id, viewer_.get()); - rendered_cloud_ids_.push_back(id); - } - { // add all feature_pts - std::string id = "feature_pts"; - DrawPointCloud(frame.feature_pts->feature_pts, "curvature", id, - viewer_.get()); - rendered_cloud_ids_.push_back(id); - } - { // add flat_surf_pts - std::string id = "flat_surf_pts"; - DrawPointCloud(frame.feature_pts->flat_surf_pts, CYAN, id, viewer_.get()); - rendered_cloud_ids_.push_back(id); - } - { // add less_flat_surf_pts - std::string id = "less_flat_surf_pts"; - DrawPointCloud(frame.feature_pts->less_flat_surf_pts, GREEN, id, - viewer_.get()); - rendered_cloud_ids_.push_back(id); - } - { // add less_sharp_corner_pts - std::string id = "less_sharp_corner_pts"; - DrawPointCloud(frame.feature_pts->less_sharp_corner_pts, ORANGE, id, - viewer_.get()); - rendered_cloud_ids_.push_back(id); - } - { // add sharp_corner_pts - std::string id = "sharp_corner_pts"; - DrawPointCloud(frame.feature_pts->sharp_corner_pts, ORANGE, id, - viewer_.get()); - rendered_cloud_ids_.push_back(id); - } - } -}; - -} // namespace oh_my_loam