oh_my_loam/main.cc

50 lines
1.4 KiB
C++
Raw Normal View History

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-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-16 18:08:31 +08:00
#include "common/common.h"
#include "src/oh_my_loam.h"
using namespace oh_my_loam;
2020-10-12 21:09:32 +08:00
void PointCloudHandler(const sensor_msgs::PointCloud2ConstPtr& msg,
2020-10-16 18:08:31 +08:00
OhMyLoam* const slam);
2020-10-12 21:09:32 +08:00
int main(int argc, char* argv[]) {
2020-10-16 18:08:31 +08:00
// config
Config::Instance()->SetConfigFile("configs/config.yaml");
bool log_to_file = Config::Instance()->Get<bool>("log_to_file");
std::string log_path = Config::Instance()->Get<std::string>("log_path");
std::string lidar = Config::Instance()->Get<std::string>("lidar");
2020-10-15 21:14:01 +08:00
// logging
2020-10-16 18:08:31 +08:00
g3::InitG3Logging(log_to_file, "oh_my_loam_" + lidar, log_path);
AINFO << "Lidar: " << lidar;
2020-10-15 21:14:01 +08:00
2020-10-14 01:10:50 +08:00
// SLAM system
2020-10-16 18:08:31 +08:00
OhMyLoam slam;
if (!slam.Init()) {
AFATAL << "Failed to initilize slam system.";
}
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,
2020-10-16 18:08:31 +08:00
OhMyLoam* const slam) {
PointCloud cloud;
2020-10-12 21:09:32 +08:00
pcl::fromROSMsg(*msg, cloud);
2020-10-16 20:49:26 +08:00
ADEBUG << "Point num = " << cloud.size()
<< ", ts = " << LOG_TIMESTAMP(msg->header.stamp.toSec());
2020-10-12 21:09:32 +08:00
slam->Run(cloud, 0.0);
}