Skip to content

Commit 9b3186d

Browse files
authored
Merge pull request #17 from juliangaal/master
Better integration into ROS ecosystem
2 parents 2b9a7ad + 0ae62cf commit 9b3186d

File tree

4 files changed

+14
-11
lines changed

4 files changed

+14
-11
lines changed

Diff for: include/patchworkpp/utils.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -65,8 +65,8 @@ POINT_CLOUD_REGISTER_POINT_STRUCT(PointXYZILID,
6565
(float, y, y)
6666
(float, z, z)
6767
(float, intensity, intensity)
68-
(uint16_t, label, label)
69-
(uint16_t, id, id))
68+
(std::uint16_t, label, label)
69+
(std::uint16_t, id, id))
7070

7171

7272
void PointXYZILID2XYZI(pcl::PointCloud<PointXYZILID>& src,
@@ -240,7 +240,7 @@ void calculate_precision_recall_without_vegetation(const pcl::PointCloud<PointXY
240240
}
241241

242242

243-
int save_all_labels(const pcl::PointCloud<PointXYZILID>& pc, string ABS_DIR, string seq, int count){
243+
void save_all_labels(const pcl::PointCloud<PointXYZILID>& pc, string ABS_DIR, string seq, int count){
244244

245245
std::string count_str = std::to_string(count);
246246
std::string count_str_padded = std::string(NUM_ZEROS - count_str.length(), '0') + count_str;

Diff for: include/tools/kitti_loader.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -92,6 +92,8 @@ class KittiLoader {
9292
}
9393

9494
}
95+
96+
return 0;
9597
}
9698

9799
private:

Diff for: rviz/demo.rviz

+2-2
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,7 @@ Visualization Manager:
110110
Size (Pixels): 3
111111
Size (m): 0.10000000149011612
112112
Style: Flat Squares
113-
Topic: /demo/ground
113+
Topic: /ground_segmentation/ground
114114
Unreliable: false
115115
Use Fixed Frame: true
116116
Use rainbow: true
@@ -138,7 +138,7 @@ Visualization Manager:
138138
Size (Pixels): 3
139139
Size (m): 0.10000000149011612
140140
Style: Flat Squares
141-
Topic: /demo/nonground
141+
Topic: /ground_segmentation/nonground
142142
Unreliable: false
143143
Use Fixed Frame: true
144144
Use rainbow: true

Diff for: src/demo.cpp

+7-6
Original file line numberDiff line numberDiff line change
@@ -19,9 +19,10 @@ ros::Publisher pub_ground;
1919
ros::Publisher pub_non_ground;
2020

2121
template<typename T>
22-
sensor_msgs::PointCloud2 cloud2msg(pcl::PointCloud<T> cloud, std::string frame_id = "map") {
22+
sensor_msgs::PointCloud2 cloud2msg(pcl::PointCloud<T> cloud, const ros::Time& stamp, std::string frame_id = "map") {
2323
sensor_msgs::PointCloud2 cloud_ROS;
2424
pcl::toROSMsg(cloud, cloud_ROS);
25+
cloud_ROS.header.stamp = stamp;
2526
cloud_ROS.header.frame_id = frame_id;
2627
return cloud_ROS;
2728
}
@@ -38,12 +39,12 @@ void callbackCloud(const sensor_msgs::PointCloud2::Ptr &cloud_msg)
3839

3940
PatchworkppGroundSeg->estimate_ground(pc_curr, pc_ground, pc_non_ground, time_taken);
4041

41-
cout << "\033[1;32m" << "Result: Input PointCloud: " << pc_curr.size() << " -> Ground: " << pc_ground.size() << "/ NonGround: " << pc_non_ground.size()
42-
<< " (running_time: " << time_taken << " sec)" << "\033[0m" << endl;
42+
ROS_INFO_STREAM("\033[1;32m" << "Input PointCloud: " << pc_curr.size() << " -> Ground: " << pc_ground.size() << "/ NonGround: " << pc_non_ground.size()
43+
<< " (running_time: " << time_taken << " sec)" << "\033[0m");
4344

44-
pub_cloud.publish(cloud2msg(pc_curr, cloud_msg->header.frame_id));
45-
pub_ground.publish(cloud2msg(pc_ground, cloud_msg->header.frame_id));
46-
pub_non_ground.publish(cloud2msg(pc_non_ground, cloud_msg->header.frame_id));
45+
pub_cloud.publish(cloud2msg(pc_curr, cloud_msg->header.stamp, cloud_msg->header.frame_id));
46+
pub_ground.publish(cloud2msg(pc_ground, cloud_msg->header.stamp, cloud_msg->header.frame_id));
47+
pub_non_ground.publish(cloud2msg(pc_non_ground, cloud_msg->header.stamp, cloud_msg->header.frame_id));
4748
}
4849

4950
int main(int argc, char**argv) {

0 commit comments

Comments
 (0)