Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include <pluginlib/class_list_macros.h>
00040 #include "pcl_ros/filters/crop_box.h"
00041
00043 bool
00044 pcl_ros::CropBox::child_init (ros::NodeHandle &nh, bool &has_service)
00045 {
00046
00047 has_service = true;
00048 srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::CropBoxConfig> > (nh);
00049 dynamic_reconfigure::Server<pcl_ros::CropBoxConfig>::CallbackType f = boost::bind (&CropBox::config_callback, this, _1, _2);
00050 srv_->setCallback (f);
00051
00052 return (true);
00053 }
00054
00056 void
00057 pcl_ros::CropBox::config_callback (pcl_ros::CropBoxConfig &config, uint32_t level)
00058 {
00059 boost::mutex::scoped_lock lock (mutex_);
00060
00061 Eigen::Vector4f min_point,max_point;
00062 min_point = impl_.getMin();
00063 max_point = impl_.getMax();
00064
00065 Eigen::Vector4f new_min_point, new_max_point;
00066 new_min_point << config.min_x, config.min_y, config.min_z, 0.0;
00067 new_max_point << config.max_x, config.max_y, config.max_z, 0.0;
00068
00069
00070 if (min_point != new_min_point)
00071 {
00072 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));
00073
00074 impl_.setMin(new_min_point);
00075 }
00076
00077 if (max_point != new_max_point)
00078 {
00079 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));
00080
00081 impl_.setMax(new_max_point);
00082 }
00083
00084
00085 if (impl_.getKeepOrganized () != config.keep_organized)
00086 {
00087 NODELET_DEBUG ("[%s::config_callback] Setting the filter keep_organized value to: %s.", getName ().c_str (), config.keep_organized ? "true" : "false");
00088
00089 impl_.setKeepOrganized (config.keep_organized);
00090 }
00091
00092
00093 if (impl_.getNegative() != config.negative)
00094 {
00095 NODELET_DEBUG ("[%s::config_callback] Setting the filter negative flag to: %s.", getName ().c_str (), config.negative ? "true" : "false");
00096
00097 impl_.setNegative(config.negative);
00098 }
00099
00100
00101 if (tf_input_frame_ != config.input_frame)
00102 {
00103 tf_input_frame_ = config.input_frame;
00104 NODELET_DEBUG ("[%s::config_callback] Setting the input TF frame to: %s.", getName ().c_str (), tf_input_frame_.c_str ());
00105 }
00106 if (tf_output_frame_ != config.output_frame)
00107 {
00108 tf_output_frame_ = config.output_frame;
00109 NODELET_DEBUG ("[%s::config_callback] Setting the output TF frame to: %s.", getName ().c_str (), tf_output_frame_.c_str ());
00110 }
00111 }
00112
00113 typedef pcl_ros::CropBox CropBox;
00114 PLUGINLIB_EXPORT_CLASS(CropBox,nodelet::Nodelet);
00115