Go to the documentation of this file.
   42 #ifndef JSK_PCL_ROS_LINE_SEGMENT_COLLECTOR_H_ 
   43 #define JSK_PCL_ROS_LINE_SEGMENT_COLLECTOR_H_ 
   45 #include <jsk_topic_tools/diagnostic_nodelet.h> 
   46 #include <jsk_recognition_msgs/ClusterPointIndices.h> 
   47 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 
   48 #include <sensor_msgs/JointState.h> 
   50 #include <jsk_topic_tools/time_accumulator.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> 
   60   class LineSegmentCluster
 
   72     virtual pcl::PointCloud<pcl::PointXYZ>::Ptr 
getPoints();
 
   73     virtual pcl::PointCloud<pcl::PointXYZ>::Ptr 
getRawPoints();
 
   79     pcl::PointCloud<pcl::PointXYZ>::Ptr 
points_;
 
   86   class TimeStampedVector: 
public std::vector<T>
 
   89     typedef typename std::vector<T>::iterator 
iterator;
 
   93            it != std::vector<T>::end();) {
 
  106   class LineSegmentCollector: 
public jsk_topic_tools::DiagnosticNodelet
 
  112       sensor_msgs::PointCloud2,
 
  113       jsk_recognition_msgs::ClusterPointIndices,
 
  114       jsk_recognition_msgs::ModelCoefficientsArray> 
SyncPolicy;
 
  118     typedef jsk_pcl_ros::LineSegmentCollectorConfig 
Config;
 
  125                                     std::vector<LineSegment::Ptr> new_segments);
 
  127       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
 
  128       const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
 
  129       const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg);
 
  133       const jsk_recognition_msgs::TimeRange::ConstPtr& trigger);
 
  137       const std_msgs::Header& 
header,
 
  138       const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
 
  139       const std::vector<pcl::PointIndices::Ptr>& connected_indices);
 
  144       pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
 
  145       std::vector<pcl::ModelCoefficients::Ptr> all_coefficients,
 
  146       std::vector<pcl::PointIndices::Ptr> all_indices);
 
  177     jsk_recognition_msgs::TimeRange::ConstPtr 
time_range_;
 
  
virtual void configCallback(Config &config, uint32_t level)
ros::Subscriber sub_trigger_
void removeBefore(const ros::Time &stamp)
virtual void addLineSegmentEWMA(LineSegment::Ptr segment, const double tau)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
virtual Eigen::Vector3f getDelta()
TimeStampedVector< LineSegment::Ptr > segments_buffer_
virtual LineSegmentCluster::Ptr lookupNearestSegment(LineSegment::Ptr segment)
TimeStampedVector< jsk_recognition_msgs::ClusterPointIndices::ConstPtr > indices_buffer_
virtual pcl::PointCloud< pcl::PointXYZ >::Ptr getRawPoints()
TimeStampedVector< jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr > coefficients_buffer_
virtual void unsubscribe()
double outlier_threshold_
virtual void cleanupBuffers(const ros::Time &stamp)
std::string fixed_frame_id_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
std::vector< LineSegment::Ptr > segments_
virtual void collectFromBuffers(const std_msgs::Header &header, std::vector< LineSegment::Ptr > new_segments)
jsk_recognition_msgs::TimeRange::ConstPtr time_range_
boost::shared_ptr< LineSegmentCluster > Ptr
ros::Publisher pub_polygons_
ros::Publisher pub_point_cloud_
virtual void removeBefore(const ros::Time &stamp)
double segment_connect_normal_threshold_
virtual void collect(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
jsk_topic_tools::TimeAccumulator connect_ac_
boost::shared_ptr< LineSegment > Ptr
virtual void publishResult(const std_msgs::Header &header, pcl::PointCloud< pcl::PointXYZ >::Ptr cloud, std::vector< pcl::ModelCoefficients::Ptr > all_coefficients, std::vector< pcl::PointIndices::Ptr > all_indices)
std::vector< LineSegmentCluster::Ptr > segment_clusters_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
ros::Publisher pub_inliers_
std::vector< T >::iterator iterator
TimeStampedVector< sensor_msgs::PointCloud2::ConstPtr > pointclouds_buffer_
pcl::PointCloud< pcl::PointXYZ >::Ptr points_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
ros::Publisher debug_pub_inliers_before_plane_
jsk_pcl_ros::LineSegmentCollectorConfig Config
ros::Publisher pub_coefficients_
virtual pcl::PointCloud< pcl::PointXYZ >::Ptr getPoints()
boost::mutex mutex
global mutex.
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual ~LineSegmentCollector()
pcl::PointCloud< pcl::PointXYZ >::Ptr raw_points_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
virtual void triggerCallback(const jsk_recognition_msgs::TimeRange::ConstPtr &trigger)
virtual void publishBeforePlaneSegmentation(const std_msgs::Header &header, const pcl::PointCloud< pcl::PointXYZ >::Ptr cloud, const std::vector< pcl::PointIndices::Ptr > &connected_indices)
virtual ~LineSegmentCluster()
jsk_pcl_ros
Author(s): Yohei Kakiuchi 
autogenerated on Fri May 16 2025 03:12:11