Go to the documentation of this file.
37 #ifndef JSK_PCL_ROS_UTILS_PLANE_CONCATENATOR_H_
38 #define JSK_PCL_ROS_UTILS_PLANE_CONCATENATOR_H_
40 #include <jsk_recognition_msgs/PolygonArray.h>
41 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
42 #include <jsk_recognition_msgs/ClusterPointIndices.h>
44 #include <jsk_pcl_ros_utils/PlaneConcatenatorConfig.h>
45 #include <dynamic_reconfigure/server.h>
46 #include <jsk_topic_tools/diagnostic_nodelet.h>
55 class PlaneConcatenator:
public jsk_topic_tools::DiagnosticNodelet
59 typedef PlaneConcatenatorConfig
Config;
60 typedef pcl::PointXYZRGB
PointT;
62 sensor_msgs::PointCloud2,
63 jsk_recognition_msgs::ClusterPointIndices,
64 jsk_recognition_msgs::PolygonArray,
65 jsk_recognition_msgs::ModelCoefficientsArray
77 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
78 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
79 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_array_msg,
80 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_array_msg);
83 pcl::KdTreeFLANN<PointT>& kdtree,
84 pcl::PointCloud<PointT>::Ptr
cloud,
86 virtual pcl::ModelCoefficients::Ptr
refinement(
87 pcl::PointCloud<PointT>::Ptr
cloud,
88 pcl::PointIndices::Ptr indices,
89 pcl::ModelCoefficients::Ptr original_coefficients);
91 const pcl::ModelCoefficients::Ptr& coefficients,
92 pcl::ModelCoefficients::Ptr& output_coefficients);
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
ros::Publisher pub_indices_
double connect_distance_threshold_
double connect_angular_threshold_
virtual void unsubscribe()
virtual void configCallback(Config &config, uint32_t level)
double connect_perpendicular_distance_threshold_
ros::Publisher pub_coefficients_
boost::shared_ptr< PlaneConcatenator > Ptr
virtual pcl::ModelCoefficients::Ptr refinement(pcl::PointCloud< PointT >::Ptr cloud, pcl::PointIndices::Ptr indices, pcl::ModelCoefficients::Ptr original_coefficients)
ros::Publisher pub_polygon_
virtual void concatenate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_array_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_array_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void forceToDirectOrigin(const pcl::ModelCoefficients::Ptr &coefficients, pcl::ModelCoefficients::Ptr &output_coefficients)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
double ransac_refinement_eps_distance_
virtual ~PlaneConcatenator()
int ransac_refinement_max_iteration_
double ransac_refinement_eps_angle_
PlaneConcatenatorConfig Config
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
double ransac_refinement_outlier_threshold_
virtual bool isNearPointCloud(pcl::KdTreeFLANN< PointT > &kdtree, pcl::PointCloud< PointT >::Ptr cloud, jsk_recognition_utils::Plane::Ptr target_plane)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43