crop_box.cpp
Go to the documentation of this file.
1 /*
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2010, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * $Id: cropbox.cpp
36  *
37  */
38 
41 
43 bool
45 {
46  // Enable the dynamic reconfigure service
47  has_service = true;
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);
51 
52  return (true);
53 }
54 
56 void
57 pcl_ros::CropBox::config_callback (pcl_ros::CropBoxConfig &config, uint32_t /*level*/)
58 {
59  boost::mutex::scoped_lock lock (mutex_);
60 
61  Eigen::Vector4f min_point,max_point;
62  min_point = impl_.getMin();
63  max_point = impl_.getMax();
64 
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;
68 
69  // Check the current values for minimum point
70  if (min_point != new_min_point)
71  {
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));
73  // Set the filter min point if different
74  impl_.setMin(new_min_point);
75  }
76  // Check the current values for the maximum point
77  if (max_point != new_max_point)
78  {
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));
80  // Set the filter max point if different
81  impl_.setMax(new_max_point);
82  }
83 
84  // Check the current value for keep_organized
85  if (impl_.getKeepOrganized () != config.keep_organized)
86  {
87  NODELET_DEBUG ("[%s::config_callback] Setting the filter keep_organized value to: %s.", getName ().c_str (), config.keep_organized ? "true" : "false");
88  // Call the virtual method in the child
89  impl_.setKeepOrganized (config.keep_organized);
90  }
91 
92  // Check the current value for the negative flag
93  if (impl_.getNegative() != config.negative)
94  {
95  NODELET_DEBUG ("[%s::config_callback] Setting the filter negative flag to: %s.", getName ().c_str (), config.negative ? "true" : "false");
96  // Call the virtual method in the child
97  impl_.setNegative(config.negative);
98  }
99 
100  // The following parameters are updated automatically for all PCL_ROS Nodelet Filters as they are inexistent in PCL
101  if (tf_input_frame_ != config.input_frame)
102  {
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 ());
105  }
106  if (tf_output_frame_ != config.output_frame)
107  {
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 ());
110  }
111 }
112 
115 
pcl_ros::CropBox::config_callback
void config_callback(pcl_ros::CropBoxConfig &config, uint32_t level)
Dynamic reconfigure service callback.
Definition: crop_box.cpp:57
crop_box.h
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
pcl_ros::CropBox::child_init
bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
Definition: crop_box.cpp:44
f
f
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
CropBox
pcl_ros::CropBox CropBox
Definition: crop_box.cpp:113
nodelet::Nodelet
class_list_macros.hpp
pcl_ros::CropBox::srv_
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::CropBoxConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition: crop_box.h:61
pcl_ros::CropBox
CropBox is a filter that allows the user to filter all the data inside of a given box.
Definition: crop_box.h:57
ros::NodeHandle
NODELET_DEBUG
#define NODELET_DEBUG(...)


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Fri Jul 12 2024 02:54:40