Program Listing for File filter.hpp
↰ Return to documentation for file (include/pcl_ros/filters/filter.hpp
)
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2009, 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: filter.h 35876 2011-02-09 01:04:36Z rusu $
*
*/
#ifndef PCL_ROS__FILTERS__FILTER_HPP_
#define PCL_ROS__FILTERS__FILTER_HPP_
#include <memory>
#include <string>
#include <vector>
#include "pcl_ros/pcl_node.hpp"
namespace pcl_ros
{
namespace sync_policies = message_filters::sync_policies;
class Filter : public PCLNode<sensor_msgs::msg::PointCloud2>
{
public:
typedef sensor_msgs::msg::PointCloud2 PointCloud2;
typedef pcl::IndicesPtr IndicesPtr;
typedef pcl::IndicesConstPtr IndicesConstPtr;
Filter(std::string node_name, const rclcpp::NodeOptions & options);
protected:
void
use_frame_params();
std::vector<std::string> add_common_params();
rclcpp::Subscription<PointCloud2>::SharedPtr sub_input_;
message_filters::Subscriber<PointCloud2> sub_input_filter_;
std::string filter_field_name_;
double filter_limit_min_;
double filter_limit_max_;
bool filter_limit_negative_;
std::string tf_input_frame_;
std::string tf_input_orig_frame_;
std::string tf_output_frame_;
std::mutex mutex_;
virtual void
filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output) = 0;
virtual void
subscribe();
virtual void
unsubscribe();
void
computePublish(const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices);
private:
OnSetParametersCallbackHandle::SharedPtr callback_handle_;
std::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2,
PointIndices>>> sync_input_indices_e_;
std::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2,
PointIndices>>> sync_input_indices_a_;
rcl_interfaces::msg::SetParametersResult
config_callback(const std::vector<rclcpp::Parameter> & params);
void
input_indices_callback(
const PointCloud2::ConstSharedPtr & cloud,
const PointIndices::ConstSharedPtr & indices);
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
} // namespace pcl_ros
#endif // PCL_ROS__FILTERS__FILTER_HPP_