ParsedStateMachine.cpp
Go to the documentation of this file.
00001 /***************************************************************************
00002   tag: Peter Soetens  Tue Jul 20 17:32:42 CEST 2004  ParsedStateMachine.cxx
00003 
00004                         ParsedStateMachine.cxx -  description
00005                            -------------------
00006     begin                : Tue July 20 2004
00007     copyright            : (C) 2004 Peter Soetens
00008     email                : peter.soetens@mech.kuleuven.ac.be
00009 
00010  ***************************************************************************
00011  *   This library is free software; you can redistribute it and/or         *
00012  *   modify it under the terms of the GNU Lesser General Public            *
00013  *   License as published by the Free Software Foundation; either          *
00014  *   version 2.1 of the License, or (at your option) any later version.    *
00015  *                                                                         *
00016  *   This library is distributed in the hope that it will be useful,       *
00017  *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
00018  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU     *
00019  *   Lesser General Public License for more details.                       *
00020  *                                                                         *
00021  *   You should have received a copy of the GNU Lesser General Public      *
00022  *   License along with this library; if not, write to the Free Software   *
00023  *   Foundation, Inc., 59 Temple Place,                                    *
00024  *   Suite 330, Boston, MA  02111-1307  USA                                *
00025  *                                                                         *
00026  ***************************************************************************/
00027 
00028 #include "ParsedStateMachine.hpp"
00029 #include "../internal/DataSource.hpp"
00030 #include "../ExecutionEngine.hpp"
00031 #include "StateDescription.hpp"
00032 
00033 #include "../Service.hpp"
00034 #include "StateMachineService.hpp"
00035 #include "../TaskContext.hpp"
00036 #include "../internal/mystd.hpp"
00037 
00038 #include <cassert>
00039 
00040 #include <boost/lambda/lambda.hpp>
00041 
00042 namespace RTT {
00043     using namespace detail;
00044     using namespace std;
00045     using boost::tuples::get;
00054     ParsedStateMachinePtr ParsedStateMachine::copy( std::map<const DataSourceBase*, DataSourceBase*>& replacements, bool instantiate ) const
00055     {
00056         /* Recursive copy :
00057          * First copy this SC, then its child SC's
00058          */
00059         std::map<const StateInterface*, StateInterface*> statemapping;
00060         ParsedStateMachinePtr ret(new ParsedStateMachine());
00061         ret->_text = this->_text;
00062         ret->setName( this->_name, false);
00063 
00064         if (instantiate)
00065             Logger::log() <<Logger::Debug <<"Creating an instance of "<< this->_name << Logger::endl;
00066 
00067         // First copy the task such that commands and attributes can be correctly
00068         // copied. This also sets the EventProcessor for the SM.
00069         ret->setService( this->object->copy(ret, replacements, instantiate) );
00070 
00071         // the parameters of the SC, similar to FunctionGraph's Arguments.
00072         for ( VisibleWritableValuesMap::const_iterator i = parametervalues.begin();
00073               i != parametervalues.end(); ++i )
00074         {
00075             // What is sure, is that each param
00076             // must also be in the ConfigurationInterface.
00077             assert( ret->getService()->getValue( i->first ) );
00078             ret->parametervalues[i->first] = ret->getService()->getValue( i->first );
00079         }
00080 
00081         //**********************
00082         // TODO add copy method to StateMachine itself where all stuff below belongs :
00083         // but, not so easy since copy makes new instance...
00084         for ( ChildList::const_iterator i = getChildren().begin(); i != getChildren().end(); ++i )
00085         {
00086             // copy the submachines....
00087             assert( dynamic_cast<ParsedStateMachine*>( i->get() ) == static_cast<ParsedStateMachine*>( i->get() ));
00088             ParsedStateMachinePtr oldmachine = boost::dynamic_pointer_cast<ParsedStateMachine>( *i );
00089             ParsedStateMachinePtr newmachine(oldmachine->copy( replacements, instantiate ));
00090             // I would think that providing 'instantiate' would not hurt...
00091             // XXX? previously, the instantiate flag was not given to copy, does it now break apps ?
00092 
00093             ret->addChild( newmachine ); // also copy tree info to StateMachine !
00094             newmachine->setParent( ret );
00095         }
00096 
00097         // Copy the InitCommand :
00098         if (this->getInitCommand()) {
00099             ret->setInitCommand( this->getInitCommand()->copy(replacements) );
00100             // test :
00101             //ret->getInitCommand()->execute();
00102         }
00103 
00104         // First make a copy of all states.  All states are either
00105         // known by their name or by a transition from or to them...
00106         statemapping[0] = 0; // insert null element.
00107         for ( TransitionMap::const_iterator i = stateMap.begin(); i != stateMap.end(); ++i )
00108         {
00109             if( statemapping.find( i->first ) == statemapping.end() && i->first != 0 ) {
00110                 StateInterface* cpy = i->first->copy( replacements );
00111                 ret->addState( cpy );
00112                 statemapping[i->first] = cpy;
00113             }
00114         }
00115 
00116         // next, copy the transitions
00117         for ( TransitionMap::const_iterator i = stateMap.begin(); i != stateMap.end(); ++i )
00118         {
00119             assert( statemapping.find( i->first ) != statemapping.end() );
00120             StateInterface* fromState = statemapping[i->first];
00121             for ( TransList::const_iterator j = i->second.begin(); j != i->second.end(); ++j )
00122             {
00123                 ConditionInterface* condition = j->get<0>()->copy( replacements );
00124                 assert( statemapping.find( j->get<1>() ) != statemapping.end() );
00125                 StateInterface* toState = statemapping[j->get<1>()];
00126                 int rank = j->get<2>();
00127                 int line = j->get<3>();
00128                 boost::shared_ptr<ProgramInterface> transprog( j->get<4>() );
00129                 if (transprog)
00130                     transprog.reset( j->get<4>()->copy(replacements) );
00131                 ret->transitionSet(fromState, toState, condition, transprog, rank, line );
00132             }
00133         }
00134 
00135         // next, copy/recreate the events
00136         for ( EventMap::const_iterator i = eventMap.begin(); i != eventMap.end(); ++i )
00137         {
00138             assert( statemapping.find( i->first ) != statemapping.end() );
00139             StateInterface* fromState = statemapping[i->first];
00140             for ( EventList::const_iterator j = i->second.begin(); j != i->second.end(); ++j )
00141             {
00142                 ServicePtr sp = j->get<0>();
00143                 string ename = j->get<1>();
00144                 vector<DataSourceBase::shared_ptr> origargs( j->get<2>() );
00145                 vector<DataSourceBase::shared_ptr> newargs;
00146                 for ( vector<DataSourceBase::shared_ptr>::const_iterator vit = origargs.begin();
00147                       vit != origargs.end(); ++vit)
00148                     newargs.push_back( (*vit)->copy(replacements) );
00149                 StateInterface* toState = statemapping[j->get<3>()];
00150                 ConditionInterface* condition = j->get<4>()->copy( replacements );
00151                 ProgramInterfacePtr tprog;
00152                 ProgramInterfacePtr tgraph( j->get<5>() );
00153                 if (tgraph)
00154                     tprog.reset( tgraph->copy(replacements) );
00155                 StateInterface* elseState = statemapping[j->get<7>()];
00156                 ProgramInterfacePtr eprog;
00157                 ProgramInterfacePtr egraph( j->get<8>() );
00158                 if (egraph)
00159                     eprog.reset( egraph->copy(replacements) );
00160 #ifndef NDEBUG
00161                 bool eresult =
00162 #endif
00163                     ret->createEventTransition(sp, ret->getService()->getOwner()->engine(), ename, newargs, fromState, toState, condition, tprog, elseState, eprog );
00164                 assert( eresult );
00165             }
00166         }
00167 
00168         // finally, copy the preconditions
00169         for ( PreConditionMap::const_iterator i = precondMap.begin(); i != precondMap.end(); ++i )
00170         {
00171             assert( statemapping.find( i->first ) != statemapping.end() );
00172             StateInterface* tgtState = statemapping[i->first];
00173             ConditionInterface* condition = i->second.first->copy( replacements );
00174             int line = i->second.second;
00175             ret->preconditionSet( tgtState, condition, line );
00176         }
00177 
00178         // init the StateMachine itself :
00179         ret->setFinalState( statemapping[ getFinalState() ]);
00180         ret->setInitialState( statemapping[ getInitialState() ]);
00181 
00182         return ret;
00183     }
00184 
00185     ParsedStateMachine::~ParsedStateMachine() {
00186         this->smStatus = Status::unloaded;
00187         if ( this->isLoaded() ){
00188             getEngine()->removeFunction(this);
00189         }
00190 
00191         // we own our states...
00192         for ( TransitionMap::iterator i = stateMap.begin();
00193               i != stateMap.end(); ++i )
00194             delete i->first;
00195         // we own our conditions...
00196         for ( TransitionMap::iterator i = stateMap.begin();
00197               i != stateMap.end(); ++i )
00198             for ( TransList::iterator i2 = i->second.begin(); i2 != i->second.end(); ++i2 )
00199                 delete get<0>( *i2 );  // delete the condition.
00200 
00201         // we own our event guards...
00202         for ( EventMap::iterator i = eventMap.begin();
00203               i != eventMap.end(); ++i )
00204             for ( EventList::iterator i2 = i->second.begin(); i2 != i->second.end(); ++i2 )
00205                 delete get<4>( *i2 );  // delete the condition.
00206 
00207     }
00208 
00209     ParsedStateMachine::ParsedStateMachine()
00210         : StateMachine( StateMachinePtr() ) // no parent, no task
00211     {
00212         _text.reset( new string("No Text Set.") );
00213     }
00214 
00215     void ParsedStateMachine::unloading()
00216     {
00217         StateMachine::unloading();
00218         // just kill off the interface.
00219         if ( !object )
00220             return;
00221         if ( object->getParent() && object->getParent()->hasService( object->getName() ) ){
00222             assert( object == object->getParent()->getService( object->getName() ) );
00223             object->getParent()->removeService( object->getName() );
00224         }
00225         object.reset();
00226     }
00227 
00228     void ParsedStateMachine::addParameter( const std::string& name, AttributeBase* var )
00229     {
00230         assert( parametervalues.find( name ) == parametervalues.end() );
00231         parametervalues[name] = var;
00232         // every parameter is also a readonly var...
00233         // visiblereadonlyvalues[name] = var->toDataSource();
00234     }
00235 
00236     AttributeBase* ParsedStateMachine::getParameter( const std::string& name ) const
00237     {
00238         if( parametervalues.find( name ) == parametervalues.end() )
00239             return 0;
00240         return parametervalues.find(name)->second;
00241     }
00242 
00243     ParsedStateMachine::VisibleWritableValuesMap ParsedStateMachine::getParameters() const
00244     {
00245         return parametervalues;
00246     }
00247 
00248     std::vector<std::string> ParsedStateMachine::getParameterNames() const
00249     {
00250         return keys( parametervalues );
00251     }
00252 
00253     void ParsedStateMachine::setName( const std::string& name, bool recursive )
00254     {
00255         // XXX BIG NOTE :
00256         // this function should me named 'instantiate' or so because it does more than
00257         // settting the name, it also recursively arranges names of children and
00258         // sets the parent-child TC connections. Reed the 'recursive' flag as 'instantiate'.
00259         // it is used only recursively for instantiating root contexts.
00260         //cerr << "Setting name "<< _name << " to " << name<<" rec: "<<recursive<<endl;
00261         // set the StateMachine name
00262         this->_name = name;
00263         // set the datasource's name
00264         //nameds->set( name );
00265 
00266         if ( recursive == false )
00267             return;
00268         //this->getService()->addPeer( this->getService()->getPeer("states")->getPeer("task") );
00269         for ( ChildList::const_iterator i = getChildren().begin(); i != getChildren().end(); ++i )
00270         {
00271             std::string subname = name + "." + (*i)->getName();
00272             ParsedStateMachine* psc = static_cast<ParsedStateMachine*>( i->get() );
00273             psc->setName( subname, true );
00274             // we own our child:
00275             psc->getService()->setOwner( 0 );
00276             this->getService()->addService( psc->getService() );
00277         }
00278     }
00279 
00280     std::string ParsedStateMachine::getText() const
00281     {
00282         return *_text;
00283     }
00284 
00285     void ParsedStateMachine::setText( std::string text)
00286     {
00287         *_text = text;
00288     }
00289 
00290     StateMachineServicePtr ParsedStateMachine::getService() const {
00291         return object;
00292     }
00293     void ParsedStateMachine::setService(StateMachineServicePtr tc) {
00294         object = tc;
00295     }
00296 
00297     bool ParsedStateMachine::inState( const std::string& name ) {
00298         StateInterface* copy = this->currentState();
00299         if (copy == 0)
00300             return false;
00301         return copy->getName() == name;
00302     }
00303 
00304     void ParsedStateMachine::finish()
00305     {
00306     }
00307 
00308 }


rtt
Author(s): RTT Developers
autogenerated on Sat Jun 8 2019 18:46:16