@@ -33,10 +33,10 @@ void DustFilter::getParams()
3333 nh_.param <float >(name_space_ + " /range_threshold_m" , range_threshold_m_, DEFAULT_RANGE_THRESHHOLD_M);
3434 nh_.param <int >(name_space_ + " /min_neighbors" , min_neighbors_, DEFAULT_MIN_NEIGHBORS);
3535 nh_.param <float >(name_space_ + " /max_range_m" , max_range_m_, DEFAULT_MAX_RANGE_M);
36- nh_.param <float >(name_space_ + " /inside_min_x_m" , inside_min_x_m_, -0.5 );
37- nh_.param <float >(name_space_ + " /inside_max_x_m" , inside_max_x_m_, 0.5 );
38- nh_.param <float >(name_space_ + " /inside_min_y_m" , inside_min_y_m_, -0.5 );
39- nh_.param <float >(name_space_ + " /inside_max_y_m" , inside_max_y_m_, 0.5 );
36+ nh_.param <float >(name_space_ + " /inside_min_x_m" , inside_min_x_m_, -0.7 );
37+ nh_.param <float >(name_space_ + " /inside_max_x_m" , inside_max_x_m_, 0.7 );
38+ nh_.param <float >(name_space_ + " /inside_min_y_m" , inside_min_y_m_, -0.7 );
39+ nh_.param <float >(name_space_ + " /inside_max_y_m" , inside_max_y_m_, 0.7 );
4040 nh_.param <float >(name_space_ + " /inside_min_z_m" , inside_min_z_m_, -0.5 );
4141 nh_.param <float >(name_space_ + " /inside_max_z_m" , inside_max_z_m_, 0.5 );
4242 nh_.param <float >(name_space_ + " /outside_min_x_m" , outside_min_x_m_, std::numeric_limits<float >::lowest ());
@@ -59,7 +59,7 @@ void DustFilter::getParams()
5959
6060void DustFilter::printInsideParams ()
6161{
62- ROS_INFO_STREAM (name_space_ + " /inside_max_x_m = " << inside_max_x_m_ );
62+ ROS_INFO_STREAM (name_space_ + " /inside_min_x_m = " << inside_min_x_m_ );
6363 ROS_INFO_STREAM (name_space_ + " /inside_max_x_m = " << inside_max_x_m_);
6464 ROS_INFO_STREAM (name_space_ + " /inside_min_y_m = " << inside_min_y_m_);
6565 ROS_INFO_STREAM (name_space_ + " /inside_max_y_m = " << inside_max_y_m_);
@@ -77,16 +77,17 @@ void DustFilter::printOutsideParams()
7777 ROS_INFO_STREAM (name_space_ + " /outside_max_z_m = " << outside_max_z_m_);
7878}
7979
80- int DustFilter::process (pcl::PointCloud<pcl::PointXYZIR> &pcl)
80+ int DustFilter::process (pcl::PointCloud<pcl::PointXYZIR> &pcl, bool skip_dust_filter )
8181{
82- bool nan_mask[pcl.width * pcl.width ];
82+ bool nan_mask[pcl.width * pcl.height ];
8383
8484 bool is_dense = pcl.is_dense ;
8585 for (uint32_t width = 0 ; width < pcl.width ; width++)
8686 {
8787 for (uint32_t height = 0 ; height < pcl.height ; height++)
8888 {
8989 int index = width * pcl.height + height;
90+ nan_mask[index] = false ;
9091 pcl::PointXYZIR &point = pcl.points [index];
9192
9293 // if already nan, continue
@@ -97,7 +98,6 @@ int DustFilter::process(pcl::PointCloud<pcl::PointXYZIR> &pcl)
9798 }
9899
99100 // if beyond the max range, don't filter dust
100- bool skip_dust_filter = false ;
101101 if (point.range > max_range_m_)
102102 {
103103 skip_dust_filter = true ;
0 commit comments