From 4cf06b28b838cbd1cd3ad14b9ab9ba2bfc838763 Mon Sep 17 00:00:00 2001
From: "Tassos (nakano) Natsakis" <891234ser@eipieq.com>
Date: Tue, 27 Sep 2022 07:42:09 +0000
Subject: [PATCH] Publishing the obstacle map

---
 src/depth_to_2d.cpp | 6 ++++++
 1 file changed, 6 insertions(+)

diff --git a/src/depth_to_2d.cpp b/src/depth_to_2d.cpp
index 30a743e..0c73f8a 100644
--- a/src/depth_to_2d.cpp
+++ b/src/depth_to_2d.cpp
@@ -70,12 +70,18 @@ void conversion_callback(const PointCloud::ConstPtr& pcl, const sensor_msgs::Imu
     obstacle_map.cells[cell_ind].y = i * device_height;
     obstacle_map.cells[cell_ind].z += pt.z; // Accumulating the z values of all the points that fall in this cell
   }
+
+  //Publishing the obstacle map for consumption from the tactile device
+  map_pub.publish(obstacle_map);
 }
 
 int main(int argc, char** argv) {
   ros::init(argc, argv, "depth_to_2d");
   ros::NodeHandle nh;
 
+  // Initializing the publisher of the obstacle map
+  map_pub = nh.advertise<nav_msgs::GridCells>("/obstacle_map", 1);
+
   // Initialising the spatial resolution of the camera and the tactile device
   // These value are assumptions but can be updated to reflect real values
   cam_width = 1024;
-- 
GitLab