2020-10-12 21:09:32 +08:00
|
|
|
#include <pcl_conversions/pcl_conversions.h>
|
|
|
|
#include <ros/ros.h>
|
|
|
|
#include <sensor_msgs/PointCloud2.h>
|
2020-10-14 01:10:50 +08:00
|
|
|
#include <yaml-cpp/yaml.h>
|
2020-10-13 01:07:59 +08:00
|
|
|
|
2020-10-12 21:09:32 +08:00
|
|
|
#include <functional>
|
2020-10-13 01:07:59 +08:00
|
|
|
|
2020-10-13 21:31:01 +08:00
|
|
|
#include "log.h"
|
2020-10-12 21:09:32 +08:00
|
|
|
#include "oh_my_loam.h"
|
|
|
|
|
|
|
|
void PointCloudHandler(const sensor_msgs::PointCloud2ConstPtr& msg,
|
|
|
|
oh_my_loam::OhMyLoam* const slam);
|
|
|
|
|
|
|
|
int main(int argc, char* argv[]) {
|
2020-10-14 01:10:50 +08:00
|
|
|
// configurations
|
|
|
|
YAML::Node config = YAML::LoadFile("./config/config.yaml");
|
2020-10-15 21:14:01 +08:00
|
|
|
|
|
|
|
// logging
|
|
|
|
g3::InitG3Logging<true>("oh_my_loam", ".log");
|
2020-10-14 01:10:50 +08:00
|
|
|
AWARN << config["lidar"].as<std::string>();
|
2020-10-15 21:14:01 +08:00
|
|
|
|
2020-10-14 01:10:50 +08:00
|
|
|
// SLAM system
|
2020-10-12 21:09:32 +08:00
|
|
|
oh_my_loam::OhMyLoam slam;
|
2020-10-15 21:14:01 +08:00
|
|
|
slam.Init(config["feature_points_extractor_config"]);
|
2020-10-12 21:09:32 +08:00
|
|
|
|
2020-10-14 01:10:50 +08:00
|
|
|
// ros
|
2020-10-12 21:09:32 +08:00
|
|
|
ros::init(argc, argv, "oh_my_loam");
|
|
|
|
ros::NodeHandle nh;
|
|
|
|
ros::Subscriber sub_point_cloud = nh.subscribe<sensor_msgs::PointCloud2>(
|
|
|
|
"/velodyne_points", 100,
|
|
|
|
std::bind(PointCloudHandler, std::placeholders::_1, &slam));
|
|
|
|
ros::spin();
|
|
|
|
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
void PointCloudHandler(const sensor_msgs::PointCloud2ConstPtr& msg,
|
|
|
|
oh_my_loam::OhMyLoam* const slam) {
|
|
|
|
oh_my_loam::PointCloud cloud;
|
|
|
|
pcl::fromROSMsg(*msg, cloud);
|
2020-10-13 21:31:01 +08:00
|
|
|
AINFO << "Point num = " << cloud.size()
|
|
|
|
<< ", ts = " << msg->header.stamp.toSec();
|
2020-10-12 21:09:32 +08:00
|
|
|
slam->Run(cloud, 0.0);
|
|
|
|
}
|