Skip to content

Commit

Permalink
Merge pull request #2663 from knorth55/default-param
Browse files Browse the repository at this point in the history
use default value for param
  • Loading branch information
k-okada committed Jun 16, 2022
2 parents 318f337 + 75741c8 commit afa6115
Showing 1 changed file with 1 addition and 3 deletions.
4 changes: 1 addition & 3 deletions jsk_pcl_ros/src/multi_plane_extraction_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,10 +58,8 @@ namespace jsk_pcl_ros
pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
nonplane_pub_ = advertise<pcl::PointCloud<pcl::PointXYZRGB> >(*pnh_, "output_nonplane_cloud", 1);
pub_indices_ = advertise<PCLIndicesMsg>(*pnh_, "output/indices", 1);
if (!pnh_->getParam("max_queue_size", maximum_queue_size_)) {
maximum_queue_size_ = 100;
}

pnh_->param("max_queue_size", maximum_queue_size_, 100);
pnh_->param("use_coefficients", use_coefficients_, false);
pnh_->param("use_sensor_frame", use_sensor_frame_, false);
if (use_sensor_frame_) {
Expand Down

0 comments on commit afa6115

Please sign in to comment.