Go to the documentation of this file.
36 #ifndef JSK_PCL_ROS_UTILS_PLANE_REJECTOR_H_
37 #define JSK_PCL_ROS_UTILS_PLANE_REJECTOR_H_
43 #include <sensor_msgs/PointCloud2.h>
50 #include <dynamic_reconfigure/server.h>
54 #include <jsk_recognition_msgs/PolygonArray.h>
55 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
56 #include <jsk_recognition_msgs/ClusterPointIndices.h>
57 #include "jsk_pcl_ros_utils/PlaneRejectorConfig.h"
60 #include <jsk_topic_tools/time_accumulator.h>
61 #include <jsk_topic_tools/vital_checker.h>
65 #include <jsk_topic_tools/rosparam_utils.h>
67 #include <jsk_topic_tools/connection_based_nodelet.h>
72 class PlaneRejector:
public jsk_topic_tools::ConnectionBasedNodelet
76 jsk_recognition_msgs::ModelCoefficientsArray >
SyncPolicy;
78 jsk_recognition_msgs::ModelCoefficientsArray,
79 jsk_recognition_msgs::ClusterPointIndices
81 typedef jsk_pcl_ros_utils::PlaneRejectorConfig
Config;
85 virtual void reject(
const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
86 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients);
87 virtual void reject(
const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
88 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
89 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& inliers);
virtual void configCallback(Config &config, uint32_t level)
ros::Timer diagnostics_timer_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
virtual void unsubscribe()
jsk_recognition_utils::Counter input_plane_counter_
boost::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
virtual void updateDiagnostics(const ros::TimerEvent &event)
jsk_recognition_utils::SeriesedBoolean::Ptr tf_success_
tf::TransformListener * listener_
jsk_topic_tools::VitalChecker::Ptr vital_checker_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
ros::Publisher coefficients_pub_
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray, jsk_recognition_msgs::ClusterPointIndices > SyncInlierPolicy
jsk_pcl_ros_utils::PlaneRejectorConfig Config
boost::shared_ptr< message_filters::Synchronizer< SyncInlierPolicy > > sync_inlier_
jsk_recognition_utils::Counter passed_plane_counter_
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
ros::Publisher inliers_pub_
virtual void updateDiagnosticsPlaneRejector(diagnostic_updater::DiagnosticStatusWrapper &stat)
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
ros::Publisher polygons_pub_
jsk_recognition_utils::Counter rejected_plane_counter_
Eigen::Vector3d reference_axis_
std::string processing_frame_id_
virtual void reject(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_inliers_
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43