example_plugin.h
Go to the documentation of this file.
00001 /******************************************************************************
00002  * \file
00003  *
00004  * $Id:$
00005  *
00006  * Copyright (C) Brno University of Technology
00007  *
00008  * This file is part of software developed by dcgm-robotics@FIT group.
00009  *
00010  * Author: Vit Stancl (stancl@fit.vutbr.cz)
00011  * Supervised by: Michal Spanel (spanel@fit.vutbr.cz)
00012  * Date: dd/mm/2012
00013  *
00014  * This file is free software: you can redistribute it and/or modify
00015  * it under the terms of the GNU Lesser General Public License as published by
00016  * the Free Software Foundation, either version 3 of the License, or
00017  * (at your option) any later version.
00018  *
00019  * This file is distributed in the hope that it will be useful,
00020  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00021  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00022  * GNU Lesser General Public License for more details.
00023  *
00024  * You should have received a copy of the GNU Lesser General Public License
00025  * along with this file.  If not, see <http://www.gnu.org/licenses/>.
00026  */
00027 #pragma once
00028 #ifndef _ExamplePlugin_H_included_
00029 #define _ExamplePlugin_H_included_
00030 
00031 #include <srs_env_model/but_server/server_tools.h>
00032 
00033 namespace srs_env_model
00034 {
00035 
00039 class CExamplePlugin : public CServerPluginBase
00040 {
00041 public:
00043         CExamplePlugin( const std::string & name = "ExamplePlugin ")
00044         : CServerPluginBase( name )
00045         {}
00046 
00050         virtual void init(ros::NodeHandle & node_handle){}
00051 
00053         virtual void reset() {}
00054 
00055 protected:
00059         virtual void publishInternal(const ros::Time & timestamp){}
00060 
00063         virtual bool shouldPublish(){ return false; }
00064 
00065 }; // class CExamplePlugin
00066 
00072 class CExampleCrawlerPlugin
00073 : public CServerPluginBase
00074 , public COctomapCrawlerBase<tButServerOcTree::NodeType>
00075 , public CDataHolderBase<std::vector<unsigned char> >
00076 {
00077 public:
00079         CExampleCrawlerPlugin( const std::string & name = "ExamplePlugin ")
00080         : CServerPluginBase( name )
00081         {
00082                 m_data->resize(3);
00083 
00084                 // Store some data
00085                 (*m_data)[0] = 255; (*m_data)[0] = 0; (*m_data)[0] = 0;
00086 
00087         }
00088 
00090         ~CExampleCrawlerPlugin() { }
00091 
00093         virtual void init(ros::NodeHandle & node_handle){}
00094 
00096         virtual void reset() {}
00097 
00098 protected:
00099 
00101         virtual void newMapDataCB( SMapWithParameters & par )
00102         {
00103                 m_frame_id = par.frameId;
00104                 m_time_stamp = par.currentTime;
00105 
00106                 // Initialize leaf iterators
00107                 tButServerOcTree & tree( par.map->getTree() );
00108                 srs_env_model::tButServerOcTree::leaf_iterator it, itEnd( tree.end_leafs() );
00109 
00110                 // Crawl through nodes
00111                 for ( it = tree.begin_leafs(m_crawlDepth); it != itEnd; ++it)
00112                 {
00113                         // Node is occupied?
00114                         if (tree.isNodeOccupied(*it))
00115                         {
00116                                 handleOccupiedNode(it, par);
00117                         }// Node is occupied?
00118                         else
00119                         {
00120                                 handleFreeNode(it, par);
00121                         }
00122 
00123                 } // Iterate through octree
00124 
00125                 invalidate();
00126         }
00127 
00128 
00129         virtual void publishInternal(const ros::Time & timestamp){}
00130 
00134         virtual bool shouldPublish(){ return false; }
00135 
00136 
00139         virtual void handleOccupiedNode(srs_env_model::tButServerOcTree::iterator& it, const SMapWithParameters & mp)
00140         {
00141                 it->r() = (*m_data)[0];
00142                 it->g() = (*m_data)[1];
00143                 it->b() = (*m_data)[2];
00144         }
00145 
00147         virtual void handleFreeNode(tButServerOcTree::iterator & it, const SMapWithParameters & mp )
00148         {
00149                 it->r() = 0;
00150                 it->g() = 255;
00151                 it->b() = 0;
00152         }
00153 
00155         virtual void handlePostNodeTraversal(const SMapWithParameters & mp){}
00156 
00157 
00158 }; // class CExampleCrawlerPlugin
00159 
00160 
00161 
00162 
00163 } // namespace srs_env_model
00164 
00165 
00166 // _ExamplePlugin_H_included_
00167 #endif
00168 


srs_env_model
Author(s): Vit Stancl (stancl@fit.vutbr.cz), Tomas Lokaj, Jan Gorig, Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Sun Jan 5 2014 11:50:48