Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef JSK_PCL_ROS_CLUSTER_POINT_INDICES_DECOMPOSER_H_
00037 #define JSK_PCL_ROS_CLUSTER_POINT_INDICES_DECOMPOSER_H_
00038
00039 #include <ros/ros.h>
00040 #include <ros/names.h>
00041
00042 #include "jsk_recognition_msgs/ClusterPointIndices.h"
00043 #include "jsk_recognition_msgs/PolygonArray.h"
00044 #include "jsk_recognition_msgs/ModelCoefficientsArray.h"
00045
00046 #include "sensor_msgs/PointCloud2.h"
00047 #include <pcl_ros/pcl_nodelet.h>
00048 #include <message_filters/subscriber.h>
00049 #include <message_filters/time_synchronizer.h>
00050 #include <message_filters/synchronizer.h>
00051 #include <pcl/point_types.h>
00052 #include <pcl/impl/point_types.hpp>
00053 #include <tf/transform_broadcaster.h>
00054 #include <std_msgs/ColorRGBA.h>
00055 #include <jsk_recognition_msgs/BoundingBoxArray.h>
00056
00057 #include <diagnostic_updater/diagnostic_updater.h>
00058 #include <diagnostic_updater/publisher.h>
00059 #include "jsk_pcl_ros/pcl_util.h"
00060 #include <jsk_topic_tools/vital_checker.h>
00061 #include "jsk_topic_tools/diagnostic_nodelet.h"
00062
00063 namespace jsk_pcl_ros
00064 {
00065 class ClusterPointIndicesDecomposer: public jsk_topic_tools::DiagnosticNodelet
00066 {
00067 public:
00068 ClusterPointIndicesDecomposer(): DiagnosticNodelet("ClusterPointIndicesDecomposer") { }
00069 typedef message_filters::sync_policies::ExactTime<
00070 sensor_msgs::PointCloud2,
00071 jsk_recognition_msgs::ClusterPointIndices > SyncPolicy;
00072 typedef message_filters::sync_policies::ExactTime<
00073 sensor_msgs::PointCloud2,
00074 jsk_recognition_msgs::ClusterPointIndices,
00075 jsk_recognition_msgs::PolygonArray,
00076 jsk_recognition_msgs::ModelCoefficientsArray> SyncAlignPolicy;
00077 virtual void onInit();
00078 virtual void extract(const sensor_msgs::PointCloud2ConstPtr &point,
00079 const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices,
00080 const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
00081 const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients);
00082 virtual void extract(const sensor_msgs::PointCloud2ConstPtr &point,
00083 const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices);
00084 virtual void sortIndicesOrder(pcl::PointCloud<pcl::PointXYZ>::Ptr input,
00085 std::vector<pcl::IndicesPtr> indices_array,
00086 std::vector<pcl::IndicesPtr> &output_array);
00087 protected:
00088 void addToDebugPointCloud
00089 (const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
00090 size_t i,
00091 pcl::PointCloud<pcl::PointXYZRGB>& debug_output);
00092
00093 virtual bool computeBoundingBox
00094 (const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
00095 const std_msgs::Header header,
00096 const Eigen::Vector4f center,
00097 const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
00098 const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
00099 jsk_recognition_msgs::BoundingBox& bounding_box);
00100
00101
00102 virtual int findNearestPlane(const Eigen::Vector4f& center,
00103 const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
00104 const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients);
00105
00106 virtual void updateDiagnostic(
00107 diagnostic_updater::DiagnosticStatusWrapper &stat);
00108 virtual void allocatePublishers(size_t num);
00109
00110 virtual void subscribe();
00111 virtual void unsubscribe();
00112
00113 static uint32_t colorRGBAToUInt32(std_msgs::ColorRGBA c)
00114 {
00115 uint8_t r, g, b;
00116 r = (uint8_t)(c.r * 255);
00117 g = (uint8_t)(c.g * 255);
00118 b = (uint8_t)(c.b * 255);
00119 return ((uint32_t)r<<16 | (uint32_t)g<<8 | (uint32_t)b);
00120 }
00121
00122 message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00123 message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_target_;
00124 message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> sub_polygons_;
00125 message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> sub_coefficients_;
00126 boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00127 boost::shared_ptr<message_filters::Synchronizer<SyncAlignPolicy> >sync_align_;
00128 std::vector<ros::Publisher> publishers_;
00129 ros::Publisher pc_pub_, box_pub_;
00130 tf::TransformBroadcaster br_;
00131 std::string tf_prefix_;
00132
00133 bool force_to_flip_z_axis_;
00134 bool publish_clouds_;
00135 bool publish_tf_;
00136 bool align_boxes_;
00137 bool use_pca_;
00138
00139 Counter cluster_counter_;
00140
00141 };
00142
00143 }
00144
00145 #endif