crop_box.cpp
Go to the documentation of this file.
00001 /*
00002  * 
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2010, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage, Inc. nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  * $Id: cropbox.cpp 
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   // Enable the dynamic reconfigure service
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   // Check the current values for minimum point
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     // Set the filter min point if different
00074     impl_.setMin(new_min_point);
00075   }
00076  // Check the current values for the maximum point
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     // Set the filter max point if different
00081     impl_.setMax(new_max_point);
00082   }
00083 
00084   // Check the current value for keep_organized
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     // Call the virtual method in the child
00089     impl_.setKeepOrganized (config.keep_organized);
00090   }
00091 
00092   // Check the current value for the negative flag
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     // Call the virtual method in the child
00097     impl_.setNegative(config.negative);
00098   }
00099 
00100   // The following parameters are updated automatically for all PCL_ROS Nodelet Filters as they are inexistent in PCL
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 


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu May 5 2016 04:16:43