diff --git a/CMakeLists.txt b/CMakeLists.txt index 0ee7f72f0c187d7b1b7929b5ea7e3c68f584d168..fd27ab0ab859cc702cf2d68a36e69db886771197 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,7 +2,7 @@ # The new CMakeLists.txt file starts here # ******************************************************************** cmake_minimum_required(VERSION 2.8.3) -project(iri_nav_hole_detection) +project(iri_point_cloud_hole_detection) ## Find catkin macros and libraries #find_package(catkin REQUIRED) @@ -54,7 +54,7 @@ find_package(iriutils REQUIRED) # ******************************************************************** # Add the dynamic reconfigure file # ******************************************************************** -generate_dynamic_reconfigure_options(cfg/HoleDetection.cfg) +generate_dynamic_reconfigure_options(cfg/PointCloudHoleDetection.cfg) # ******************************************************************** # Add run time dependencies here @@ -87,7 +87,7 @@ include_directories(${iriutils_INCLUDE_DIR} ./include) # add_library(${PROJECT_NAME} <list of source files>) ## Declare a cpp executable -add_executable(${PROJECT_NAME} src/iri_nav_hole_detection_alg.cpp src/iri_nav_hole_detection_alg_node.cpp) +add_executable(${PROJECT_NAME} src/iri_point_cloud_hole_detection_alg.cpp src/iri_point_cloud_hole_detection_alg_node.cpp) # ******************************************************************** # Add the libraries diff --git a/cfg/HoleDetection.cfg b/cfg/PointCloudHoleDetection.cfg similarity index 65% rename from cfg/HoleDetection.cfg rename to cfg/PointCloudHoleDetection.cfg index d8c1a88d6ab27efa8db25da633d77a14987a6849..8e9864d17f19d5b7fca90d4d0cedd2d35459797c 100755 --- a/cfg/HoleDetection.cfg +++ b/cfg/PointCloudHoleDetection.cfg @@ -31,7 +31,7 @@ # Author: -PACKAGE='iri_nav_hole_detection' +PACKAGE='iri_point_cloud_hole_detection' from dynamic_reconfigure.parameter_generator_catkin import * @@ -39,13 +39,12 @@ gen = ParameterGenerator() # Name Type Reconfiguration level Description Default Min Max #gen.add("velocity_scale_factor", double_t, 0, "Maximum velocity scale factor", 0.5, 0.0, 1.0) -gen.add( "hole_min_p", int_t, 0, "No of Points to be hole (less points is a hole)", 30, 5, 200) -gen.add( "num_cells", int_t, 0, "No of cells in the detections zone", 3, 1, 10) -gen.add( "box_y", double_t, 0, "Y distance hole detection zone", 0.6, 0, 1.5) -gen.add( "box_z_ini", double_t, 0, "Initial Z hole detection zone", 0, -0.5, 0.5) -gen.add( "box_z_end", double_t, 0, "Z distance hole detection zone", 0.1, -0.5, 0.5) -gen.add( "box_x_ini", double_t, 0, "Initial X hole detection zone", 0.8, 0, 2) -gen.add( "box_x_end", double_t, 0, "X distance hole detection zone", 0.9, 0.5, 2) +gen.add("hole_min_p", int_t, 0, "No of Points to be hole (less points is a hole)",30,5,200) +gen.add("num_cells", int_t, 0, "No of cells in the detections zone",3, 1, 10) +gen.add("box_y", double_t, 0, "Y distance hole detection zone", 0.6, 0, 1.5) +gen.add("box_z_ini", double_t, 0, "Initial Z hole detection zone", 0, -0.5, 0.5) +gen.add("box_z_end", double_t, 0, "Z distance hole detection zone", 0.1, -0.5, 0.5) +gen.add("box_x_ini", double_t, 0, "Initial X hole detection zone", 0.8, 0, 2) +gen.add("box_x_end", double_t, 0, "X distance hole detection zone", 0.9, 0.5, 2) - -exit(gen.generate(PACKAGE, "HoleDetectionAlgorithm", "HoleDetection")) +exit(gen.generate(PACKAGE, "PointCloudHoleDetectionAlgorithm", "PointCloudHoleDetection")) diff --git a/config/far_config.yaml b/config/far_config.yaml new file mode 100755 index 0000000000000000000000000000000000000000..217b2186429cfb36e881879b387e6513e88d76b4 --- /dev/null +++ b/config/far_config.yaml @@ -0,0 +1,7 @@ +hole_min_p: 35 +num_cells: 3 +box_y: 0.6 +box_z_ini: -0.1 +box_z_end: 0.1 +box_x_ini: 0.8 +box_x_end: 1.1 diff --git a/config/near_config.yaml b/config/near_config.yaml new file mode 100755 index 0000000000000000000000000000000000000000..70c30b1747842ccbf7b8e62f2d0df4e9132559fa --- /dev/null +++ b/config/near_config.yaml @@ -0,0 +1,7 @@ +hole_min_p: 35 +num_cells: 3 +box_y: 0.45 +box_z_ini: -0.1 +box_z_end: 0.1 +box_x_ini: 0.6 +box_x_end: 0.85 diff --git a/include/iri_nav_hole_detection_alg.h b/include/iri_point_cloud_hole_detection_alg.h similarity index 87% rename from include/iri_nav_hole_detection_alg.h rename to include/iri_point_cloud_hole_detection_alg.h index 9ef67472a8cf79d70c6582b32511055d4060f88b..16835cc0cfaa9b201fcd0cb1cf6d40df1178fade 100644 --- a/include/iri_nav_hole_detection_alg.h +++ b/include/iri_point_cloud_hole_detection_alg.h @@ -22,10 +22,10 @@ // refer to the IRI wiki page for more information: // http://wikiri.upc.es/index.php/Robotics_Lab -#ifndef _iri_nav_hole_detection_alg_h_ -#define _iri_nav_hole_detection_alg_h_ +#ifndef _iri_point_cloud_hole_detection_alg_h_ +#define _iri_point_cloud_hole_detection_alg_h_ -#include <iri_nav_hole_detection/HoleDetectionConfig.h> +#include <iri_point_cloud_hole_detection/PointCloudHoleDetectionConfig.h> #include "mutex.h" #include <pcl_ros/point_cloud.h> @@ -33,9 +33,6 @@ #include <pcl/point_types.h> #include <pcl/impl/point_types.hpp> - -using namespace pcl; -using namespace std; //include hole_detection_alg main library /** @@ -43,13 +40,13 @@ using namespace std; * * */ -class HoleDetectionAlgorithm +class PointCloudHoleDetectionAlgorithm { protected: /** * \brief define config type * - * Define a Config type with the HoleDetectionConfig. All driver implementations + * Define a Config type with the PointCloudHoleDetectionConfig. All driver implementations * will then use the same variable type Config. */ CMutex alg_mutex_; @@ -63,10 +60,10 @@ class HoleDetectionAlgorithm /** * \brief define config type * - * Define a Config type with the HoleDetectionConfig. All driver implementations + * Define a Config type with the PointCloudHoleDetectionConfig. All driver implementations * will then use the same variable type Config. */ - typedef iri_nav_hole_detection::HoleDetectionConfig Config; + typedef iri_point_cloud_hole_detection::PointCloudHoleDetectionConfig Config; /** * \brief config variable @@ -84,7 +81,7 @@ class HoleDetectionAlgorithm * Attributes from the main node driver class IriBaseDriver such as loop_rate, * may be also overload here. */ - HoleDetectionAlgorithm(void); + PointCloudHoleDetectionAlgorithm(void); /** * \brief Lock Algorithm @@ -131,7 +128,7 @@ class HoleDetectionAlgorithm * This destructor is called when the object is about to be destroyed. * */ - ~HoleDetectionAlgorithm(void); + ~PointCloudHoleDetectionAlgorithm(void); void cloud_all(int hole_min_p, float box_z_end, float box_x_ini, float box_y, float box_z_ini, float box_x_end, int num_cells, float Z, diff --git a/include/iri_nav_hole_detection_alg_node.h b/include/iri_point_cloud_hole_detection_alg_node.h similarity index 91% rename from include/iri_nav_hole_detection_alg_node.h rename to include/iri_point_cloud_hole_detection_alg_node.h index 28221d8e8dbf5522036f4d724c3aec4fcc283a3a..c2e249b1ce7ccd574434dd2779a9df683a4d3b68 100644 --- a/include/iri_nav_hole_detection_alg_node.h +++ b/include/iri_point_cloud_hole_detection_alg_node.h @@ -22,11 +22,11 @@ // refer to the IRI wiki page for more information: // http://wikiri.upc.es/index.php/Robotics_Lab -#ifndef _iri_nav_hole_detection_alg_node_h_ -#define _iri_nav_hole_detection_alg_node_h_ +#ifndef _iri_point_cloud_hole_detection_alg_node_h_ +#define _iri_point_cloud_hole_detection_alg_node_h_ #include <iri_base_algorithm/iri_base_algorithm.h> -#include "iri_nav_hole_detection_alg.h" +#include "iri_point_cloud_hole_detection_alg.h" #include <ros/ros.h> //#include <ros/publisher.h> @@ -51,7 +51,7 @@ using namespace std; * \brief IRI ROS Specific Algorithm Class * */ -class HoleDetectionAlgNode : public algorithm_base::IriBaseAlgorithm<HoleDetectionAlgorithm> +class PointCloudHoleDetectionAlgNode : public algorithm_base::IriBaseAlgorithm<PointCloudHoleDetectionAlgorithm> { private: @@ -80,7 +80,7 @@ class HoleDetectionAlgNode : public algorithm_base::IriBaseAlgorithm<HoleDetecti // [client attributes] // [action server attributes] - HoleDetectionAlgorithm hole_detect; + PointCloudHoleDetectionAlgorithm hole_detect; // [action client attributes] public: @@ -90,7 +90,7 @@ class HoleDetectionAlgNode : public algorithm_base::IriBaseAlgorithm<HoleDetecti * This constructor initializes specific class attributes and all ROS * communications variables to enable message exchange. */ - HoleDetectionAlgNode(void); + PointCloudHoleDetectionAlgNode(void); /** * \brief Destructor @@ -98,7 +98,7 @@ class HoleDetectionAlgNode : public algorithm_base::IriBaseAlgorithm<HoleDetecti * This destructor frees all necessary dynamic memory allocated within this * this class. */ - ~HoleDetectionAlgNode(void); + ~PointCloudHoleDetectionAlgNode(void); protected: /** diff --git a/launch/node.launch b/launch/node.launch new file mode 100644 index 0000000000000000000000000000000000000000..38083f4f96fc7361ab9a902d4fdcc4217a66b023 --- /dev/null +++ b/launch/node.launch @@ -0,0 +1,24 @@ +<?xml version="1.0" encoding="UTF-8"?> +<launch> + + <arg name="ns" default="ana"/> + <arg name="node_name" default="point_cloud_hole_detection"/> + <arg name="config_file" default="$(find iri_point_cloud_hole_detection)/config/default_config.yaml"/> + <arg name="output" default="screen"/> + <arg name="launch_prefix" default=""/> + <arg name="cloud_in" default="~pointcloud_in"/> + + <group ns="$(arg ns)"> + + <node pkg ="iri_point_cloud_hole_detection" + type="iri_point_cloud_hole_detection" + name="$(arg node_name)" + output="$(arg output)" + launch-prefix="$(arg launch_prefix)"> + <remap from="~input" to="$(arg cloud_in)"/> + <rosparam file="$(arg config_file)" command="load"/> + </node> + + </group> + +</launch> diff --git a/launch/nodelet.launch b/launch/nodelet.launch new file mode 100644 index 0000000000000000000000000000000000000000..8bc3fd6b2fc60d0bb6def78f87a44483cffff4e8 --- /dev/null +++ b/launch/nodelet.launch @@ -0,0 +1,25 @@ +<?xml version="1.0" encoding="UTF-8"?> +<launch> + + <arg name="ns" default="ana"/> + <arg name="node_name" default="point_cloud_hole_detection"/> + <arg name="camera_nodelet_manager" default="camera_nodelet_manager"/> + <arg name="config_file" default="$(find iri_point_cloud_hole_detection)/config/default_config.yaml"/> + <arg name="output" default="screen"/> + <arg name="launch_prefix" default=""/> + <arg name="cloud_in" default="~pointcloud_in"/> + + <group ns="$(arg ns)"> + + <node name="$(arg node_name)" + pkg="nodelet" + type="nodelet" + args="load iri_point_cloud_hole_detection/AveragePointCloudAlgNodelet $(arg camera_nodelet_manager)" + output="$(arg output)"> + <remap from="~input" to="$(arg cloud_in)"/> + <rosparam file="$(arg config_file)" command="load"/> + </node> + + </group> + +</launch> diff --git a/mainpage.dox b/mainpage.dox deleted file mode 100644 index 1884406135d37652c42317d1b8bb6e88bec9e0b4..0000000000000000000000000000000000000000 --- a/mainpage.dox +++ /dev/null @@ -1,26 +0,0 @@ -/** -\mainpage -\htmlinclude manifest.html - -\b iri_hole_detection is ... - -<!-- -Provide an overview of your package. ---> - - -\section codeapi Code API - -<!-- -Provide links to specific auto-generated API documentation within your -package that is of particular interest to a reader. Doxygen will -document pretty much every part of your code, so do your best here to -point the reader to the actual API. - -If your codebase is fairly large or has different sets of APIs, you -should use the doxygen 'group' tag to keep these APIs together. For -example, the roscpp documentation has 'libros' group. ---> - - -*/ diff --git a/package.xml b/package.xml index 7e51220cff94a0e86badeefd7f2089587076821e..7d1923bdb6a1a692f86d0953a6bcdee39887fd36 100644 --- a/package.xml +++ b/package.xml @@ -1,8 +1,8 @@ <?xml version="1.0"?> <package> - <name>iri_nav_hole_detection</name> + <name>iri_point_cloud_hole_detection</name> <version>1.0.0</version> - <description>iri_nav_hole_detection</description> + <description>iri_point_cloud_hole_detection</description> <!-- One maintainer tag required, multiple allowed, one person per tag --> <!-- Example: --> diff --git a/src/iri_nav_hole_detection_alg.cpp b/src/iri_nav_hole_detection_alg.cpp deleted file mode 100644 index f72fbbbff43404275ea5b8788265804260d5a8e9..0000000000000000000000000000000000000000 --- a/src/iri_nav_hole_detection_alg.cpp +++ /dev/null @@ -1,92 +0,0 @@ -#include "iri_nav_hole_detection_alg.h" -using namespace std; - -HoleDetectionAlgorithm::HoleDetectionAlgorithm(void) -{ -} - -HoleDetectionAlgorithm::~HoleDetectionAlgorithm(void) -{ -} - -void HoleDetectionAlgorithm::config_update(Config& new_cfg, uint32_t level) -{ - this->lock(); - - // save the current configuration - this->config_=new_cfg; - - this->unlock(); -} - -// HoleDetectionAlgorithm Public API -/* -It selects the points inside a box generated using the input params. These points -are separated in three regions. If any of them has less than a minimum number of -points, there is a hole so it generates a virtual obstacle in order to notify -the navigation stack. -*/ -void HoleDetectionAlgorithm::cloud_all(int hole_min_p, float box_z_end, float box_x_ini, - float box_y, float box_z_ini, float box_x_end, int num_cells, float Z, - pcl::PointCloud<pcl::PointXYZRGB>& cloud_in, - pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud_for) -{ - -int p [num_cells] = {}; -float threshold [num_cells+1] = {}; - -////////////////////////////////////////////////////////////////////////////// -// Hole detection box generation -////////////////////////////////////////////////////////////////////////////// -for (int i=0; i<=num_cells; ++i) -{ - threshold[i] = (box_y/2)-((num_cells-i)*(box_y/num_cells)); -} - - -for (size_t rowIndex=0, pointIndex=0; rowIndex<cloud_in.height; ++rowIndex) -{ - for (size_t colIndex=0; colIndex<cloud_in.width; ++colIndex, ++pointIndex) - { - if (box_z_ini < cloud_in.points[pointIndex].z && - cloud_in.points[pointIndex].z < box_z_end && - box_x_ini < cloud_in.points[pointIndex].x && - cloud_in.points[pointIndex].x < box_x_end) - { - for (int cell=0; cell<num_cells; ++cell) - { - if ( threshold[cell] < cloud_in.points[pointIndex].y && - cloud_in.points[pointIndex].y < threshold[cell+1] ) - { - cloud_in.points[pointIndex].r=0; - cloud_in.points[pointIndex].g=int(255*(float(cell)/float(max(1,num_cells-1)))); - cloud_in.points[pointIndex].b=255; - p[cell]=p[cell]+1; - } - } - } //if() bracket - } -} - -////////////////////////////////////////////////////////////////////////////// -// Virtual obstacle generation -////////////////////////////////////////////////////////////////////////////// -Z=0.1; - -for (size_t rowIndex=0, pointIndex=0; rowIndex<5; ++rowIndex) -{ - for (size_t colIndex=0; colIndex<5; ++colIndex, ++pointIndex) - { - for (int cell=0; cell<num_cells; ++cell) - { - if (p[cell] < hole_min_p) - { - cloud_for->points.push_back (pcl::PointXYZ(box_x_ini, threshold[cell] + - (threshold[cell+1]-threshold[cell])*colIndex/4, Z)); - } - } - } - Z=Z+0.05; -} - -} diff --git a/src/iri_point_cloud_hole_detection_alg.cpp b/src/iri_point_cloud_hole_detection_alg.cpp new file mode 100644 index 0000000000000000000000000000000000000000..8dd1bc9e73f3f66a181fffe9ba7219e1e299c14c --- /dev/null +++ b/src/iri_point_cloud_hole_detection_alg.cpp @@ -0,0 +1,88 @@ +#include "iri_point_cloud_hole_detection_alg.h" +using namespace std; + +PointCloudHoleDetectionAlgorithm::PointCloudHoleDetectionAlgorithm(void) +{ +} + +PointCloudHoleDetectionAlgorithm::~PointCloudHoleDetectionAlgorithm(void) +{ +} + +void PointCloudHoleDetectionAlgorithm::config_update(Config& new_cfg, uint32_t level) +{ + this->lock(); + + // save the current configuration + this->config_=new_cfg; + + this->unlock(); +} + +// PointCloudHoleDetectionAlgorithm Public API +/* +It selects the points inside a box generated using the input params. These points +are separated in three regions. If any of them has less than a minimum number of +points, there is a hole so it generates a virtual obstacle in order to notify +the navigation stack. +*/ +void PointCloudHoleDetectionAlgorithm::cloud_all(int hole_min_p, float box_z_end, float box_x_ini, + float box_y, float box_z_ini, float box_x_end, int num_cells, float Z, + pcl::PointCloud<pcl::PointXYZRGB>& cloud_in, + pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud_for) +{ + int p [num_cells] = {}; + float threshold [num_cells+1] = {}; + + ////////////////////////////////////////////////////////////////////////////// + // Hole detection box generation + ////////////////////////////////////////////////////////////////////////////// + for(int i=0;i<=num_cells;++i) + threshold[i]=(box_y/2)-((num_cells-i)*(box_y/num_cells)); + + + for (size_t rowIndex=0, pointIndex=0; rowIndex<cloud_in.height; ++rowIndex) + { + for (size_t colIndex=0; colIndex<cloud_in.width; ++colIndex, ++pointIndex) + { + if (box_z_ini < cloud_in.points[pointIndex].z && + cloud_in.points[pointIndex].z < box_z_end && + box_x_ini < cloud_in.points[pointIndex].x && + cloud_in.points[pointIndex].x < box_x_end) + { + for (int cell=0; cell<num_cells; ++cell) + { + if ( threshold[cell] < cloud_in.points[pointIndex].y && + cloud_in.points[pointIndex].y < threshold[cell+1] ) + { + cloud_in.points[pointIndex].r=0; + cloud_in.points[pointIndex].g=int(255*(float(cell)/float(max(1,num_cells-1)))); + cloud_in.points[pointIndex].b=255; + p[cell]=p[cell]+1; + } + } + } //if() bracket + } + } + + ////////////////////////////////////////////////////////////////////////////// + // Virtual obstacle generation + ////////////////////////////////////////////////////////////////////////////// + Z=0.1; + + for (size_t rowIndex=0, pointIndex=0; rowIndex<5; ++rowIndex) + { + for (size_t colIndex=0; colIndex<5; ++colIndex, ++pointIndex) + { + for (int cell=0; cell<num_cells; ++cell) + { + if (p[cell] < hole_min_p) + { + cloud_for->points.push_back (pcl::PointXYZ(box_x_ini, threshold[cell] + + (threshold[cell+1]-threshold[cell])*colIndex/4, Z)); + } + } + } + Z=Z+0.05; + } +} diff --git a/src/iri_nav_hole_detection_alg_node.cpp b/src/iri_point_cloud_hole_detection_alg_node.cpp similarity index 79% rename from src/iri_nav_hole_detection_alg_node.cpp rename to src/iri_point_cloud_hole_detection_alg_node.cpp index 5159593f36cb2bb23300e595529d90b009e824ce..428da29783828ae722902d21954f32f601baec3d 100644 --- a/src/iri_nav_hole_detection_alg_node.cpp +++ b/src/iri_point_cloud_hole_detection_alg_node.cpp @@ -1,7 +1,7 @@ -#include "iri_nav_hole_detection_alg_node.h" +#include "iri_point_cloud_hole_detection_alg_node.h" -HoleDetectionAlgNode::HoleDetectionAlgNode(void) : - algorithm_base::IriBaseAlgorithm<HoleDetectionAlgorithm>(),hole_min_p(60),box_z_end(0),box_x_ini(1), +PointCloudHoleDetectionAlgNode::PointCloudHoleDetectionAlgNode(void) : + algorithm_base::IriBaseAlgorithm<PointCloudHoleDetectionAlgorithm>(),hole_min_p(60),box_z_end(0),box_x_ini(1), box_z_ini(-0.1),box_x_end(1.8),box_y(0.9),num_cells(3) { //init class attributes if necessary @@ -11,7 +11,7 @@ HoleDetectionAlgNode::HoleDetectionAlgNode(void) : this->hole_obstacle_publisher_ = this->public_node_handle_.advertise<sensor_msgs::PointCloud>("hole_obstacle", 10); this->hole_all_publisher_ = this->public_node_handle_.advertise<sensor_msgs::PointCloud2>("hole_zone", 10); // [init subscribers] - this->input_subscriber_ = this->public_node_handle_.subscribe("input", 10, &HoleDetectionAlgNode::input_callback, this); + this->input_subscriber_ = this->public_node_handle_.subscribe("input", 10, &PointCloudHoleDetectionAlgNode::input_callback, this); // [init services] @@ -23,12 +23,12 @@ HoleDetectionAlgNode::HoleDetectionAlgNode(void) : // [init action clients] } -HoleDetectionAlgNode::~HoleDetectionAlgNode(void) +PointCloudHoleDetectionAlgNode::~PointCloudHoleDetectionAlgNode(void) { // [free dynamic memory] } -void HoleDetectionAlgNode::mainNodeThread(void) +void PointCloudHoleDetectionAlgNode::mainNodeThread(void) { // [fill msg structures] //this->PointCloud2_msg_.data = my_var; @@ -41,9 +41,9 @@ void HoleDetectionAlgNode::mainNodeThread(void) } //PointCloud2_msg_ /* [subscriber callbacks] */ -void HoleDetectionAlgNode::input_callback(const sensor_msgs::PointCloud2::ConstPtr& msg) +void PointCloudHoleDetectionAlgNode::input_callback(const sensor_msgs::PointCloud2::ConstPtr& msg) { - ROS_INFO("HoleDetectionAlgNode::input_callback: New Message Received"); + ROS_INFO("PointCloudHoleDetectionAlgNode::input_callback: New Message Received"); @@ -116,7 +116,7 @@ void HoleDetectionAlgNode::input_callback(const sensor_msgs::PointCloud2::ConstP /* [action requests] */ -void HoleDetectionAlgNode::node_config_update(Config &config, uint32_t level) +void PointCloudHoleDetectionAlgNode::node_config_update(Config &config, uint32_t level) { this->alg_.lock(); hole_min_p=config.hole_min_p; @@ -129,12 +129,12 @@ num_cells=config.num_cells; this->alg_.unlock(); } -void HoleDetectionAlgNode::addNodeDiagnostics(void) +void PointCloudHoleDetectionAlgNode::addNodeDiagnostics(void) { } /* main function */ int main(int argc,char *argv[]) { - return algorithm_base::main<HoleDetectionAlgNode>(argc, argv, "iri_nav_hole_detection_alg_node"); + return algorithm_base::main<PointCloudHoleDetectionAlgNode>(argc, argv, "iri_point_cloud_hole_detection_alg_node"); }