cloud_composer_item.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement  (BSD License)
00003  *
00004  *  Point Cloud Library  (PCL) - www.pointclouds.org
00005  *  Copyright  (c) 2012, Jeremie Papon.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES  (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT  (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  */
00037 
00038 #ifndef CLOUD_COMPOSER_ITEM_H_
00039 #define CLOUD_COMPOSER_ITEM_H_
00040 
00041 
00042 #include <pcl/point_types.h>
00043 #include <pcl/visualization/pcl_visualizer.h>
00044 #include <pcl/apps/cloud_composer/qt.h>
00045 #include <pcl/apps/cloud_composer/properties_model.h>
00046 
00047 
00048 
00049 
00050 static QStringList ITEM_TYPES_STRINGS(QStringList() 
00051       << "Cloud Composer Item"
00052       << "Cloud Item"
00053       << "Normals Item"
00054       << "FPFH Item"
00055       );
00056 
00057 namespace pcl
00058 {
00059   namespace cloud_composer
00060   {
00061     class PropertiesModel;
00062     namespace ItemDataRole 
00063     { 
00064       enum
00065       { 
00066         PROPERTIES = Qt::UserRole,
00067         ITEM_ID,
00068         CLOUD_BLOB,
00069         CLOUD_TEMPLATED,
00070         GEOMETRY_HANDLER, 
00071         COLOR_HANDLER,
00072         ORIGIN,
00073         ORIENTATION,
00074         KD_TREE_SEARCH
00075       };
00076     };
00077     class PCL_EXPORTS CloudComposerItem : public QStandardItem
00078     {
00079       public:  
00080         
00081   
00082         enum ItemType 
00083         { 
00084           CLOUD_COMPOSER_ITEM = QStandardItem::UserType,
00085           CLOUD_ITEM,
00086           NORMALS_ITEM,
00087           FPFH_ITEM
00088         };
00089 
00090         CloudComposerItem (const QString name = "default item");
00091         CloudComposerItem (const CloudComposerItem& to_copy);
00092         virtual ~CloudComposerItem ();
00093         
00094         inline virtual int 
00095         type () const { return CLOUD_COMPOSER_ITEM; }
00096       
00098         inline QString
00099         getId () const { return data (ItemDataRole::ITEM_ID).toString (); }
00100         
00102         inline PropertiesModel*
00103         getPropertiesModel () const { return properties_; }
00104         
00106         QList <CloudComposerItem*>
00107         getChildren (ItemType type) const;
00108         
00109         void 
00110         addChild (CloudComposerItem* item_arg);
00111         
00112         virtual CloudComposerItem*
00113         clone () const;
00114 
00115      //   /** \brief Convenience function which pulls out a cloud Ptr of type CloudPtrT */
00116     //    template <typename CloudPtrT>
00117     //    CloudPtrT
00118     //    getCloudPtr () const;
00119         
00121         virtual void
00122         paintView (boost::shared_ptr<pcl::visualization::PCLVisualizer> vis) const;
00123         
00125         virtual void
00126         removeFromView (boost::shared_ptr<pcl::visualization::PCLVisualizer> vis) const;
00127         
00129         virtual QMap <QString, QWidget*>
00130         getInspectorTabs ();
00131               
00133         inline void 
00134         propertyChanged ()
00135         {
00136           emitDataChanged ();
00137         }
00138         
00139         virtual bool
00140         isSanitized () const { return false; }
00141       protected:
00142 
00144         PropertiesModel* properties_;
00145         
00146     };
00147     
00148     
00149    
00151     template <class T> class VPtr
00152     {
00153       public:
00154         static T* asPtr (QVariant v)
00155         {
00156           return (static_cast<T *> (v.value<void *> ()));
00157         }
00158 
00159         static QVariant asQVariant (T* ptr)
00160         {
00161           return (qVariantFromValue (static_cast<void*>(ptr)));
00162         }
00163     };
00164     
00165   }
00166 }
00167 
00168 typedef QList<const pcl::cloud_composer::CloudComposerItem*> ConstItemList;
00169 
00170 Q_DECLARE_METATYPE (pcl::cloud_composer::CloudComposerItem);
00171 
00172 
00173 
00174 
00175 
00176 
00177 
00178 
00179 
00180 
00181 #endif //CLOUD_COMPOSER_ITEM_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:36