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" 76 jsk_recognition_msgs::ModelCoefficientsArray >
SyncPolicy;
78 jsk_recognition_msgs::ModelCoefficientsArray,
79 jsk_recognition_msgs::ClusterPointIndices
81 typedef jsk_pcl_ros_utils::PlaneRejectorConfig
Config;
84 virtual void reject(
const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
85 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients);
86 virtual void reject(
const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
87 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
88 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& inliers);
virtual void updateDiagnosticsPlaneRejector(diagnostic_updater::DiagnosticStatusWrapper &stat)
Eigen::Vector3d reference_axis_
jsk_pcl_ros_utils::PlaneRejectorConfig Config
jsk_topic_tools::VitalChecker::Ptr vital_checker_
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray, jsk_recognition_msgs::ClusterPointIndices > SyncInlierPolicy
ros::Publisher polygons_pub_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void updateDiagnostics(const ros::TimerEvent &event)
jsk_recognition_utils::Counter passed_plane_counter_
jsk_recognition_utils::SeriesedBoolean::Ptr tf_success_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_inliers_
virtual void configCallback(Config &config, uint32_t level)
virtual void unsubscribe()
jsk_recognition_utils::Counter rejected_plane_counter_
ros::Publisher coefficients_pub_
std::string processing_frame_id_
boost::shared_ptr< message_filters::Synchronizer< SyncInlierPolicy > > sync_inlier_
boost::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
virtual void reject(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients)
ros::Timer diagnostics_timer_
message_filters::sync_policies::ExactTime< jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
jsk_recognition_utils::Counter input_plane_counter_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
ros::Publisher inliers_pub_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
tf::TransformListener * listener_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_