37 #ifndef JSK_PCL_ROS_NORMAL_DIRECTION_FILTER_H_ 38 #define JSK_PCL_ROS_NORMAL_DIRECTION_FILTER_H_ 41 #include <sensor_msgs/PointCloud2.h> 43 #include "jsk_pcl_ros/NormalDirectionFilterConfig.h" 44 #include <dynamic_reconfigure/server.h> 49 #include <sensor_msgs/Imu.h> 58 typedef NormalDirectionFilterConfig
Config;
60 sensor_msgs::PointCloud2,
68 virtual void filter(
const sensor_msgs::PointCloud2::ConstPtr&
msg);
69 virtual void filter(
const sensor_msgs::PointCloud2::ConstPtr& msg,
70 const sensor_msgs::Imu::ConstPtr& imu_msg);
72 const pcl::PointCloud<pcl::Normal>::Ptr& normal,
73 const Eigen::Vector3f& direction,
74 pcl::PointIndices& indices);
virtual void configCallback(Config &config, uint32_t level)
virtual void filterIndices(const pcl::PointCloud< pcl::Normal >::Ptr &normal, const Eigen::Vector3f &direction, pcl::PointIndices &indices)
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::Imu > SyncPolicy
tf::TransformListener * tf_listener_
message_filters::Subscriber< sensor_msgs::Imu > sub_imu_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::mutex mutex
global mutex.
NormalDirectionFilterConfig Config
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Eigen::Vector3f static_direction_
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &msg)
virtual void unsubscribe()