oh_my_loam/examples/main_rosbag.cc

58 lines
1.8 KiB
C++
Raw Normal View History

2020-11-20 20:07:41 +08:00
#include <pcl/io/pcd_io.h>
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
2021-01-05 14:33:42 +08:00
#include <filesystem>
2020-10-12 21:09:32 +08:00
#include <functional>
2020-10-13 01:07:59 +08:00
2021-01-05 14:33:42 +08:00
#include "common/common.h"
#include "oh_my_loam/oh_my_loam.h"
2020-10-16 18:08:31 +08:00
2021-01-05 14:33:42 +08:00
using namespace common;
2020-10-16 18:08:31 +08:00
using namespace oh_my_loam;
2020-10-12 21:09:32 +08:00
2021-01-22 16:33:55 +08:00
void PointCloudHandler(const sensor_msgs::PointCloud2ConstPtr &msg,
OhMyLoam *const slam);
2020-10-12 21:09:32 +08:00
2021-01-22 16:33:55 +08:00
int main(int argc, char *argv[]) {
if (argc != 2) {
std::cerr << "\033[1m\033[31mConfiguration file should be specified!\033[m"
<< std::endl;
return -1;
}
2020-10-16 18:08:31 +08:00
// config
2021-01-14 00:34:13 +08:00
YAMLConfig::Instance()->Init(argv[1]);
bool is_log_to_file = YAMLConfig::Instance()->Get<bool>("log_to_file");
2021-01-05 14:33:42 +08:00
std::string log_path = YAMLConfig::Instance()->Get<std::string>("log_path");
std::string lidar = YAMLConfig::Instance()->Get<std::string>("lidar");
2020-10-15 21:14:01 +08:00
// logging
InitG3Logging(is_log_to_file, "oh_my_loam_" + lidar, log_path);
2020-10-18 01:14:43 +08:00
AUSER << "LOAM start..., lidar = " << lidar;
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-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;
}
2021-01-22 16:33:55 +08:00
void PointCloudHandler(const sensor_msgs::PointCloud2ConstPtr &msg,
OhMyLoam *const slam) {
2021-01-05 14:33:42 +08:00
PointCloudPtr cloud(new PointCloud);
pcl::fromROSMsg(*msg, *cloud);
2020-11-20 20:07:41 +08:00
double timestamp = msg->header.stamp.toSec();
2021-01-25 21:00:10 +08:00
static size_t frame_id = 0;
AINFO << "Ohmyloam: frame_id = " << ++frame_id
<< ", timestamp = " << FMT_TIMESTAMP(timestamp)
<< ", point_number = " << cloud->size();
2021-01-05 14:33:42 +08:00
slam->Run(timestamp, cloud);
2020-10-12 21:09:32 +08:00
}