Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions depth_segmentation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@
<depend>opencv3_catkin</depend>
<depend>OpenMP</depend>
<depend>pcl_catkin</depend>
<depend>pcl_conversions</depend>
<depend>pcl_ros</depend>
<depend>roscpp</depend>
<depend>tf</depend>
</package>
12 changes: 6 additions & 6 deletions depth_segmentation/src/depth_segmentation_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ class DepthSegmentationNode {

void publish_segments(
const std::vector<depth_segmentation::Segment>& segments,
const ros::Time& timestamp) {
const std_msgs::Header& header ) {
CHECK_GT(segments.size(), 0u);
pcl::PointCloud<PointType>::Ptr scene_pcl(new pcl::PointCloud<PointType>);
for (depth_segmentation::Segment segment : segments) {
Expand All @@ -144,17 +144,17 @@ class DepthSegmentationNode {
}
sensor_msgs::PointCloud2 pcl2_msg;
pcl::toROSMsg(*segment_pcl, pcl2_msg);
pcl2_msg.header.stamp = timestamp;
pcl2_msg.header.frame_id = depth_segmentation::kTfDepthCameraFrame;
pcl2_msg.header.stamp = header.stamp;
pcl2_msg.header.frame_id = header.frame_id;
point_cloud2_segment_pub_.publish(pcl2_msg);
}
// Just for rviz also publish the whole scene, as otherwise only ~10
// segments are shown:
// https://github.com/ros-visualization/rviz/issues/689
sensor_msgs::PointCloud2 pcl2_msg;
pcl::toROSMsg(*scene_pcl, pcl2_msg);
pcl2_msg.header.stamp = timestamp;
pcl2_msg.header.frame_id = depth_segmentation::kTfDepthCameraFrame;
pcl2_msg.header.stamp = header.stamp;
pcl2_msg.header.frame_id = header.frame_id;
point_cloud2_scene_pub_.publish(pcl2_msg);
}

Expand Down Expand Up @@ -278,7 +278,7 @@ class DepthSegmentationNode {
depth_map, edge_map, normal_map, &label_map,
&segment_masks, &segments);
if (segments.size() > 0) {
publish_segments(segments, depth_msg->header.stamp);
publish_segments(segments, depth_msg->header);
}

// Update the member images to the new images.
Expand Down