commands.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 COMMANDS_H_
00039 #define COMMANDS_H_
00040 
00041 #include <pcl/apps/cloud_composer/qt.h>
00042 #include <pcl/pcl_exports.h>
00043 #include <pcl/apps/cloud_composer/items/cloud_item.h>
00044 
00045 namespace pcl
00046 {
00047   namespace cloud_composer
00048   {
00049     class AbstractTool;
00050     class ProjectModel;
00051     struct OutputPair
00052     {
00053       QList <const CloudComposerItem*> input_items_;
00054       QList <CloudComposerItem*> output_items_;
00055     };
00056 
00057 
00058     
00059     class PCL_EXPORTS CloudCommand : public QUndoCommand
00060     {
00061       public: 
00062         CloudCommand (ConstItemList input_data, QUndoCommand* parent = 0);
00063         
00064         virtual
00065         ~CloudCommand ();
00066         
00067         virtual bool
00068         runCommand (AbstractTool* tool) = 0;
00069 
00070         virtual void 
00071         undo ()  = 0;
00072         
00073         virtual void
00074         redo () = 0;
00075         
00076         //QList <CloudComposerItem*> 
00077        // executeToolOnTemplateCloud (AbstractTool* tool, ConstItemList &input_data);
00078         
00079         void 
00080         setProjectModel (ProjectModel* model);
00081         
00082         inline void
00083         setInputData (ConstItemList input_data)
00084         {
00085           original_data_ = input_data;
00086         }
00087       protected:
00092         bool 
00093         replaceOriginalWithNew (QList <const CloudComposerItem*> originals, QList <CloudComposerItem*> new_items);
00094         
00096         bool
00097         restoreOriginalRemoveNew (QList <const CloudComposerItem*> originals, QList <CloudComposerItem*> new_items);
00098         
00099         ConstItemList original_data_;
00100         
00101         QMap <QStandardItem*, QStandardItem*> removed_to_parent_map_;
00102         QList <OutputPair> output_data_;
00103         ProjectModel* project_model_;
00104        
00110         bool last_was_undo_;
00111         
00115         bool 
00116         canUseTemplates (ConstItemList &input_data);
00117         
00118         bool can_use_templates_;
00119         int template_type_;
00120     };
00121     
00122     class PCL_EXPORTS ModifyItemCommand : public CloudCommand
00123     {
00124       public: 
00125         ModifyItemCommand (ConstItemList input_data, QUndoCommand* parent = 0);
00126     
00127         virtual bool
00128         runCommand (AbstractTool* tool);
00129         
00130         virtual void
00131         undo ();
00132       
00133         virtual void
00134         redo ();
00135       private: 
00136         
00137       
00138       
00139     };
00140     
00141     class PCL_EXPORTS NewItemCloudCommand : public CloudCommand
00142     {
00143       public: 
00144         NewItemCloudCommand (ConstItemList input_data, QUndoCommand* parent = 0);
00145       
00146         virtual bool
00147         runCommand (AbstractTool* tool);
00148         
00149         virtual void
00150         undo ();
00151       
00152         virtual void
00153         redo ();
00154 
00155     };
00156     
00157 
00158     class PCL_EXPORTS SplitCloudCommand : public CloudCommand
00159     {
00160       public: 
00161         SplitCloudCommand (ConstItemList input_data, QUndoCommand* parent = 0);
00162       
00163         virtual bool
00164         runCommand (AbstractTool* tool);
00165         
00166         virtual void
00167         undo ();
00168       
00169         virtual void
00170         redo ();
00171       private:
00172 
00173     };  
00174     
00175     class PCL_EXPORTS DeleteItemCommand : public CloudCommand
00176     {
00177       public: 
00178         DeleteItemCommand (ConstItemList input_data, QUndoCommand* parent = 0);
00179       
00180         virtual bool
00181         runCommand (AbstractTool* tool);
00182         
00183         virtual void
00184         undo ();
00185       
00186         virtual void
00187         redo ();
00188       private:
00189     };
00190     
00191     class PCL_EXPORTS MergeCloudCommand : public CloudCommand
00192     {
00193       public: 
00198         MergeCloudCommand (ConstItemList input_data, QUndoCommand* parent = 0);
00199       
00200         virtual bool
00201         runCommand (AbstractTool* tool);
00202         
00203         virtual void
00204         undo ();
00205       
00206         virtual void
00207         redo ();
00208         
00209         inline void
00210         setSelectedIndicesMap( const QMap <CloudItem*, pcl::PointIndices::Ptr > selected_item_index_map)
00211         {
00212           selected_item_index_map_ = selected_item_index_map;
00213         }
00214           
00215       private:
00216         QMap <CloudItem*, pcl::PointIndices::Ptr > selected_item_index_map_;
00217     };
00218   }
00219 } 
00220 
00221 Q_DECLARE_METATYPE (ConstItemList);
00222 #endif //COMMANDS_H_


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