diff --git a/src/ground_segmentation_alg_node.cpp b/src/ground_segmentation_alg_node.cpp
index b8f9263a77a6df7c1c2ac50f0448ec3d370f190f..890e33223c51c2383e175230dd7046f5f5b9a216 100644
--- a/src/ground_segmentation_alg_node.cpp
+++ b/src/ground_segmentation_alg_node.cpp
@@ -294,6 +294,24 @@ void GroundSegmentationAlgNode::convertInputsToSuitableFormats(void)
 {
   //std::cout << "GroundSegmentationAlgNode::convertInputsToSuitableFormats..." << std::endl;
   this->rosPointCloudtoPCLPointCloud(lidar_ros_cloud_, lidar_pcl_cloud_);
+//  std::cout << "x = " << lidar_pcl_cloud_.points[100].x << std::endl;
+//  std::cout << "y = " << lidar_pcl_cloud_.points[100].y << std::endl;
+//  std::cout << "z = " << lidar_pcl_cloud_.points[100].z << std::endl;
+//
+//  std::cout << "r = " << (int)lidar_pcl_cloud_.points[100].r << std::endl;
+//  std::cout << "g = " << (int)lidar_pcl_cloud_.points[100].g << std::endl;
+//  std::cout << "b = " << (int)lidar_pcl_cloud_.points[100].b << std::endl;
+//
+//  std::cout << "DATA_N_0_INTENSITY = " << lidar_pcl_cloud_.points[100].data_n[DATA_N_0_INTENSITY] << std::endl;
+//  std::cout << "DATA_N_1_INTENSITY_VARIANCE = " << lidar_pcl_cloud_.points[100].data_n[DATA_N_1_INTENSITY_VARIANCE] << std::endl;
+//  std::cout << "DATA_N_2_Z_MEAN = " << lidar_pcl_cloud_.points[100].data_n[DATA_N_2_Z_MEAN] << std::endl;
+//  std::cout << "DATA_N_3_Z_VARIANCE = " << lidar_pcl_cloud_.points[100].data_n[DATA_N_3_Z_VARIANCE] << std::endl;
+//
+//  std::cout << "DATA_C_0_RGB_CAST_INTO_FLOAT = " << lidar_pcl_cloud_.points[100].data_c[DATA_C_0_RGB_CAST_INTO_FLOAT] << std::endl;
+//  std::cout << "DATA_C_1_ID_CLASS = " << lidar_pcl_cloud_.points[100].data_c[DATA_C_1_ID_CLASS] << std::endl;
+//  std::cout << "DATA_C_2_MEAN_INTENSITY = " << lidar_pcl_cloud_.points[100].data_c[DATA_C_2_MEAN_INTENSITY] << std::endl;
+//  std::cout << "DATA_C_3_ORIGINAL_INDEX = " << lidar_pcl_cloud_.points[100].data_c[DATA_C_3_ORIGINAL_INDEX] << std::endl;
+
   flag_new_lidar_data_ = false;
 }