48 srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::CropBoxConfig> > (nh);
49 dynamic_reconfigure::Server<pcl_ros::CropBoxConfig>::CallbackType
f = boost::bind (&
CropBox::config_callback,
this, _1, _2);
50 srv_->setCallback (
f);
59 boost::mutex::scoped_lock lock (mutex_);
61 Eigen::Vector4f min_point,max_point;
62 min_point = impl_.getMin();
63 max_point = impl_.getMax();
65 Eigen::Vector4f new_min_point, new_max_point;
66 new_min_point << config.min_x, config.min_y, config.min_z, 0.0;
67 new_max_point << config.max_x, config.max_y, config.max_z, 0.0;
70 if (min_point != new_min_point)
72 NODELET_DEBUG (
"[%s::config_callback] Setting the minimum point to: %f %f %f.",
getName ().c_str (), new_min_point(0),new_min_point(1),new_min_point(2));
74 impl_.setMin(new_min_point);
77 if (max_point != new_max_point)
79 NODELET_DEBUG (
"[%s::config_callback] Setting the maximum point to: %f %f %f.",
getName ().c_str (), new_max_point(0),new_max_point(1),new_max_point(2));
81 impl_.setMax(new_max_point);
85 if (impl_.getKeepOrganized () != config.keep_organized)
87 NODELET_DEBUG (
"[%s::config_callback] Setting the filter keep_organized value to: %s.",
getName ().c_str (), config.keep_organized ?
"true" :
"false");
89 impl_.setKeepOrganized (config.keep_organized);
93 if (impl_.getNegative() != config.negative)
95 NODELET_DEBUG (
"[%s::config_callback] Setting the filter negative flag to: %s.",
getName ().c_str (), config.negative ?
"true" :
"false");
97 impl_.setNegative(config.negative);
101 if (tf_input_frame_ != config.input_frame)
103 tf_input_frame_ = config.input_frame;
104 NODELET_DEBUG (
"[%s::config_callback] Setting the input TF frame to: %s.",
getName ().c_str (), tf_input_frame_.c_str ());
106 if (tf_output_frame_ != config.output_frame)
108 tf_output_frame_ = config.output_frame;
109 NODELET_DEBUG (
"[%s::config_callback] Setting the output TF frame to: %s.",
getName ().c_str (), tf_output_frame_.c_str ());