@@ -33,18 +33,18 @@ 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 );
37- nh_.param <float >(name_space_ + " /inside_max_x_m" , inside_max_x_m_, 0 );
38- nh_.param <float >(name_space_ + " /inside_min_y_m" , inside_min_y_m_, 0 );
39- nh_.param <float >(name_space_ + " /inside_max_y_m" , inside_max_y_m_, 0 );
40- nh_.param <float >(name_space_ + " /inside_min_z_m" , inside_min_z_m_, 0 );
41- nh_.param <float >(name_space_ + " /inside_max_z_m" , inside_max_z_m_, 0 );
42- nh_.param <float >(name_space_ + " /outside_min_x_m" , outside_min_x_m_, std::numeric_limits<double >::min ());
43- nh_.param <float >(name_space_ + " /outside_max_x_m" , outside_max_x_m_, std::numeric_limits<double >::max ());
44- nh_.param <float >(name_space_ + " /outside_min_y_m" , outside_min_y_m_, std::numeric_limits<double >::min ());
45- nh_.param <float >(name_space_ + " /outside_max_y_m" , outside_max_y_m_, std::numeric_limits<double >::max ());
46- nh_.param <float >(name_space_ + " /outside_min_z_m" , outside_min_z_m_, std::numeric_limits<double >::min ());
47- nh_.param <float >(name_space_ + " /outside_max_z_m" , outside_max_z_m_, std::numeric_limits<double >::max ());
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 );
40+ nh_.param <float >(name_space_ + " /inside_min_z_m" , inside_min_z_m_, - 0.5 );
41+ nh_.param <float >(name_space_ + " /inside_max_z_m" , inside_max_z_m_, 0.5 );
42+ nh_.param <float >(name_space_ + " /outside_min_x_m" , outside_min_x_m_, std::numeric_limits<float >::lowest ());
43+ nh_.param <float >(name_space_ + " /outside_max_x_m" , outside_max_x_m_, std::numeric_limits<float >::max ());
44+ nh_.param <float >(name_space_ + " /outside_min_y_m" , outside_min_y_m_, std::numeric_limits<float >::lowest ());
45+ nh_.param <float >(name_space_ + " /outside_max_y_m" , outside_max_y_m_, std::numeric_limits<float >::max ());
46+ nh_.param <float >(name_space_ + " /outside_min_z_m" , outside_min_z_m_, std::numeric_limits<float >::lowest ());
47+ nh_.param <float >(name_space_ + " /outside_max_z_m" , outside_max_z_m_, std::numeric_limits<float >::max ());
4848
4949
5050 if (first_run)
0 commit comments