42 #ifndef JSK_PCL_ROS_LINE_SEGMENT_COLLECTOR_H_ 43 #define JSK_PCL_ROS_LINE_SEGMENT_COLLECTOR_H_ 46 #include <jsk_recognition_msgs/ClusterPointIndices.h> 47 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 48 #include <sensor_msgs/JointState.h> 51 #include <jsk_pcl_ros/LineSegmentCollectorConfig.h> 52 #include <dynamic_reconfigure/server.h> 54 #include <jsk_recognition_msgs/PolygonArray.h> 55 #include <jsk_recognition_msgs/TimeRange.h> 72 virtual pcl::PointCloud<pcl::PointXYZ>::Ptr
getPoints();
73 virtual pcl::PointCloud<pcl::PointXYZ>::Ptr
getRawPoints();
79 pcl::PointCloud<pcl::PointXYZ>::Ptr
points_;
89 typedef typename std::vector<T>::iterator
iterator;
92 for (iterator it = std::vector<T>::begin();
93 it != std::vector<T>::end();) {
111 sensor_msgs::PointCloud2,
112 jsk_recognition_msgs::ClusterPointIndices,
115 ROTATION_SPINDLE, ROTATION_TILT, ROTATION_TILT_TWO_WAY
117 typedef jsk_pcl_ros::LineSegmentCollectorConfig
Config;
122 virtual void onInit();
123 virtual void collectFromBuffers(
const std_msgs::Header&
header,
124 std::vector<LineSegment::Ptr> new_segments);
126 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
127 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
128 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg);
130 virtual void unsubscribe();
131 virtual void triggerCallback(
132 const jsk_recognition_msgs::TimeRange::ConstPtr& trigger);
133 virtual void cleanupBuffers(
135 virtual void publishBeforePlaneSegmentation(
136 const std_msgs::Header&
header,
137 const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
138 const std::vector<pcl::PointIndices::Ptr>& connected_indices);
141 virtual void publishResult(
142 const std_msgs::Header&
header,
143 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
144 std::vector<pcl::ModelCoefficients::Ptr> all_coefficients,
145 std::vector<pcl::PointIndices::Ptr> all_indices);
146 virtual void configCallback(Config &config, uint32_t level);
void removeBefore(const ros::Time &stamp)
ros::Publisher pub_point_cloud_
virtual pcl::PointCloud< pcl::PointXYZ >::Ptr getRawPoints()
virtual void addLineSegmentEWMA(LineSegment::Ptr segment, const double tau)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
virtual void removeBefore(const ros::Time &stamp)
virtual Eigen::Vector3f getDelta()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
std::vector< LineSegment::Ptr > segments_
double segment_connect_normal_threshold_
jsk_pcl_ros::LineSegmentCollectorConfig Config
ros::Subscriber sub_trigger_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
TimeStampedVector< jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr > coefficients_buffer_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
jsk_topic_tools::TimeAccumulator connect_ac_
std::vector< LineSegmentCluster::Ptr > segment_clusters_
pcl::PointCloud< pcl::PointXYZ >::Ptr points_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
double outlier_threshold_
TimeStampedVector< jsk_recognition_msgs::ClusterPointIndices::ConstPtr > indices_buffer_
ros::Publisher pub_coefficients_
jsk_recognition_msgs::TimeRange::ConstPtr time_range_
ros::Publisher pub_polygons_
boost::mutex mutex
global mutex.
virtual ~LineSegmentCluster()
std::vector< T >::iterator iterator
TimeStampedVector< sensor_msgs::PointCloud2::ConstPtr > pointclouds_buffer_
ros::Publisher debug_pub_inliers_before_plane_
TimeStampedVector< LineSegment::Ptr > segments_buffer_
ros::Publisher pub_inliers_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
boost::shared_ptr< LineSegmentCluster > Ptr
pcl::PointCloud< pcl::PointXYZ >::Ptr raw_points_
std::string fixed_frame_id_
virtual pcl::PointCloud< pcl::PointXYZ >::Ptr getPoints()