yaml-cpp: OK

main
feixyz10 2020-10-14 01:10:50 +08:00 committed by feixyz
parent 7f9e3f97a6
commit f901e8424c
6 changed files with 29 additions and 9 deletions

1
.gitignore vendored
View File

@ -1,4 +1,3 @@
/.vscode
/.log
/lib
/build

View File

@ -6,8 +6,9 @@ set(CMAKE_CXX_FLAGS "-std=c++17 -lpthread")
set(CMAKE_CXX_FLAGS_RELEASE "-O3 -Wall -g")
find_package(Ceres REQUIRED)
find_package(PCL REQUIRED)
find_package(PCL QUIET)
find_package(g3log REQUIRED)
find_package(yaml-cpp REQUIRED)
find_package(catkin REQUIRED COMPONENTS
geometry_msgs
@ -22,11 +23,14 @@ find_package(catkin REQUIRED COMPONENTS
tf
)
include_directories(
include_directories(SYSTEM
${catkin_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
${CERES_INCLUDE_DIRS}
${G3LOG_INCLUDE_DIRS}
)
include_directories(
src
common
)
@ -37,7 +41,6 @@ catkin_package(
INCLUDE_DIRS src common
)
add_subdirectory(common)
add_subdirectory(src)
@ -46,7 +49,8 @@ target_link_libraries(oh_my_loam
${catkin_LIBRARIES}
${PCL_LIBRARIES}
${CERES_LIBRARIES}
${G3LOG_INCLUDE_DIRS}
${G3LOG_LIBRARIES}
${YAML_CPP_LIBRARIES}
g3log
OhMyLoam
)

6
config/config.yaml Normal file
View File

@ -0,0 +1,6 @@
%YAML:1.0
lidar: VPL16
feature_points_extractor_config:
min_point_num: 10

11
main.cc
View File

@ -1,6 +1,7 @@
#include <pcl_conversions/pcl_conversions.h>
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <yaml-cpp/yaml.h>
#include <functional>
@ -11,11 +12,17 @@ void PointCloudHandler(const sensor_msgs::PointCloud2ConstPtr& msg,
oh_my_loam::OhMyLoam* const slam);
int main(int argc, char* argv[]) {
g3::InitG3Logging<true>("oh_my_loam", ".log");
// logging
g3::InitG3Logging<false>("oh_my_loam", ".log");
// configurations
YAML::Node config = YAML::LoadFile("./config/config.yaml");
AWARN << config["lidar"].as<std::string>();
// SLAM system
oh_my_loam::OhMyLoam slam;
slam.Init();
slam.Init(config);
// ros
ros::init(argc, argv, "oh_my_loam");
ros::NodeHandle nh;
ros::Subscriber sub_point_cloud = nh.subscribe<sensor_msgs::PointCloud2>(

View File

@ -2,8 +2,9 @@
namespace oh_my_loam {
bool OhMyLoam::Init() {
bool OhMyLoam::Init(const YAML::Node& config) {
is_vis_ = true;
config_ = config;
feature_extractor_.reset(new FeatureExtractorVLP16);
if (is_vis_) {
visualizer_.reset(new FeaturePointsVisualizer);

View File

@ -1,5 +1,7 @@
#pragma once
#include <yaml-cpp/yaml.h>
#include "common.h"
#include "feature_extractor_VLP16.h"
#include "visualizer_feature_points.h"
@ -13,7 +15,7 @@ class OhMyLoam {
OhMyLoam(const OhMyLoam&) = delete;
OhMyLoam& operator=(const OhMyLoam&) = delete;
bool Init();
bool Init(const YAML::Node& config);
void Run(const PointCloud& cloud, double timestamp);
@ -25,6 +27,7 @@ class OhMyLoam {
bool is_vis_ = false;
std::unique_ptr<FeaturePointsExtractor> feature_extractor_ = nullptr;
std::unique_ptr<FeaturePointsVisualizer> visualizer_ = nullptr;
YAML::Node config_;
};
} // namespace oh_my_loam