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);
pcl::CropBox< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
std::string tf_input_frame_
The input TF frame the data should be transformed into, if input.header.frame_id is different...
std::string tf_output_frame_
The output TF frame the data should be transformed into, if input.header.frame_id is different...
const std::string & getName() const
CropBox is a filter that allows the user to filter all the data inside of a given box...
boost::mutex mutex_
Internal mutex.
void config_callback(pcl_ros::CropBoxConfig &config, uint32_t level)
Dynamic reconfigure service callback.
bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
PLUGINLIB_EXPORT_CLASS(CropBox, nodelet::Nodelet)
#define NODELET_DEBUG(...)
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::CropBoxConfig > > srv_
Pointer to a dynamic reconfigure service.