abstract_tool.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 ABSTRACT_TOOL_H_
00039 #define ABSTRACT_TOOL_H_
00040 
00041 #include <pcl/apps/cloud_composer/qt.h>
00042 #include <pcl/apps/cloud_composer/commands.h>
00043 #include <pcl/apps/cloud_composer/items/cloud_item.h>
00044 #include <pcl/apps/cloud_composer/properties_model.h>
00045 
00046 namespace pcl
00047 {
00048   namespace cloud_composer
00049   {
00050        
00051         
00052     class AbstractTool : public QObject
00053     {
00054       Q_OBJECT
00055       public:
00056 
00057         AbstractTool (PropertiesModel* parameter_model, QObject* parent); 
00058 
00059         virtual ~AbstractTool () { qDebug() << "Tool Destructed"; }
00060         
00066         virtual QList <CloudComposerItem*>
00067         performAction (QList <const CloudComposerItem*> input_data, PointTypeFlags::PointType type = PointTypeFlags::NONE) = 0;
00068         
00069         virtual CloudCommand*
00070         createCommand (QList <const CloudComposerItem*> input_data) = 0;
00071         
00072         QString 
00073         getActionText () const {return action_text_;}
00074         
00075         void
00076         setActionText (const QString text) { action_text_ = text; }
00077               
00078         virtual QString
00079         getToolName () const = 0;
00080         
00081       protected:
00082              
00083         PropertiesModel* parameter_model_;   
00084        
00085       private:
00086         QString action_text_;
00087         
00088     };
00089     
00090     class ModifyItemTool : public AbstractTool
00091     {
00092       Q_OBJECT
00093       public:
00094         ModifyItemTool (PropertiesModel* parameter_model, QObject* parent) 
00095                       : AbstractTool (parameter_model, parent) 
00096                       {}
00097         
00098         virtual ~ModifyItemTool () { }
00099         
00100         virtual QList <CloudComposerItem*>
00101         performAction (QList <const CloudComposerItem*> input_data, PointTypeFlags::PointType type = PointTypeFlags::NONE) = 0;
00102         
00103         inline virtual CloudCommand* 
00104         createCommand (QList <const CloudComposerItem*> input_data) 
00105         {
00106           return new ModifyItemCommand (input_data);
00107         }
00108         
00109         inline virtual QString
00110         getToolName () const { return "ModifyItemTool";}
00111         
00112     };
00113     
00114     class NewItemTool : public AbstractTool
00115     {
00116       Q_OBJECT
00117       public:
00118         NewItemTool (PropertiesModel* parameter_model, QObject* parent) 
00119                       : AbstractTool (parameter_model, parent)
00120                       {}
00121         
00122         virtual ~NewItemTool () { }
00123         
00124         virtual QList <CloudComposerItem*>
00125         performAction (QList <const CloudComposerItem*> input_data, PointTypeFlags::PointType type = PointTypeFlags::NONE) = 0;
00126         
00127         inline virtual CloudCommand*
00128         createCommand (QList <const CloudComposerItem*> input_data) 
00129         {
00130           return new NewItemCloudCommand (input_data);
00131         }
00132         
00133         inline virtual QString
00134         getToolName () const { return "NewItemTool";}
00135       
00136     };
00137     
00138     class SplitItemTool : public AbstractTool
00139     {
00140       Q_OBJECT
00141       public:
00142         SplitItemTool (PropertiesModel* parameter_model, QObject* parent) 
00143                       : AbstractTool (parameter_model, parent) 
00144                       {}
00145         
00146         virtual ~SplitItemTool () { }
00147         
00148         virtual QList <CloudComposerItem*>
00149         performAction (QList <const CloudComposerItem*> input_data, PointTypeFlags::PointType type = PointTypeFlags::NONE) = 0;
00150         
00151         inline virtual CloudCommand* 
00152         createCommand (QList <const CloudComposerItem*> input_data) 
00153         {
00154           return new SplitCloudCommand (input_data);
00155         }
00156         
00157         inline virtual QString
00158         getToolName () const { return "SplitItemTool";}
00159         
00160     };
00161     
00162     class MergeCloudTool : public AbstractTool
00163     {
00164       Q_OBJECT
00165       public:
00166         MergeCloudTool (PropertiesModel* parameter_model, QObject* parent) 
00167                       : AbstractTool (parameter_model, parent) 
00168                       {}
00169         
00170         virtual ~MergeCloudTool () { }
00171         
00172         virtual QList <CloudComposerItem*>
00173         performAction (QList <const CloudComposerItem*> input_data, PointTypeFlags::PointType type = PointTypeFlags::NONE) = 0;
00174         
00175         inline virtual CloudCommand* 
00176         createCommand (QList <const CloudComposerItem*> input_data) 
00177         {
00178           return new MergeCloudCommand (input_data);
00179         }
00180         
00181         inline virtual QString
00182         getToolName () const { return "MergeCloudTool";}
00183         
00184     };
00185   }
00186 }
00187 
00188 
00189 #endif //ABSTRACT_TOOL_H_


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