cluster_point_indices_decomposer.h
Go to the documentation of this file.
00001 // -*- mode: C++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2013, Ryohei Ueda and JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
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 #include "jsk_recognition_utils/tf_listener_singleton.h"
00046 
00047 #include "sensor_msgs/PointCloud2.h"
00048 #include <dynamic_reconfigure/server.h>
00049 #include <pcl_ros/pcl_nodelet.h>
00050 #include <message_filters/subscriber.h>
00051 #include <message_filters/time_synchronizer.h>
00052 #include <message_filters/synchronizer.h>
00053 #include <pcl/point_types.h>
00054 #include <pcl/impl/point_types.hpp>
00055 #include <tf/transform_broadcaster.h>
00056 #include <std_msgs/ColorRGBA.h>
00057 #include <jsk_recognition_msgs/BoundingBoxArray.h>
00058 
00059 #include <diagnostic_updater/diagnostic_updater.h>
00060 #include <diagnostic_updater/publisher.h>
00061 #include "jsk_recognition_utils/pcl_util.h"
00062 #include <jsk_topic_tools/vital_checker.h>
00063 #include "jsk_topic_tools/diagnostic_nodelet.h"
00064 #include "jsk_pcl_ros/ClusterPointIndicesDecomposerConfig.h"
00065 
00066 namespace jsk_pcl_ros
00067 {
00068   class ClusterPointIndicesDecomposer: public jsk_topic_tools::DiagnosticNodelet
00069   {
00070   public:
00071     ClusterPointIndicesDecomposer(): DiagnosticNodelet("ClusterPointIndicesDecomposer") { }
00072     typedef jsk_pcl_ros::ClusterPointIndicesDecomposerConfig Config;
00073     typedef message_filters::sync_policies::ExactTime<
00074     sensor_msgs::PointCloud2,
00075     jsk_recognition_msgs::ClusterPointIndices > SyncPolicy;
00076     typedef message_filters::sync_policies::ApproximateTime<
00077     sensor_msgs::PointCloud2,
00078     jsk_recognition_msgs::ClusterPointIndices > ApproximateSyncPolicy;
00079     typedef message_filters::sync_policies::ExactTime<
00080       sensor_msgs::PointCloud2,
00081       jsk_recognition_msgs::ClusterPointIndices,
00082       jsk_recognition_msgs::PolygonArray,
00083       jsk_recognition_msgs::ModelCoefficientsArray> SyncAlignPolicy;
00084     virtual void onInit();
00085     virtual void extract(const sensor_msgs::PointCloud2ConstPtr &point,
00086                          const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices,
00087                          const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
00088                          const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients);
00089     virtual void extract(const sensor_msgs::PointCloud2ConstPtr &point,
00090                          const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices);
00091     virtual void sortIndicesOrder(const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
00092                                   const std::vector<pcl::IndicesPtr> indices_array,
00093                                   std::vector<size_t>* argsort);
00094     void sortIndicesOrderByIndices(const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
00095                                    const std::vector<pcl::IndicesPtr> indices_array,
00096                                    std::vector<size_t>* argsort);
00097     void sortIndicesOrderByZAxis(const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
00098                                  const std::vector<pcl::IndicesPtr> indices_array,
00099                                  std::vector<size_t>* argsort);
00100     void sortIndicesOrderByCloudSize(const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
00101                                      const std::vector<pcl::IndicesPtr> indices_array,
00102                                      std::vector<size_t>* argsort);
00103   protected:
00104     boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_;
00105     boost::mutex mutex_;
00106 
00107     void addToDebugPointCloud
00108     (const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
00109      size_t i,
00110      pcl::PointCloud<pcl::PointXYZRGB>& debug_output);
00111     
00112     virtual bool computeCenterAndBoundingBox
00113     (const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
00114      const std_msgs::Header header,
00115      const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
00116      const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
00117      geometry_msgs::Pose& center_pose_msg,
00118      jsk_recognition_msgs::BoundingBox& bounding_box);
00119 
00120     virtual bool transformPointCloudToAlignWithPlane(
00121       const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
00122       pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud_transformed,
00123       const Eigen::Vector4f center,
00124       const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
00125       const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
00126       Eigen::Matrix4f& m4,
00127       Eigen::Quaternionf& q);
00128     
00129     virtual int findNearestPlane(const Eigen::Vector4f& center,
00130                                  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
00131                                  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients);
00132 
00133     virtual void configCallback (Config &config, uint32_t level);
00134     virtual void updateDiagnostic(
00135       diagnostic_updater::DiagnosticStatusWrapper &stat);
00136     virtual void allocatePublishers(size_t num);
00137     virtual void publishNegativeIndices(
00138       const sensor_msgs::PointCloud2ConstPtr &input,
00139       const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input);
00140     virtual void subscribe();
00141     virtual void unsubscribe();
00142     
00143     static uint32_t colorRGBAToUInt32(std_msgs::ColorRGBA c)
00144     {
00145         uint8_t r, g, b;
00146         r = (uint8_t)(c.r * 255);
00147         g = (uint8_t)(c.g * 255);
00148         b = (uint8_t)(c.b * 255);
00149         return ((uint32_t)r<<16 | (uint32_t)g<<8 | (uint32_t)b);
00150     }
00151 
00152     message_filters::Subscriber<sensor_msgs::PointCloud2> sub_input_;
00153     message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> sub_target_;
00154     message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> sub_polygons_;
00155     message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> sub_coefficients_;
00156     boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> >sync_;
00157     boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> >async_;
00158     boost::shared_ptr<message_filters::Synchronizer<SyncAlignPolicy> >sync_align_;
00159     std::vector<ros::Publisher> publishers_;
00160     ros::Publisher pc_pub_, box_pub_, mask_pub_, label_pub_, centers_pub_, negative_indices_pub_, indices_pub_;
00161     boost::shared_ptr<tf::TransformBroadcaster> br_;
00162     std::string tf_prefix_;
00163     
00164     bool use_async_;
00165     int queue_size_;
00166     bool force_to_flip_z_axis_;
00167     bool publish_clouds_;
00168     bool publish_tf_;
00169     bool align_boxes_;
00170     bool align_boxes_with_plane_;
00171     std::string target_frame_id_;
00172     tf::TransformListener* tf_listener_;
00173     bool use_pca_;
00174     int max_size_;
00175     int min_size_;
00176     std::string sort_by_;
00177 
00178     jsk_recognition_utils::Counter cluster_counter_;
00179     
00180   };
00181 
00182   class ClusterPointIndicesDecomposerZAxis: public ClusterPointIndicesDecomposer
00183   {
00184   public:
00185     virtual void onInit();
00186   };
00187 
00188 }  // namespace jsk_pcl_ros
00189 
00190 #endif  // JSK_PCL_ROS_CLUSTER_POINT_INDICES_DECOMPOSER_H_


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:49