-
Notifications
You must be signed in to change notification settings - Fork 14
/
extract_pcdFbag_tf.cpp
224 lines (199 loc) · 7.67 KB
/
extract_pcdFbag_tf.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
/**
* Copyright (C) 2022-now, RPL, KTH Royal Institute of Technology
* MIT License
* Author: Kin ZHANG (https://kin-zhang.github.io/)
* Date: 2023-04-26 14:33
* Description: extract pcd file and also insert the pose in PCD VIEWPOINT Field
* So that we don't need pose.csv file etc.
*
* Input: ROS bag file, LiDAR topic name, Output: PCD files!
*/
#include <glog/logging.h>
#include <nav_msgs/Odometry.h>
#include <pcl/common/transforms.h>
#include <pcl/io/pcd_io.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/filters/filter.h>
#include <ros/ros.h>
#include <rosbag/bag.h>
#include <rosbag/view.h>
#include <sensor_msgs/PointCloud2.h>
#include <tf2_eigen/tf2_eigen.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
#include <sensor_msgs/PointCloud2.h>
#include <filesystem>
#include <fstream>
#include <iostream>
#include <string>
#include "timer.h"
using PCDPoint = pcl::PointXYZI;
// using PCDPoint = pcl::PointXYZRGB;
int main(int argc, char** argv) {
// Initialize the ROS system
ros::init(argc, argv, "bag2pcd_tf");
// Create a NodeHandle object
ros::NodeHandle nh;
google::InitGoogleLogging(argv[0]);
google::InstallFailureSignalHandler();
FLAGS_colorlogtostderr = true;
google::SetStderrLogging(google::INFO);
// if no argv, return 0
if(argc < 5){
LOG(ERROR) << "./bag2pcd_tf <rosbag_path> <save_pcd_folder> <pc2_topic_name> <world_or_map_frame_id>";
return 1;
}
std::string rosbag_path = argv[1];
std::string save_pcd_folder = argv[2];
std::string pc2_topic = argv[3];
std::string world_frame_id = argv[4];
int save_map_pcd = 0;
if (argc > 5) {
save_map_pcd = std::stoi(argv[5]);
if (save_map_pcd == 1) {
LOG(INFO) << "We will save map pcd file";
}
}
// check if the file exists
if (!std::filesystem::exists(rosbag_path)) {
LOG(ERROR) << "File does not exist: " << rosbag_path;
return 1;
}
// create the folder if not exists
if (!std::filesystem::exists(save_pcd_folder)) {
std::filesystem::create_directory(save_pcd_folder);
LOG(INFO) << "Create folder: " << save_pcd_folder;
}
if(!std::filesystem::exists(save_pcd_folder+"/pcd"))
std::filesystem::create_directory(save_pcd_folder+"/pcd");
LOG(INFO) << "we will read bag through: " << rosbag_path;
rosbag::Bag bag;
bag.open(rosbag_path, rosbag::bagmode::Read);
std::vector<std::string> topics = {pc2_topic, "/tf", "/tf_static"};
LOG(INFO) << "We will read pc2 topic: " << ANSI_BOLD << pc2_topic
<< ANSI_RESET << " and pose info from tf topic directly";
TIC;
// Create a view for the bag with the desired topic
rosbag::View view(bag, rosbag::TopicQuery(topics));
pcl::PointCloud<PCDPoint>::Ptr pcl_cloud(
new pcl::PointCloud<PCDPoint>());
pcl::PointCloud<PCDPoint>::Ptr pcl_cloud_map(
new pcl::PointCloud<PCDPoint>());
std::vector<float> pose(7, 0.0);
int count = 0;
ros::Duration cache_length(3600.0);// 3600s = 1h HARD CODE!
tf2_ros::Buffer tf_buffer(cache_length);
tf2_ros::TransformListener tf_listener(tf_buffer);
geometry_msgs::TransformStamped static_transform;
bool static_frame_set = false;
for (const rosbag::MessageInstance& m : view) {
if (m.isType<tf2_msgs::TFMessage>()) {
tf2_msgs::TFMessage::ConstPtr tf_msg =
m.instantiate<tf2_msgs::TFMessage>();
if (tf_msg != nullptr) {
for (const auto& transform : tf_msg->transforms) {
try {
// FIXME: set velodyne frame and livox frame HARD CODE! HERE
if(transform.child_frame_id == "livox_frame"){
static_transform = transform;
static_frame_set = true;
continue;
}
if(transform.header.frame_id == world_frame_id && static_frame_set){
static_transform.header.stamp = transform.header.stamp;
tf_buffer.setTransform(static_transform, "static_transform");
}
tf_buffer.setTransform(transform, "bag_tf");
} catch (tf2::TransformException& ex) {
ROS_WARN("%s", ex.what());
}
}
}
}
}
bool pc_rec = false;
for(const rosbag::MessageInstance& m : view)
{
if(m.getTopic() == pc2_topic)
{
sensor_msgs::PointCloud2::ConstPtr pc2 =
m.instantiate<sensor_msgs::PointCloud2>();
if(pc2 != nullptr)
{
pcl::fromROSMsg(*pc2, *pcl_cloud);
try{
std::string frame_id = pc2->header.frame_id;
// make sure no '/' in the frame_id
frame_id.erase(std::remove(frame_id.begin(), frame_id.end(), '/'), frame_id.end());
geometry_msgs::TransformStamped transform = tf_buffer.lookupTransform(world_frame_id, frame_id, pc2->header.stamp);
// Position
pose[0] = transform.transform.translation.x;
pose[1] = transform.transform.translation.y;
pose[2] = transform.transform.translation.z;
// Orientation
pose[3] = transform.transform.rotation.x;
pose[4] = transform.transform.rotation.y;
pose[5] = transform.transform.rotation.z;
pose[6] = transform.transform.rotation.w;
pc_rec = true;
}
catch (tf2::TransformException& ex) {
ROS_WARN("%s, We will skip this frame", ex.what());
continue;
}
}
}
if(pc_rec)
{
// transform the pcd
Eigen::Matrix4f transform = Eigen::Matrix4f::Identity();
transform.block<3, 3>(0, 0) = Eigen::Quaternionf(pose[6], pose[3],pose[4], pose[5]).toRotationMatrix();
transform.block<3, 1>(0, 3) = Eigen::Vector3f(pose[0], pose[1], pose[2]);
// remove the points that are too close to the origin, specially for some dataset add 0,0,0 pts in pointcloud
pcl::PointCloud<PCDPoint>::Ptr pcl_cloud_tmp(new pcl::PointCloud<PCDPoint>());
double min_dis = 0.01;
for(auto p : pcl_cloud->points)
{
if(abs(p.x)<min_dis && abs(p.y)<min_dis && abs(p.z)<min_dis){
// LOG_EVERY_N(INFO, 100) << "We will remove this point: " << p.x << " " << p.y << " " << p.z;
continue;
}
pcl_cloud_tmp->push_back(p);
}
// remove NaN points
std::vector<int> indices;
pcl::removeNaNFromPointCloud(*pcl_cloud_tmp, *pcl_cloud_tmp, indices);
// Remember we transform! The Point Cloud!!
pcl::transformPointCloud(*pcl_cloud_tmp, *pcl_cloud, transform);
if(save_map_pcd == 1)
pcl_cloud_map->insert(pcl_cloud_map->end(), pcl_cloud->begin(),
pcl_cloud->end());
// set the viewpoint -> CHECK PCD VIEWPOINT FIELD
pcl_cloud->sensor_origin_ = Eigen::Vector4f(pose[0], pose[1], pose[2], 0.0);
pcl_cloud->sensor_orientation_ = Eigen::Quaternionf(pose[6], pose[3], pose[4], pose[5]); // w, x, y, z
// save the pcd
std::ostringstream tmp_filename;
tmp_filename << save_pcd_folder << "/pcd/" << std::setfill('0') <<
std::setw(6) << count << ".pcd"; std::string pcd_file =
tmp_filename.str(); pcl::io::savePCDFileBinary(pcd_file, *pcl_cloud);
pc_rec = false;
count++;
}
}
TOC("Extract pcd files from rosbag", true);
if(save_map_pcd == 1)
{
std::ostringstream tmp_filename;
tmp_filename << save_pcd_folder << "/" << "raw_map.pcd";
std::string pcd_file = tmp_filename.str();
LOG(INFO) << pcd_file;
pcl::io::savePCDFileBinary(pcd_file, *pcl_cloud_map);
LOG(INFO) << "Save raw map pcd file: " << pcd_file << " with " <<
pcl_cloud_map->size() << " points";
}
LOG(INFO) << "Total pcd files: " << count << ANSI_GREEN << " Run successfully!" << ANSI_RESET; bag.close();
LOG(INFO) << "We will save pcd files in: " << save_pcd_folder << "/pcd/" << " Check it ^_^";
return 0;
}