42 #include "../base/AttributeBase.hpp" 43 #include "../internal/DataSource.hpp" 45 #include "../FactoryExceptions.hpp" 52 #include <boost/graph/copy.hpp> 58 using namespace detail;
59 using namespace boost;
101 boost::property_map<Graph, vertex_command_t>::type
103 cmap[
func->exitNode()].setLineNumber( endline );
152 boost::property_map<Graph, vertex_command_t>::type
155 return cmap[cn].getCommand();
166 boost::property_map<Graph, vertex_command_t>::type
169 delete cmap[cn].setCommand( comm );
173 func->setName(pname);
214 boost::property_map<Graph, vertex_command_t>::type
216 cmap[
build].setLineNumber( line );
220 template<
class _Map >
226 const std::pair<_Map, int>& to_find )
const 229 return to_find.first[v] == to_find.second;
234 std::vector<DataSourceBase::shared_ptr> fnargs )
248 boost::property_map<Graph, vertex_index_t>::type indexmap =
249 get( vertex_index, *
graph );
250 boost::graph_traits<Graph>::vertex_iterator v, vend;
252 for ( tie( v, vend ) = vertices( *
graph ); v != vend; ++v )
253 indexmap[*v] = index++;
256 std::vector<AttributeBase*> origlist = fn->getArguments();
257 if ( fnargs.size() != origlist.size() ) {
266 std::map<const DataSourceBase*, DataSourceBase*> replacementdss;
267 std::vector<AttributeBase*> newlist;
268 for (
unsigned int i=0; i < origlist.size(); ++i)
269 newlist.push_back( origlist[i]->copy( replacementdss,
false ) );
274 std::vector<DataSourceBase::shared_ptr>::const_iterator dit = fnargs.begin();
275 std::vector<AttributeBase*>::const_iterator tit = newlist.begin();
278 for (; dit != fnargs.end(); ++dit, ++tit)
279 icom->
add( (*tit)->getDataSource()->updateAction( dit->get() ) );
283 for (
unsigned int i=0; i < newlist.size(); ++i)
286 int parnb = (dit - fnargs.begin());
290 for (; dit != fnargs.end(); ++dit, ++tit) {
291 ActionInterface* ret = (*tit)->getDataSource()->updateAction( dit->get() );
296 for (
unsigned int i=0; i < newlist.size(); ++i)
308 GraphVertexCopier gvc( fn->getGraph(), *
graph, replacementdss );
309 GraphEdgeCopier gec( fn->getGraph(), *
graph, replacementdss );
312 boost::copy_graph( fn->getGraph(), *
graph, boost::vertex_copy( gvc ).edge_copy( gec ) );
317 for (
unsigned int i=0; i < newlist.size(); ++i)
328 graph_traits<Graph>::vertex_iterator v1,v2, vc;
329 tie(v1,v2) = vertices(*
graph);
330 boost::property_map<Graph, vertex_exec_t>::type
352 bind2nd(
finder<boost::property_map<Graph, vertex_exec_t>::type>() ,
356 bind2nd(
finder<boost::property_map<Graph, vertex_exec_t>::type>() ,
374 std::vector<DataSourceBase::shared_ptr> fnargs )
479 void FunctionGraphBuilder::prependCommand(
ActionInterface* command,
int line_nr )
482 start = add_vertex( program );
483 boost::property_map<Graph, vertex_exec_t>::type
485 put( vmap, start,
get( vmap, previousstart ) );
487 boost::property_map<Graph, vertex_command_t>::type
491 put( cmap, start, vnode );
493 if (
build == previousstart )
497 boost::property_map<Graph, vertex_index_t>::type indexmap =
498 get( vertex_index, *
graph );
499 boost::graph_traits<Graph>::vertex_iterator v, vend;
501 for ( tie( v, vend ) = vertices( *
graph ); v != vend; ++v )
502 indexmap[*v] = index++;
std::pair< _Map, int > second_argument_type
boost::shared_ptr< FunctionGraph > FunctionGraphPtr
CommandNode nextNode() const
This interface represents the concept of a condition which can be evaluated and return true or false...
base::ActionInterface * getCommand(CommandNode cn)
void endElseBlock(int linenumber)
CommandNode setFunction(FunctionGraphPtr fn, std::vector< base::DataSourceBase::shared_ptr > fnargs)
void startIfStatement(ConditionInterface *cond, int linenumber)
void closeConditionEdge(CommandNode vert, ConditionInterface *cond)
void returnFunction(ConditionInterface *cond, int line)
void connectToNext(CommandNode v, ConditionInterface *cond)
std::stack< CommandNode > branch_stack
A stack which keeps track of branch points.
void endIfBlock(int linenumber)
void startWhileStatement(ConditionInterface *cond, int linenumber)
void setLineNumber(int ln)
void endWhileBlock(int linenumber)
FunctionGraphPtr getFunction()
CommandNode moveTo(CommandNode _build, CommandNode _next, int linenr)
Based on the software pattern 'command', this interface allows execution of action objects...
FunctionGraphPtr endFunction(int line=0)
size_t buildEdges() const
boost::graph_traits< Graph >::vertex_descriptor Vertex
void setName(const std::string &_name)
FunctionGraphBuilder::Vertex first_argument_type
void setCommand(base::ActionInterface *comm)
void setLineNumber(int ln)
std::stack< CommandNode > break_stack
virtual void add(base::ActionInterface *com)
CommandNode buildNode() const
Contains TaskContext, Activity, OperationCaller, Operation, Property, InputPort, OutputPort, Attribute.
This class represents a conditional branch in a program tree. It contains a condition which must be s...
bool operator()(const FunctionGraphBuilder::Vertex &v, const std::pair< _Map, int > &to_find) const
void addConditionEdge(ConditionInterface *cond, CommandNode vert)
Based on the software pattern 'composite', this class RTT_SCRIPTING_API allows composing command obje...
FunctionGraph::Vertex CommandNode
CommandNode appendFunction(ConditionInterface *cond, FunctionGraphPtr fn, std::vector< base::DataSourceBase::shared_ptr > fnargs)
CommandNode proceedToNext(int line_nr=0)
CommandNode addCommand(ConditionInterface *cond, base::ActionInterface *com)
FunctionGraphPtr startFunction(const std::string &fname)