FunctionGraphBuilder.cpp
Go to the documentation of this file.
00001 /***************************************************************************
00002   tag: Peter Soetens  Wed Jan 18 14:11:40 CET 2006  FunctionGraphBuilder.cxx
00003 
00004                         FunctionGraphBuilder.cxx -  description
00005                            -------------------
00006     begin                : Wed January 18 2006
00007     copyright            : (C) 2006 Peter Soetens
00008     email                : peter.soetens@mech.kuleuven.be
00009 
00010  ***************************************************************************
00011  *   This library is free software; you can redistribute it and/or         *
00012  *   modify it under the terms of the GNU General Public                   *
00013  *   License as published by the Free Software Foundation;                 *
00014  *   version 2 of the License.                                             *
00015  *                                                                         *
00016  *   As a special exception, you may use this file as part of a free       *
00017  *   software library without restriction.  Specifically, if other files   *
00018  *   instantiate templates or use macros or inline functions from this     *
00019  *   file, or you compile this file and link it with other files to        *
00020  *   produce an executable, this file does not by itself cause the         *
00021  *   resulting executable to be covered by the GNU General Public          *
00022  *   License.  This exception does not however invalidate any other        *
00023  *   reasons why the executable file might be covered by the GNU General   *
00024  *   Public License.                                                       *
00025  *                                                                         *
00026  *   This library is distributed in the hope that it will be useful,       *
00027  *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
00028  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU     *
00029  *   Lesser General Public License for more details.                       *
00030  *                                                                         *
00031  *   You should have received a copy of the GNU General Public             *
00032  *   License along with this library; if not, write to the Free Software   *
00033  *   Foundation, Inc., 59 Temple Place,                                    *
00034  *   Suite 330, Boston, MA  02111-1307  USA                                *
00035  *                                                                         *
00036  ***************************************************************************/
00037 
00038 
00039 
00040 #include "FunctionGraphBuilder.hpp"
00041 #include "CommandComposite.hpp"
00042 #include "../base/AttributeBase.hpp"
00043 #include "../internal/DataSource.hpp"
00044 //#include "parse_exception.hpp"
00045 #include "../FactoryExceptions.hpp"
00046 #include "GraphCopier.hpp"
00047 
00048 #include "CommandNOP.hpp"
00049 #include "ConditionFalse.hpp"
00050 #include "ConditionTrue.hpp"
00051 #include "ConditionTrue.hpp"
00052 #include <boost/graph/copy.hpp>
00053 #include <utility>
00054 
00055 #include <iostream>
00056 
00057 namespace RTT {
00058     using namespace detail;
00059     using namespace boost;
00060     using namespace std;
00061 
00062 
00063 
00064 
00065     FunctionGraphBuilder::FunctionGraphBuilder()
00066         : graph( 0 )
00067     {
00068     }
00069 
00070     FunctionGraphBuilder::~FunctionGraphBuilder()
00071     {
00072     }
00073 
00074     FunctionGraphPtr FunctionGraphBuilder::startFunction(const std::string& fname)
00075     {
00076         // next node should be 'empty'/ not used here.
00077         // a function is to be constructed, it will unload when it stops/errors
00078         func.reset( new FunctionGraph( fname, true ) );
00079         graph   = &func->getGraph();
00080         build   = func->startNode();
00081         next    = add_vertex( *graph );
00082         put( vertex_exec, *graph, next, VertexNode::normal_node );
00083         return func;
00084     }
00085 
00086     void FunctionGraphBuilder::returnFunction( ConditionInterface* cond, int line )
00087     {
00088         // connect the build node to the exitNode under a condition,
00089         // for example, the build implicit term condition.
00090         add_edge(build, func->exitNode(), EdgeCondition(cond), *graph);
00091     }
00092 
00093     FunctionGraphPtr FunctionGraphBuilder::getFunction()
00094     {
00095         return func;
00096     }
00097 
00098     FunctionGraphPtr FunctionGraphBuilder::endFunction( int endline )
00099     {
00100         // the map contains _references_ to all vertex_command properties
00101         boost::property_map<Graph, vertex_command_t>::type
00102             cmap = get(vertex_command, *graph);
00103         cmap[func->exitNode()].setLineNumber( endline );
00104 
00105         // A return statement is obligatory, so the returnFunction has
00106         // already connected the build node to exitNode of the function.
00107         // the end of the statement will proceedToNext
00108         // remove the empty next nodes.
00109         remove_vertex( build, *graph );
00110         remove_vertex( next, *graph );
00111 
00112         func->finish();
00113         func->reset();
00114 
00115         FunctionGraphPtr tfunc = func;
00116         func.reset();
00117         return tfunc;
00118     }
00119 
00120     FunctionGraphBuilder::CommandNode FunctionGraphBuilder::addCommand( ConditionInterface* cond,  ActionInterface* com )
00121     {
00122         add_edge(build, next, EdgeCondition(cond), *graph);
00123         build = next;
00124         setCommand(com);
00125         next    = add_vertex( *graph );
00126         put( vertex_exec, *graph, next, VertexNode::normal_node );
00127         return next;
00128     }
00129 
00130     void FunctionGraphBuilder::addConditionEdge( ConditionInterface* cond, CommandNode vert )
00131     {
00132         add_edge(build, vert, EdgeCondition(cond), *graph);
00133     }
00134 
00135     void FunctionGraphBuilder::closeConditionEdge( CommandNode vert, ConditionInterface* cond )
00136     {
00137         add_edge(vert, build, EdgeCondition(cond), *graph);
00138     }
00139 
00140     FunctionGraphBuilder::CommandNode FunctionGraphBuilder::moveTo( CommandNode _build, CommandNode _next, int linenumber )
00141     {
00142         this->setLineNumber( linenumber );
00143         CommandNode old = build;
00144         build = _build;
00145         next    = _next;
00146         return old;
00147     }
00148 
00149     ActionInterface* FunctionGraphBuilder::getCommand( CommandNode cn )
00150     {
00151         // the map contains _references_ to all vertex_command properties
00152         boost::property_map<Graph, vertex_command_t>::type
00153             cmap = get(vertex_command, *graph);
00154         // access the one of build
00155         return cmap[cn].getCommand();
00156     }
00157 
00158     void FunctionGraphBuilder::setCommand( ActionInterface* comm )
00159     {
00160         this->setCommand(build, comm);
00161     }
00162 
00163     void FunctionGraphBuilder::setCommand(CommandNode cn, ActionInterface* comm )
00164     {
00165         // the map contains _references_ to all vertex_command properties
00166         boost::property_map<Graph, vertex_command_t>::type
00167             cmap = get(vertex_command, *graph);
00168         // access the one of build
00169         delete cmap[cn].setCommand( comm );
00170     }
00171 
00172     void FunctionGraphBuilder::setName(const std::string& pname) {
00173         func->setName(pname);
00174     }
00175 
00176     FunctionGraphBuilder::CommandNode FunctionGraphBuilder::proceedToNext( ConditionInterface* cond, int this_line )
00177     {
00178         add_edge(build, next, EdgeCondition(cond), *graph);
00179         return proceedToNext( this_line );
00180     }
00181 
00182     FunctionGraphBuilder::CommandNode FunctionGraphBuilder::proceedToNext( int this_line )
00183     {
00184         if ( this_line )
00185             this->setLineNumber( this_line );
00186         build = next;
00187         next    = add_vertex( *graph );
00188         put(vertex_exec, *graph, next, VertexNode::normal_node );
00189         return build;
00190     }
00191 
00192     void FunctionGraphBuilder::connectToNext( CommandNode v, ConditionInterface* cond )
00193     {
00194         add_edge( v, next, EdgeCondition(cond), *graph);
00195     }
00196 
00197     FunctionGraphBuilder::CommandNode FunctionGraphBuilder::buildNode() const
00198     {
00199         return build;
00200     }
00201 
00202     size_t FunctionGraphBuilder::buildEdges() const
00203     {
00204         return out_degree( build, *graph );
00205     }
00206 
00207     FunctionGraphBuilder::CommandNode FunctionGraphBuilder::nextNode() const
00208     {
00209         return next;
00210     }
00211 
00212     void FunctionGraphBuilder::setLineNumber( int line )
00213     {
00214         boost::property_map<Graph, vertex_command_t>::type
00215             cmap = get(vertex_command, *graph);
00216         cmap[build].setLineNumber( line );
00217     }
00218 
00219 
00220     template< class _Map >
00221     struct finder {
00222         typedef FunctionGraphBuilder::Vertex first_argument_type ;
00223         typedef std::pair<_Map, int> second_argument_type ;
00224         typedef bool result_type;
00225         bool operator()(const FunctionGraphBuilder::Vertex& v,
00226                         const std::pair<_Map, int>& to_find  ) const
00227             {
00228                 // return : Is this the node with the given property ?
00229                 return to_find.first[v] == to_find.second;
00230             }
00231     };
00232 
00233     FunctionGraphBuilder::CommandNode FunctionGraphBuilder::appendFunction( ConditionInterface* cond, FunctionGraphPtr fn,
00234                                                             std::vector<DataSourceBase::shared_ptr> fnargs )
00235     {
00239         // Do not move build inhere !
00240         // copy FunctionGraph's graph into the current *graph, add an edge with
00241         // the condition. Connect the exitNode() of the function with
00242         // the next node.
00243 
00244         // The reason to reindex the vertexes of source graph is
00245         // to silence valgrinds warnings about uninitialised values
00246         // in the following piece of code. Technically, copy_graph
00247         // does not need it.
00248         boost::property_map<Graph, vertex_index_t>::type indexmap =
00249             get( vertex_index, *graph );
00250         boost::graph_traits<Graph>::vertex_iterator v, vend;
00251         int index = 0;
00252         for ( tie( v, vend ) = vertices( *graph ); v != vend; ++v )
00253             indexmap[*v] = index++;
00254 
00255         // check nb of arguments:
00256         std::vector<AttributeBase*> origlist = fn->getArguments();
00257         if ( fnargs.size() != origlist.size() ) {
00258 #ifndef ORO_EMBEDDED
00259             throw wrong_number_of_args_exception( origlist.size(), fnargs.size() );
00260 #else
00261             return buildNode();
00262 #endif
00263         }
00264 
00265         // make a deep copy of the function :
00266         std::map<const DataSourceBase*, DataSourceBase*> replacementdss;
00267         std::vector<AttributeBase*> newlist;
00268         for (unsigned int i=0; i < origlist.size(); ++i)
00269             newlist.push_back( origlist[i]->copy( replacementdss, false ) ); // args are not instantiated.
00270         // newlist contains the DS which need initialisations :
00271 
00272         // create commands that init all the args :
00273         CommandComposite* icom=  new CommandComposite();
00274         std::vector<DataSourceBase::shared_ptr>::const_iterator dit = fnargs.begin();
00275         std::vector<AttributeBase*>::const_iterator tit =  newlist.begin();
00276 #ifndef ORO_EMBEDDED
00277         try {
00278             for (; dit != fnargs.end(); ++dit, ++tit)
00279                 icom->add( (*tit)->getDataSource()->updateAction( dit->get() ) );
00280         }
00281         catch( const bad_assignment& ) {
00282             // cleanup allocated memory
00283             for (unsigned int i=0; i < newlist.size(); ++i)
00284                 delete newlist[i];
00285             delete icom;
00286             int parnb = (dit - fnargs.begin());
00287             throw wrong_types_of_args_exception(parnb, (*tit)->getDataSource()->getType() ,(*dit)->getType() );
00288         }
00289 #else
00290         for (; dit != fnargs.end(); ++dit, ++tit) {
00291             ActionInterface* ret = (*tit)->getDataSource()->updateAction( dit->get() );
00292             if (ret)
00293                 icom->add( ret );
00294             else {
00295                 // cleanup allocated memory
00296                 for (unsigned int i=0; i < newlist.size(); ++i)
00297                     delete newlist[i];
00298                 delete icom;
00299                 return buildNode();
00300             }
00301         }
00302 #endif
00303         // set the init command on the build node
00304         //assert( build not used by other than NOP )
00305         assert( dynamic_cast<CommandNOP*>( this->getCommand(build) ));
00306         this->setCommand( icom );
00307         
00308         GraphVertexCopier gvc( fn->getGraph(), *graph, replacementdss );
00309         GraphEdgeCopier gec( fn->getGraph(), *graph, replacementdss );
00310 
00311         // This gives  a compiler warning with GCC:
00312         boost::copy_graph( fn->getGraph(), *graph, boost::vertex_copy( gvc ).edge_copy( gec ) );
00313         // It's a bug in boost::copy_graph with 3 arguments. We'd have to implement the copy ourselves
00314         // in order to get rid of this warning/bug.
00315 
00316         // cleanup newlist, the (var)DS's are stored in the assignCommand
00317         for (unsigned int i=0; i < newlist.size(); ++i)
00318             delete newlist[i];
00319 
00320         // the subgraph has been copied but is now 'floating' in the current graph.
00321         // we search func start and exit points and connect them to
00322         // the current graph.
00323 
00324         // domi: it would be cleaner if a function would keep a
00325         // reference to its enter and exit point, and we would use the
00326         // copy_graph orig_to_copy map to find the corresponding nodes
00327         // in the copy...
00328         graph_traits<Graph>::vertex_iterator v1,v2, vc;
00329         tie(v1,v2) = vertices(*graph);
00330         boost::property_map<Graph, vertex_exec_t>::type
00331             vmap = get(vertex_exec, *graph);
00332 
00333 //         // test not initialised value.
00334 //         vc = v1;
00335 //         while (vc != v2) {
00336 //             std::cerr << int( vmap[*vc] )<<std::endl;
00337 //             ++vc;
00338 //         }
00339 //         std::cerr<<std::endl;
00340 //         // test foo :
00341 //         tie(v1,v2) = vertices(fn->getGraph());
00342 //             vmap = get(vertex_exec, fn->getGraph());
00343 //         vc = v1;
00344 //         while (vc != v2) {
00345 //             std::cerr << int( vmap[*vc] )<<std::endl;
00346 //             ++vc;
00347 //         }
00348 
00349 
00350         Vertex funcStart=*
00351                          find_if(v1, v2,
00352                                  bind2nd( finder<boost::property_map<Graph, vertex_exec_t>::type>() ,
00353                                           std::make_pair( vmap, int(VertexNode::func_start_node)) ) );
00354         Vertex funcExit=*
00355                         find_if(v1, v2,
00356                                 bind2nd( finder<boost::property_map<Graph, vertex_exec_t>::type>() ,
00357                                          std::make_pair( vmap, int(VertexNode::func_exit_node)) ) );
00358 
00359         // reset their special meanings.
00360         vmap[funcStart] = VertexNode::normal_node;
00361         vmap[funcExit]  = VertexNode::normal_node;
00362         // connect the graph.
00363         addConditionEdge( cond, funcStart );
00364         connectToNext( funcExit, new ConditionTrue );
00365 
00366         return funcExit;
00367 //         // try to solve call in function bug with arguments
00368 //         boost::property_map<Graph, vertex_command_t>::type
00369 //             cmap = get(vertex_command, *graph);
00370 //         return proceedToNext( cmap[funcExit].getLineNumber() );
00371     }
00372 
00373     FunctionGraphBuilder::CommandNode FunctionGraphBuilder::setFunction( FunctionGraphPtr fn,
00374                                                          std::vector<DataSourceBase::shared_ptr> fnargs )
00375     {
00384         return appendFunction( new ConditionTrue, fn, fnargs) ;
00385     }
00386 
00387     void FunctionGraphBuilder::startIfStatement( ConditionInterface* cond, int linenumber )
00388     {
00389         // push all relevant nodes on the branch_stack.
00390         // endIf and endElse will pop them
00391 
00392         // * next will become the first node of the succeeding if statement
00393         // * after_else_node will become the node after the if block is finished
00394         // and the else block is finished.
00395         // * else_node is the first node of a failing if statement (this may be _any_statement, thus also an if)
00396         CommandNode else_node = add_vertex( *graph );
00397         put(vertex_exec, *graph, else_node, VertexNode::normal_node );
00398         branch_stack.push( else_node );
00399         CommandNode after_else_node =  add_vertex( *graph );
00400         put(vertex_exec, *graph, after_else_node, VertexNode::normal_node );
00401         branch_stack.push( after_else_node );
00402         //branch_stack.push( build );
00403 
00404         // add edge from build to next
00405         addConditionEdge( cond, next );
00406         // add edge from build to 'after_else_node'
00407         addConditionEdge( new ConditionTrue(), else_node );
00408         proceedToNext(linenumber);
00409     }
00410 
00411     void FunctionGraphBuilder::endIfBlock(int linenumber){
00412         // this is called after a proceedToNext of the last statement of
00413         // the if block.
00414         // Connect end of if block with after_else_node
00415         CommandNode after_else_node = branch_stack.top();
00416         addConditionEdge( new ConditionTrue(), after_else_node );
00417         branch_stack.pop();
00418         // make else_node build, next remains.
00419         moveTo( branch_stack.top(), next, linenumber );
00420         branch_stack.pop();
00421         // store again !
00422         branch_stack.push( after_else_node );
00423     }
00424 
00425     // Else : can be empty and is then a plain proceed to next.
00426     void FunctionGraphBuilder::endElseBlock(int linenumber) {
00427         // after_else_node is on top of stack
00428         CommandNode after_else_node = branch_stack.top();
00429         branch_stack.pop();
00430         addConditionEdge( new ConditionTrue(), after_else_node );
00431         // make after_else_node build
00432         moveTo( after_else_node, next, linenumber );
00433     }
00434 
00435     void FunctionGraphBuilder::startWhileStatement( ConditionInterface* cond, int linenumber )
00436     {
00437         // very analogous to the if statement, but there is no else part
00438         // and we stack the first commandnode to be able to close the loop.
00439         CommandNode after_while_node = add_vertex( *graph );
00440         put(vertex_exec, *graph, after_while_node, VertexNode::normal_node );
00441         branch_stack.push( after_while_node );
00442         break_stack.push( after_while_node );
00443         branch_stack.push( build );
00444         // add edge from build to next if condition == true
00445         addConditionEdge( cond, next );
00446         // if condition fails, go from build to 'after_while_node'
00447         addConditionEdge( new ConditionTrue(), after_while_node );
00448         proceedToNext(linenumber);
00449     }
00450 
00451     void FunctionGraphBuilder::endWhileBlock(int linenumber)
00452     {
00453         CommandNode start_of_while = branch_stack.top();
00454         branch_stack.pop();
00455         // go from build back to start (and check there the condition).
00456         addConditionEdge( new ConditionTrue(), start_of_while );
00457         CommandNode after_while_node =  branch_stack.top();
00458         branch_stack.pop();
00459         break_stack.pop();
00460         moveTo( after_while_node, next, linenumber );
00461     }
00462 
00463     bool FunctionGraphBuilder::inLoop()
00464     {
00465         return break_stack.size() != 0;
00466     }
00467 
00468     bool FunctionGraphBuilder::breakLoop()
00469     {
00470         if ( !inLoop() )
00471             return false;
00472 
00473         // go from build to last nested exit point.
00474         addConditionEdge( new ConditionTrue(), break_stack.top() );
00475         return true;
00476     }
00477 
00478 #if 0
00479     void FunctionGraphBuilder::prependCommand( ActionInterface* command, int line_nr )
00480     {
00481         CommandNode previousstart = start;
00482         start = add_vertex( program );
00483         boost::property_map<Graph, vertex_exec_t>::type
00484             vmap = get(vertex_exec, program);
00485         put( vmap, start, get( vmap, previousstart ) );
00486         put( vmap, previousstart, VertexNode::normal_node );
00487         boost::property_map<Graph, vertex_command_t>::type
00488             cmap = get( vertex_command, program );
00489         VertexNode vnode( command );
00490         vnode.setLineNumber( line_nr );
00491         put( cmap, start, vnode );
00492         add_edge(start, previousstart, EdgeCondition(new ConditionTrue), program);
00493         if ( build == previousstart )
00494             build = start;
00495 
00496         // now let's reindex the vertices...
00497         boost::property_map<Graph, vertex_index_t>::type indexmap =
00498             get( vertex_index, *graph );
00499         boost::graph_traits<Graph>::vertex_iterator v, vend;
00500         int index = 0;
00501         for ( tie( v, vend ) = vertices( *graph ); v != vend; ++v )
00502             indexmap[*v] = index++;
00503     }
00504 #endif
00505 
00506 }
00507 


rtt
Author(s): RTT Developers
autogenerated on Fri Sep 9 2016 04:01:53