merge pull request #60
This commit is contained in:
parent
aac231674a
commit
08e83a67bf
@ -53,6 +53,7 @@ generate_dynamic_reconfigure_options(
|
|||||||
cfg/SegmentDifferences.cfg
|
cfg/SegmentDifferences.cfg
|
||||||
cfg/StatisticalOutlierRemoval.cfg
|
cfg/StatisticalOutlierRemoval.cfg
|
||||||
cfg/VoxelGrid.cfg
|
cfg/VoxelGrid.cfg
|
||||||
|
cfg/CropBox.cfg
|
||||||
)
|
)
|
||||||
|
|
||||||
## Declare the catkin package
|
## Declare the catkin package
|
||||||
@ -125,6 +126,7 @@ add_library(pcl_ros_filters
|
|||||||
src/pcl_ros/filters/radius_outlier_removal.cpp
|
src/pcl_ros/filters/radius_outlier_removal.cpp
|
||||||
src/pcl_ros/filters/statistical_outlier_removal.cpp
|
src/pcl_ros/filters/statistical_outlier_removal.cpp
|
||||||
src/pcl_ros/filters/voxel_grid.cpp
|
src/pcl_ros/filters/voxel_grid.cpp
|
||||||
|
src/pcl_ros/filters/crop_box.cpp
|
||||||
)
|
)
|
||||||
target_link_libraries(pcl_ros_filters pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
|
target_link_libraries(pcl_ros_filters pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
|
||||||
add_dependencies(pcl_ros_filters ${PROJECT_NAME}_gencfg)
|
add_dependencies(pcl_ros_filters ${PROJECT_NAME}_gencfg)
|
||||||
|
|||||||
25
pcl_ros/cfg/CropBox.cfg
Executable file
25
pcl_ros/cfg/CropBox.cfg
Executable file
@ -0,0 +1,25 @@
|
|||||||
|
#! /usr/bin/env python
|
||||||
|
|
||||||
|
# set up parameters that we care about
|
||||||
|
PACKAGE = 'pcl_ros'
|
||||||
|
|
||||||
|
import os
|
||||||
|
import sys
|
||||||
|
sys.path.insert(0, os.path.dirname(__file__))
|
||||||
|
|
||||||
|
from dynamic_reconfigure.parameter_generator_catkin import *
|
||||||
|
|
||||||
|
gen = ParameterGenerator ()
|
||||||
|
# def add (self, name, paramtype, level, description, default = None, min = None, max = None, edit_method = ""):
|
||||||
|
gen.add ("min_x", double_t, 0, "X coordinate of the minimum point of the box.", -1, -5, 5)
|
||||||
|
gen.add ("max_x", double_t, 0, "X coordinate of the maximum point of the box.", 1, -5, 5)
|
||||||
|
gen.add ("min_y", double_t, 0, "Y coordinate of the minimum point of the box.", -1, -5, 5)
|
||||||
|
gen.add ("max_y", double_t, 0, "Y coordinate of the maximum point of the box.", 1, -5, 5)
|
||||||
|
gen.add ("min_z", double_t, 0, "Z coordinate of the minimum point of the box.", -1, -5, 5)
|
||||||
|
gen.add ("max_z", double_t, 0, "Z coordinate of the maximum point of the box.", 1, -5, 5)
|
||||||
|
gen.add ("keep_organized", bool_t, 0, "Set whether the filtered points should be kept and set to NaN, or removed from the PointCloud, thus potentially breaking its organized structure.", False)
|
||||||
|
gen.add ("negative", bool_t, 0, "If True the box will be empty Else the remaining points will be the ones in the box", False)
|
||||||
|
gen.add ("input_frame", str_t, 0, "The input TF frame the data should be transformed into before processing, if input.header.frame_id is different.", "")
|
||||||
|
gen.add ("output_frame", str_t, 0, "The output TF frame the data should be transformed into after processing, if input.header.frame_id is different.", "")
|
||||||
|
|
||||||
|
exit (gen.generate (PACKAGE, "pcl_ros", "CropBox"))
|
||||||
104
pcl_ros/include/pcl_ros/filters/crop_box.h
Normal file
104
pcl_ros/include/pcl_ros/filters/crop_box.h
Normal file
@ -0,0 +1,104 @@
|
|||||||
|
/*
|
||||||
|
*
|
||||||
|
* Software License Agreement (BSD License)
|
||||||
|
*
|
||||||
|
* Copyright (c) 2010, Willow Garage, Inc.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* * Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* * Redistributions in binary form must reproduce the above
|
||||||
|
* copyright notice, this list of conditions and the following
|
||||||
|
* disclaimer in the documentation and/or other materials provided
|
||||||
|
* with the distribution.
|
||||||
|
* * Neither the name of Willow Garage, Inc. nor the names of its
|
||||||
|
* contributors may be used to endorse or promote products derived
|
||||||
|
* from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||||
|
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
* $Id: cropbox.cpp
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef PCL_ROS_FILTERS_CROPBOX_H_
|
||||||
|
#define PCL_ROS_FILTERS_CROPBOX_H_
|
||||||
|
|
||||||
|
// PCL includes
|
||||||
|
#include <pcl/filters/crop_box.h>
|
||||||
|
#include "pcl_ros/filters/filter.h"
|
||||||
|
|
||||||
|
// Dynamic reconfigure
|
||||||
|
#include "pcl_ros/CropBoxConfig.h"
|
||||||
|
|
||||||
|
namespace pcl_ros
|
||||||
|
{
|
||||||
|
/** \brief @b CropBox is a filter that allows the user to filter all the data inside of a given box.
|
||||||
|
*
|
||||||
|
* \author Radu Bogdan Rusu
|
||||||
|
* \author Justin Rosen
|
||||||
|
* \author Marti Morta Garriga
|
||||||
|
*/
|
||||||
|
class CropBox : public Filter
|
||||||
|
{
|
||||||
|
protected:
|
||||||
|
/** \brief Pointer to a dynamic reconfigure service. */
|
||||||
|
boost::shared_ptr <dynamic_reconfigure::Server<pcl_ros::CropBoxConfig> > srv_; // TODO
|
||||||
|
|
||||||
|
/** \brief Call the actual filter.
|
||||||
|
* \param input the input point cloud dataset
|
||||||
|
* \param indices the input set of indices to use from \a input
|
||||||
|
* \param output the resultant filtered dataset
|
||||||
|
*/
|
||||||
|
inline void
|
||||||
|
filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
|
||||||
|
PointCloud2 &output)
|
||||||
|
{
|
||||||
|
boost::mutex::scoped_lock lock (mutex_);
|
||||||
|
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
|
||||||
|
pcl_conversions::toPCL (*(input), *(pcl_input));
|
||||||
|
impl_.setInputCloud (pcl_input);
|
||||||
|
impl_.setIndices (indices);
|
||||||
|
pcl::PCLPointCloud2 pcl_output;
|
||||||
|
impl_.filter (pcl_output);
|
||||||
|
pcl_conversions::moveFromPCL(pcl_output, output);
|
||||||
|
}
|
||||||
|
|
||||||
|
/** \brief Child initialization routine.
|
||||||
|
* \param nh ROS node handle
|
||||||
|
* \param has_service set to true if the child has a Dynamic Reconfigure service
|
||||||
|
*/
|
||||||
|
bool
|
||||||
|
child_init (ros::NodeHandle &nh, bool &has_service);
|
||||||
|
|
||||||
|
/** \brief Dynamic reconfigure service callback.
|
||||||
|
* \param config the dynamic reconfigure CropBoxConfig object
|
||||||
|
* \param level the dynamic reconfigure level
|
||||||
|
*/
|
||||||
|
void
|
||||||
|
config_callback (pcl_ros::CropBoxConfig &config, uint32_t level);
|
||||||
|
|
||||||
|
private:
|
||||||
|
/** \brief The PCL filter implementation used. */
|
||||||
|
pcl::CropBox<pcl::PCLPointCloud2> impl_;
|
||||||
|
public:
|
||||||
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif //#ifndef PCL_ROS_FILTERS_CROPBOX_H_
|
||||||
@ -1,3 +1,42 @@
|
|||||||
|
<<<<<<< HEAD
|
||||||
|
=======
|
||||||
|
|
||||||
|
<!-- PCL Features library component -->
|
||||||
|
<library path="lib/libpcl_ros_features">
|
||||||
|
<class name="pcl/BoundaryEstimation" type="BoundaryEstimation" base_class_type="nodelet::Nodelet">
|
||||||
|
<description>
|
||||||
|
BoundaryEstimation estimates whether a set of points is lying on surface boundaries using an angle criterion. The
|
||||||
|
code makes use of the estimated surface normals at each point in the input data set.
|
||||||
|
</description>
|
||||||
|
</class>
|
||||||
|
|
||||||
|
<class name="pcl/FPFHEstimation" type="FPFHEstimation" base_class_type="nodelet::Nodelet">
|
||||||
|
<description>
|
||||||
|
FPFHEstimation estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset
|
||||||
|
containing points and normals.
|
||||||
|
</description>
|
||||||
|
</class>
|
||||||
|
|
||||||
|
<class name="pcl/FPFHEstimationOMP" type="FPFHEstimationOMP" base_class_type="nodelet::Nodelet">
|
||||||
|
<description>
|
||||||
|
FPFHEstimationOMP estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud dataset
|
||||||
|
containing points and normals, in parallel, using the OpenMP standard.
|
||||||
|
</description>
|
||||||
|
</class>
|
||||||
|
|
||||||
|
<class name="pcl/MomentInvariantsEstimation" type="MomentInvariantsEstimation" base_class_type="nodelet::Nodelet">
|
||||||
|
<description>
|
||||||
|
MomentInvariantsEstimation estimates the 3 moment invariants (j1, j2, j3) at each 3D point.
|
||||||
|
</description>
|
||||||
|
</class>
|
||||||
|
|
||||||
|
<class name="pcl/NormalEstimationOMP" type="NormalEstimationOMP" base_class_type="nodelet::Nodelet">
|
||||||
|
<description>
|
||||||
|
NormalEstimationOMP estimates local surface properties at each 3D point, such as surface normals and curvatures,
|
||||||
|
in parallel, using the OpenMP standard.
|
||||||
|
</description>
|
||||||
|
</class>
|
||||||
|
>>>>>>> c3c0d30... Merge pull request #60 from martimorta/hydro-devel
|
||||||
|
|
||||||
|
|
||||||
<!-- PCL IO library component -->
|
<!-- PCL IO library component -->
|
||||||
@ -81,6 +120,13 @@
|
|||||||
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data.
|
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data.
|
||||||
</description>
|
</description>
|
||||||
</class>
|
</class>
|
||||||
|
|
||||||
|
<class name="pcl/CropBox" type="CropBox" base_class_type="nodelet::Nodelet">
|
||||||
|
<description>
|
||||||
|
CropBox is a filter that allows the user to filter all the data inside of a given box.
|
||||||
|
</description>
|
||||||
|
</class>
|
||||||
</library>
|
</library>
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
115
pcl_ros/src/pcl_ros/filters/crop_box.cpp
Normal file
115
pcl_ros/src/pcl_ros/filters/crop_box.cpp
Normal file
@ -0,0 +1,115 @@
|
|||||||
|
/*
|
||||||
|
*
|
||||||
|
* Software License Agreement (BSD License)
|
||||||
|
*
|
||||||
|
* Copyright (c) 2010, Willow Garage, Inc.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions
|
||||||
|
* are met:
|
||||||
|
*
|
||||||
|
* * Redistributions of source code must retain the above copyright
|
||||||
|
* notice, this list of conditions and the following disclaimer.
|
||||||
|
* * Redistributions in binary form must reproduce the above
|
||||||
|
* copyright notice, this list of conditions and the following
|
||||||
|
* disclaimer in the documentation and/or other materials provided
|
||||||
|
* with the distribution.
|
||||||
|
* * Neither the name of Willow Garage, Inc. nor the names of its
|
||||||
|
* contributors may be used to endorse or promote products derived
|
||||||
|
* from this software without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||||
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||||
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||||
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||||
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||||
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||||
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||||
|
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||||
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||||
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||||
|
* POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*
|
||||||
|
* $Id: cropbox.cpp
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <pluginlib/class_list_macros.h>
|
||||||
|
#include "pcl_ros/filters/crop_box.h"
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
bool
|
||||||
|
pcl_ros::CropBox::child_init (ros::NodeHandle &nh, bool &has_service)
|
||||||
|
{
|
||||||
|
// Enable the dynamic reconfigure service
|
||||||
|
has_service = true;
|
||||||
|
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::CropBoxConfig> > (nh);
|
||||||
|
dynamic_reconfigure::Server<pcl_ros::CropBoxConfig>::CallbackType f = boost::bind (&CropBox::config_callback, this, _1, _2);
|
||||||
|
srv_->setCallback (f);
|
||||||
|
|
||||||
|
return (true);
|
||||||
|
}
|
||||||
|
|
||||||
|
//////////////////////////////////////////////////////////////////////////////////////////////
|
||||||
|
void
|
||||||
|
pcl_ros::CropBox::config_callback (pcl_ros::CropBoxConfig &config, uint32_t level)
|
||||||
|
{
|
||||||
|
boost::mutex::scoped_lock lock (mutex_);
|
||||||
|
|
||||||
|
Eigen::Vector4f min_point,max_point;
|
||||||
|
min_point = impl_.getMin();
|
||||||
|
max_point = impl_.getMax();
|
||||||
|
|
||||||
|
Eigen::Vector4f new_min_point, new_max_point;
|
||||||
|
new_min_point << config.min_x, config.min_y, config.min_z, 0.0;
|
||||||
|
new_max_point << config.max_x, config.max_y, config.max_z, 0.0;
|
||||||
|
|
||||||
|
// Check the current values for minimum point
|
||||||
|
if (min_point != new_min_point)
|
||||||
|
{
|
||||||
|
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));
|
||||||
|
// Set the filter min point if different
|
||||||
|
impl_.setMin(new_min_point);
|
||||||
|
}
|
||||||
|
// Check the current values for the maximum point
|
||||||
|
if (max_point != new_max_point)
|
||||||
|
{
|
||||||
|
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));
|
||||||
|
// Set the filter max point if different
|
||||||
|
impl_.setMax(new_max_point);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Check the current value for keep_organized
|
||||||
|
if (impl_.getKeepOrganized () != config.keep_organized)
|
||||||
|
{
|
||||||
|
NODELET_DEBUG ("[%s::config_callback] Setting the filter keep_organized value to: %s.", getName ().c_str (), config.keep_organized ? "true" : "false");
|
||||||
|
// Call the virtual method in the child
|
||||||
|
impl_.setKeepOrganized (config.keep_organized);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Check the current value for the negative flag
|
||||||
|
if (impl_.getNegative() != config.negative)
|
||||||
|
{
|
||||||
|
NODELET_DEBUG ("[%s::config_callback] Setting the filter negative flag to: %s.", getName ().c_str (), config.negative ? "true" : "false");
|
||||||
|
// Call the virtual method in the child
|
||||||
|
impl_.setNegative(config.negative);
|
||||||
|
}
|
||||||
|
|
||||||
|
// The following parameters are updated automatically for all PCL_ROS Nodelet Filters as they are inexistent in PCL
|
||||||
|
if (tf_input_frame_ != config.input_frame)
|
||||||
|
{
|
||||||
|
tf_input_frame_ = config.input_frame;
|
||||||
|
NODELET_DEBUG ("[%s::config_callback] Setting the input TF frame to: %s.", getName ().c_str (), tf_input_frame_.c_str ());
|
||||||
|
}
|
||||||
|
if (tf_output_frame_ != config.output_frame)
|
||||||
|
{
|
||||||
|
tf_output_frame_ = config.output_frame;
|
||||||
|
NODELET_DEBUG ("[%s::config_callback] Setting the output TF frame to: %s.", getName ().c_str (), tf_output_frame_.c_str ());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
typedef pcl_ros::CropBox CropBox;
|
||||||
|
PLUGINLIB_EXPORT_CLASS(CropBox,nodelet::Nodelet);
|
||||||
|
|
||||||
Loading…
x
Reference in New Issue
Block a user