OrocosComponentLibrary  2.7.0
TaskBrowser.cpp
00001 #ifndef NO_GPL
00002 /***************************************************************************
00003   tag: Peter Soetens  Thu Jul 3 15:31:34 CEST 2008  TaskBrowser.cpp
00004 
00005                         TaskBrowser.cpp -  description
00006                            -------------------
00007     begin                : Thu July 03 2008
00008     copyright            : (C) 2008 Peter Soetens
00009     email                : peter.soetens@fmtc.be
00010 
00011  ***************************************************************************
00012  *                                                                         *
00013  *   This program is free software; you can redistribute it and/or modify  *
00014  *   it under the terms of the GNU General Public License as published by  *
00015  *   the Free Software Foundation; either version 2 of the License, or     *
00016  *   (at your option) any later version.                                   *
00017  *                                                                         *
00018  *   This program is distributed in the hope that it will be useful,       *
00019  *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
00020  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU     *
00021  *   General Public License for more details.                              *
00022  *                                                                         *
00023  *   You should have received a copy of the GNU General Public             *
00024  *   License along with this program; if not, write to the Free Software   *
00025  *   Foundation, Inc., 59 Temple Place,                                    *
00026  *   Suite 330, Boston, MA  02111-1307  USA                                *
00027  ***************************************************************************/
00028 #else
00029 /***************************************************************************
00030   tag: Peter Soetens  Tue Dec 21 22:43:07 CET 2004  TaskBrowser.cxx
00031 
00032                         TaskBrowser.cxx -  description
00033                            -------------------
00034     begin                : Tue December 21 2004
00035     copyright            : (C) 2004 Peter Soetens
00036     email                : peter.soetens@mech.kuleuven.ac.be
00037 
00038  ***************************************************************************
00039  *   This library is free software; you can redistribute it and/or         *
00040  *   modify it under the terms of the GNU Lesser General Public            *
00041  *   License as published by the Free Software Foundation; either          *
00042  *   version 2.1 of the License, or (at your option) any later version.    *
00043  *                                                                         *
00044  *   This library is distributed in the hope that it will be useful,       *
00045  *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
00046  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU     *
00047  *   Lesser General Public License for more details.                       *
00048  *                                                                         *
00049  *   You should have received a copy of the GNU Lesser General Public      *
00050  *   License along with this library; if not, write to the Free Software   *
00051  *   Foundation, Inc., 59 Temple Place,                                    *
00052  *   Suite 330, Boston, MA  02111-1307  USA                                *
00053  *                                                                         *
00054  ***************************************************************************/
00055 #endif
00056 
00057 
00058 #include <rtt/Logger.hpp>
00059 #include <rtt/extras/MultiVector.hpp>
00060 #include <rtt/types/TypeStream.hpp>
00061 #include <rtt/types/Types.hpp>
00062 #include "TaskBrowser.hpp"
00063 
00064 #include <rtt/scripting/TryCommand.hpp>
00065 #include <rtt/TaskContext.hpp>
00066 #include <rtt/plugin/PluginLoader.hpp>
00067 #include <rtt/scripting/parser-debug.hpp>
00068 #include <rtt/scripting/Parser.hpp>
00069 #include <rtt/scripting/parse_exception.hpp>
00070 #include <rtt/scripting/PeerParser.hpp>
00071 #include <rtt/scripting/Scripting.hpp>
00072 #include <rtt/plugin/PluginLoader.hpp>
00073 #include <rtt/internal/GlobalService.hpp>
00074 #include <rtt/types/GlobalsRepository.hpp>
00075 #include <rtt/internal/GlobalEngine.hpp>
00076 #include <boost/algorithm/string.hpp>
00077 
00078 #include <iostream>
00079 #include <fstream>
00080 #include <sstream>
00081 #include <iomanip>
00082 #include <deque>
00083 #include <stdio.h>
00084 #include <algorithm>
00085 
00086 #if defined(HAS_READLINE) && !defined(NO_GPL)
00087 # define USE_READLINE
00088 #endif
00089 #if defined(HAS_EDITLINE)
00090 // we use the readline bc wrapper:
00091 # define USE_READLINE
00092 # define USE_EDITLINE
00093 #endif
00094 // only use signals if posix, and pure readline
00095 # if defined(_POSIX_VERSION) && defined(HAS_READLINE) && !defined(HAS_EDITLINE)
00096 #   define USE_SIGNALS 1
00097 # endif
00098 
00099 
00100 #ifdef USE_READLINE
00101 # ifdef USE_EDITLINE
00102 #  include <editline/readline.h>
00103 # else
00104 #  include <readline/readline.h>
00105 #  include <readline/history.h>
00106 # endif
00107 #endif
00108 #include <boost/bind.hpp>
00109 #include <boost/lambda/lambda.hpp>
00110 
00111 #ifdef USE_SIGNALS
00112 #include <signal.h>
00113 #endif
00114 
00115 // we need to declare it since Xenomai does not declare it in any header
00116 #if defined(USE_SIGNALS) && defined(OROCOS_TARGET_XENOMAI) && CONFIG_XENO_VERSION_MAJOR == 2 && CONFIG_XENO_VERSION_MINOR >= 5
00117 extern "C"
00118 int xeno_sigwinch_handler(int sig, siginfo_t *si, void *ctxt);
00119 #endif
00120 namespace OCL
00121 {
00122     using namespace boost;
00123     using namespace std;
00124     using namespace RTT;
00125     using namespace RTT::detail;
00126 #ifdef USE_READLINE
00127     std::vector<std::string> TaskBrowser::candidates;
00128     std::vector<std::string> TaskBrowser::completes;
00129     std::vector<std::string>::iterator TaskBrowser::complete_iter;
00130     std::string TaskBrowser::component;
00131     std::string TaskBrowser::component_found;
00132     std::string TaskBrowser::peerpath;
00133     std::string TaskBrowser::text;
00134 #endif
00135     RTT::TaskContext* TaskBrowser::taskcontext = 0;
00136     Service::shared_ptr TaskBrowser::taskobject;
00137     RTT::TaskContext* TaskBrowser::peer = 0;
00138     RTT::TaskContext* TaskBrowser::tb = 0;
00139     RTT::TaskContext* TaskBrowser::context = 0;
00140 
00141     using boost::bind;
00142     using namespace RTT;
00143     using namespace std;
00144 
00145     string TaskBrowser::red;
00146     string TaskBrowser::green;
00147     string TaskBrowser::blue;
00148     std::deque<TaskContext*> taskHistory;
00149     std::string TaskBrowser::prompt("> ");
00150     std::string TaskBrowser::coloron;
00151     std::string TaskBrowser::underline;
00152     std::string TaskBrowser::coloroff;
00153 
00154 
00158     static std::ostream&
00159     nl(std::ostream& __os)
00160     { return __os.put(__os.widen('\n')); }
00161 
00162     // All readline specific functions
00163 #if defined(USE_READLINE)
00164 
00165     // Signal code only on Posix:
00166 #if defined(USE_SIGNALS)
00167 
00168     void TaskBrowser::rl_sigwinch_handler(int sig, siginfo_t *si, void *ctxt) {
00169 #if defined(OROCOS_TARGET_XENOMAI) && CONFIG_XENO_VERSION_MAJOR == 2 && CONFIG_XENO_VERSION_MINOR >= 5
00170         if (xeno_sigwinch_handler(sig, si, ctxt) == 0)
00171 #endif
00172             rl_resize_terminal();
00173     }
00174 #endif // USE_SIGNALS
00175 
00176     char *TaskBrowser::rl_gets ()
00177     {
00178         /* If the buffer has already been allocated,
00179            return the memory to the free pool. */
00180         if (line_read)
00181             {
00182 #ifdef _WIN32
00183 
00194           free(line_read);
00195 #else
00196                 free (line_read);
00197 #endif
00198                 line_read = 0;
00199             }
00200 
00201         /* Get a line from the user. */
00202         std::string p;
00203         if ( !macrorecording ) {
00204             p = prompt;
00205         } else {
00206             p = "> ";
00207         }
00208 #if defined(USE_SIGNALS)
00209 
00210         if (rl_set_signals() != 0)
00211             cerr << "Error setting signals !" <<endl;
00212 #endif
00213         line_read = readline ( p.c_str() );
00214 
00215         /* If the line has any text in it,
00216            save it on the history. */
00217         if (line_read && *line_read) {
00218             // do not store "quit"
00219             string s = line_read;
00220             if (s != "quit" && ! ( history_get( where_history() ) && s == string(history_get( where_history() )->line) ) ) {
00221 //                cout << "Where: " << where_history() << " history_get: " << ( history_get( where_history() ) ? history_get( where_history() )->line : "(null)") << endl;
00222 //                cout << "History: " << (current_history()  ? (const char*) current_history()->line : "(null)") << endl;
00223                 add_history (line_read);
00224             }
00225         }
00226         return (line_read);
00227     }
00228 
00229     char* TaskBrowser::dupstr( const char *s )
00230     {
00231         char * rv;
00232         // must be C-style :
00233         rv = (char*) malloc( strlen( s ) + 1 );
00234         strncpy( rv, s, strlen(s) + 1 );
00235         return rv;
00236     }
00237 
00238     char *TaskBrowser::command_generator( const char *_text, int state )
00239     {
00240         // first time called.
00241         if ( !state )
00242             {
00243                 // make a copy :
00244                 text = _text;
00245                 // rebuild a completion list
00246                 completes.clear();
00247                 find_completes();
00248                 complete_iter = completes.begin();
00249             }
00250         else
00251             ++complete_iter;
00252 
00253         // return zero if nothing more is found
00254         if ( complete_iter == completes.end() )
00255             return 0;
00256         // return the next completion option
00257         return  dupstr( complete_iter->c_str() ); // RL requires malloc !
00258     }
00259 
00264     void TaskBrowser::find_completes() {
00265         std::string::size_type pos;
00266         std::string::size_type startpos;
00267         std::string line( rl_line_buffer, rl_point );
00268 
00269         // complete on 'cd' or 'ls' :
00270         if ( line.find(std::string("cd ")) == 0 || line.find(std::string("ls ")) == 0) {
00271             //cerr <<endl<< "switch to :" << text<<endl;
00272 //             pos = text.rfind(".");
00273             pos = line.find(" ");      // pos+1 is first peername
00274             startpos = line.find_last_of(". "); // find last peer
00275             //cerr <<"startpos :"<<startpos<<endl;
00276             // start searching from component.
00277             peer = taskcontext;
00278             if ( pos+1 != line.length() ) // bounds check
00279                 peer = findPeer( line.substr(pos+1) );
00280 
00281             if (!peer)
00282                 return;
00283             //std::string peername = text.substring( pos+1, std::string::npos );
00284             RTT::TaskContext::PeerList v = peer->getPeerList();
00285             for (RTT::TaskContext::PeerList::iterator i = v.begin(); i != v.end(); ++i) {
00286                 std::string path;
00287                 if ( !( pos+1 > startpos) )
00288                     path = line.substr(pos+1, startpos - pos);
00289                 //cerr << "path :"<<path<<endl;
00290                 if ( *i == line.substr(startpos+1) )
00291                      completes.push_back( path + *i + ".");
00292                 else
00293                     if ( startpos == std::string::npos || startpos+1 == line.length() || i->find( line.substr(startpos+1)) == 0 )
00294                         completes.push_back( *i );
00295             }
00296             // Stop here if 'cd'
00297             if (line.find(std::string("cd ")) == 0)
00298                 return;
00299             // Add objects for 'ls'.
00300             v = peer->provides()->getProviderNames();
00301             for (RTT::TaskContext::PeerList::iterator i = v.begin(); i != v.end(); ++i) {
00302                 std::string path;
00303                 if ( !( pos+1 > startpos) )
00304                     path = line.substr(pos+1, startpos - pos);
00305                 //cerr << "provider:"<< *i << ", path :"<<path<<endl;
00306                 if ( *i == line.substr(startpos+1) )
00307                      completes.push_back( path + *i + ".");
00308                 else
00309                     if ( startpos == std::string::npos || startpos+1 == line.length() || i->find( line.substr(startpos+1)) == 0 )
00310                         completes.push_back( *i );
00311             }
00312             return; // do not add component names.
00313         }
00314 
00315         // TaskBrowser commands :
00316         if ( line.find(std::string(".")) == 0 ) {
00317             // first make a list of all sensible completions.
00318             std::vector<std::string> tbcoms;
00319             tbcoms.push_back(".loadProgram ");
00320             tbcoms.push_back(".unloadProgram ");
00321             tbcoms.push_back(".loadStateMachine ");
00322             tbcoms.push_back(".unloadStateMachine ");
00323             tbcoms.push_back(".light");
00324             tbcoms.push_back(".dark");
00325             tbcoms.push_back(".hex");
00326             tbcoms.push_back(".nohex");
00327             tbcoms.push_back(".nocolors");
00328             tbcoms.push_back(".connect");
00329             tbcoms.push_back(".record");
00330             tbcoms.push_back(".end");
00331             tbcoms.push_back(".cancel");
00332             tbcoms.push_back(".provide");
00333             tbcoms.push_back(".services");
00334             tbcoms.push_back(".typekits");
00335             tbcoms.push_back(".types");
00336 
00337             // then see which one matches the already typed line :
00338             for( std::vector<std::string>::iterator it = tbcoms.begin();
00339                  it != tbcoms.end();
00340                  ++it)
00341                 if ( it->find(line) == 0 )
00342                     completes.push_back( *it ); // if partial match, add.
00343             return;
00344         }
00345 
00346         if ( line.find(std::string("list ")) == 0
00347              || line.find(std::string("trace ")) == 0
00348              || line.find(std::string("untrace ")) == 0) {
00349             stringstream ss( line.c_str() ); // copy line into ss.
00350             string lcommand;
00351             ss >> lcommand;
00352             lcommand += ' ';
00353             std::vector<std::string> progs;
00354 
00355             if ( context->provides()->hasService("scripting") ) {
00356                 // THIS:
00357                 progs = context->getProvider<Scripting>("scripting")->getProgramList();
00358                 // then see which one matches the already typed line :
00359                 for( std::vector<std::string>::iterator it = progs.begin();
00360                         it != progs.end();
00361                         ++it) {
00362                     string res = lcommand + *it;
00363                     if ( res.find(line) == 0 )
00364                         completes.push_back( *it ); // if partial match, add.
00365                 }
00366                 progs = context->getProvider<Scripting>("scripting")->getStateMachineList();
00367                 for( std::vector<std::string>::iterator it = progs.begin();
00368                         it != progs.end();
00369                         ++it) {
00370                     string res = lcommand + *it;
00371                     if ( res.find(line) == 0 )
00372                         completes.push_back( *it ); // if partial match, add.
00373                 }
00374             }
00375             return;
00376         }
00377 
00378         startpos = text.find_last_of(",( ");
00379         if ( startpos == std::string::npos )
00380             startpos = 0;      // if none is found, start at beginning
00381 
00382         // complete on peers and objects, and find the peer the user wants completion for
00383         find_peers(startpos);
00384         // now proceed with 'this->peer' as TC,
00385         // this->taskobject as TO and
00386         // this->component as object and
00387         // this->peerpath as the text leading up to 'this->component'.
00388 
00389         // store the partial compname or peername
00390         std::string comp = component;
00391 
00392 
00393         // NEXT: use taskobject to complete commands, events, methods, attrs
00394         // based on 'component' (find trick).
00395         // if taskobject == peer, also complete properties
00396         find_ops();
00397 
00398         // TODO: concat two cases below as text.find("cd")...
00399         // check if the user is tabbing on an empty command, then add the console commands :
00400         if (  line.empty() ) {
00401             completes.push_back("cd ");
00402             completes.push_back("cd ..");
00403             completes.push_back("ls");
00404             completes.push_back("help");
00405             completes.push_back("quit");
00406             completes.push_back("list");
00407             completes.push_back("trace");
00408             completes.push_back("untrace");
00409             if (taskcontext == context)
00410                 completes.push_back("leave");
00411             else
00412                 completes.push_back("enter");
00413             // go on below to add components and tasks as well.
00414         }
00415 
00416         // only try this if text is not empty.
00417         if ( !text.empty() ) {
00418             if ( std::string( "cd " ).find(text) == 0 )
00419                 completes.push_back("cd ");
00420             if ( std::string( "ls" ).find(text) == 0 )
00421                 completes.push_back("ls");
00422             if ( std::string( "cd .." ).find(text) == 0 )
00423                 completes.push_back("cd ..");
00424             if ( std::string( "help" ).find(text) == 0 )
00425                 completes.push_back("help");
00426             if ( std::string( "quit" ).find(text) == 0 )
00427                 completes.push_back("quit");
00428             if ( std::string( "list " ).find(text) == 0 )
00429                 completes.push_back("list ");
00430             if ( std::string( "trace " ).find(text) == 0 )
00431                 completes.push_back("trace ");
00432             if ( std::string( "untrace " ).find(text) == 0 )
00433                 completes.push_back("untrace ");
00434 
00435             if (taskcontext == context && string("leave").find(text) == 0)
00436                 completes.push_back("leave");
00437 
00438             if (context == tb && string("enter").find(text) == 0)
00439                 completes.push_back("enter");
00440         }
00441     }
00442 
00443     void TaskBrowser::find_ops()
00444     {
00445         // the last (incomplete) text is stored in 'component'.
00446         // all attributes :
00447         std::vector<std::string> attrs;
00448         attrs = taskobject->getAttributeNames();
00449         for (std::vector<std::string>::iterator i = attrs.begin(); i!= attrs.end(); ++i ) {
00450             if ( i->find( component ) == 0 )
00451                 completes.push_back( peerpath + *i );
00452         }
00453         // all properties if RTT::TaskContext/Service:
00454         std::vector<std::string> props;
00455         taskobject->properties()->list(props);
00456         for (std::vector<std::string>::iterator i = props.begin(); i!= props.end(); ++i ) {
00457             if ( i->find( component ) == 0 ) {
00458                 completes.push_back( peerpath + *i );
00459             }
00460         }
00461 
00462         // methods:
00463         vector<string> comps = taskobject->getNames();
00464         for (std::vector<std::string>::iterator i = comps.begin(); i!= comps.end(); ++i ) {
00465             if ( i->find( component ) == 0  )
00466                 completes.push_back( peerpath + *i );
00467         }
00468 
00469         // types:
00470         comps = Types()->getDottedTypes();
00471         for (std::vector<std::string>::iterator i = comps.begin(); i!= comps.end(); ++i ) {
00472             if ( peerpath.empty() && i->find( component ) == 0  )
00473                 completes.push_back( *i );
00474         }
00475 
00476         // Global Attributes:
00477         comps = GlobalsRepository::Instance()->getAttributeNames();
00478         for (std::vector<std::string>::iterator i = comps.begin(); i!= comps.end(); ++i ) {
00479             if ( peerpath.empty() && i->find( component ) == 0  )
00480                 completes.push_back( *i );
00481         }
00482 
00483         // Global methods:
00484         if ( taskobject == peer->provides() && peer == context) {
00485             comps = GlobalService::Instance()->getNames();
00486             for (std::vector<std::string>::iterator i = comps.begin(); i!= comps.end(); ++i ) {
00487                 if ( i->find( component ) == 0  )
00488                     completes.push_back( peerpath + *i );
00489             }
00490         }
00491 
00492         // complete on types:
00493         bool try_deeper = false;
00494         try {
00495             Parser parser(GlobalEngine::Instance());
00496             DataSourceBase::shared_ptr result = parser.parseExpression( peerpath + component_found, context );
00497             if (result && !component.empty() ) {
00498                 vector<string> members = result->getMemberNames();
00499                 for (std::vector<std::string>::iterator i = members.begin(); i!= members.end(); ++i ) {
00500                     if ( string( component_found + "." + *i ).find( component ) == 0  )
00501                         completes.push_back( peerpath + component_found + "." + *i );
00502                     if ( component_found + "." + *i == component )
00503                         try_deeper = true;
00504                 }
00505             }
00506         } catch(...) {}
00507         // this is a hack to initiate a complete on a valid expression that might have members.
00508         // the completer above would only return the expression itself, while this one tries to 
00509         // go a level deeper again.
00510         if (try_deeper) {
00511             try {
00512                 Parser parser(GlobalEngine::Instance());
00513                 DataSourceBase::shared_ptr result = parser.parseExpression( peerpath + component, context );
00514                 if (result && !component.empty() ) {
00515                     vector<string> members = result->getMemberNames();
00516                     for (std::vector<std::string>::iterator i = members.begin(); i!= members.end(); ++i ) {
00517                         if (component_found + "." != component ) // catch corner case.
00518                             completes.push_back( peerpath + component + "." + *i );
00519                     }
00520                 }
00521             } catch(...) {}
00522         }
00523     }
00524 
00525     void TaskBrowser::find_peers( std::string::size_type startpos )
00526     {
00527         peerpath.clear();
00528         peer = context;
00529         taskobject = context->provides();
00530 
00531         std::string to_parse = text.substr(startpos);
00532         startpos = 0;
00533         std::string::size_type endpos = 0;
00534         // Traverse the entered peer-list
00535         component.clear();
00536         peerpath.clear();
00537         // This loop separates the peer/service from the member/method
00538         while (endpos != std::string::npos )
00539             {
00540                 bool itemfound = false;
00541                 endpos = to_parse.find(".");
00542                 if ( endpos == startpos ) {
00543                     component.clear();
00544                     break;
00545                 }
00546                 std::string item = to_parse.substr(startpos, endpos);
00547 
00548                 if ( taskobject->hasService( item ) ) {
00549                     taskobject = taskobject->provides(item);
00550                     itemfound = true;
00551                 } else
00552                     if ( peer->hasPeer( item ) ) {
00553                         peer = peer->getPeer( item );
00554                         taskobject = peer->provides();
00555                         itemfound = true;
00556                     } else if ( GlobalService::Instance()->hasService(item) ) {
00557                         taskobject = GlobalService::Instance()->provides(item);
00558                         itemfound = true;
00559                     }
00560                 if ( itemfound ) { // if "." found and correct path
00561                     peerpath += to_parse.substr(startpos, endpos) + ".";
00562                     if ( endpos != std::string::npos )
00563                         to_parse = to_parse.substr(endpos + 1);
00564                     else
00565                         to_parse.clear();
00566                     startpos = 0;
00567                 }
00568                 else {
00569                     // no match: typo or member name
00570                     // store the text until the last dot:
00571                     component_found = to_parse.substr(startpos, to_parse.rfind("."));
00572                     // store the complete text
00573                     component = to_parse.substr(startpos, std::string::npos);
00574                     break;
00575                 }
00576             }
00577 
00578         // now we got the peer and taskobject pointers,
00579         // the completed path in peerpath
00580         // the last partial path in component
00581 //         cout << "text: '" << text <<"'"<<endl;
00582 //         cout << "to_parse: '" << text <<"'"<<endl;
00583 //         cout << "Peerpath: '" << peerpath <<"'"<<endl;
00584         // cout <<endl<< "Component: '" << component <<"'"<<endl;
00585         // cout << "Component_found: '" << component_found <<"'"<<endl;
00586 
00587         RTT::TaskContext::PeerList v;
00588         if ( taskobject == peer->provides() ) {
00589             // add peer's completes:
00590             v = peer->getPeerList();
00591             for (RTT::TaskContext::PeerList::iterator i = v.begin(); i != v.end(); ++i) {
00592                 if ( i->find( component ) == 0 ) { // only add if match
00593                     completes.push_back( peerpath + *i );
00594                     completes.push_back( peerpath + *i + "." );
00595                     //cerr << "added " << peerpath+*i+"."<<endl;
00596                 }
00597             }
00598         }
00599         // add taskobject's completes:
00600         v = taskobject->getProviderNames();
00601         for (RTT::TaskContext::PeerList::iterator i = v.begin(); i != v.end(); ++i) {
00602             if ( i->find( component ) == 0 ) { // only add if match
00603                 completes.push_back( peerpath + *i );
00604                 if ( *i != "this" ) // "this." confuses our parsing lateron
00605                     completes.push_back( peerpath + *i + "." );
00606                 //cerr << "added " << peerpath+*i+"."<<endl;
00607             }
00608         }
00609         // add global service completes:
00610         if ( peer == context && taskobject == peer->provides() ) {
00611             v = GlobalService::Instance()->getProviderNames();
00612             for (RTT::TaskContext::PeerList::iterator i = v.begin(); i != v.end(); ++i) {
00613                 if ( i->find( component ) == 0 ) { // only add if match
00614                     completes.push_back( peerpath + *i );
00615                     if ( *i != "this" ) // "this." confuses our parsing lateron
00616                         completes.push_back( peerpath + *i + "." );
00617                     //cerr << "added " << peerpath+*i+"."<<endl;
00618                 }
00619             }
00620         }
00621         return;
00622     }
00623 
00624     char ** TaskBrowser::orocos_hmi_completion ( const char *text, int start, int end )
00625     {
00626         char **matches;
00627         matches = ( char ** ) 0;
00628 
00629         matches = rl_completion_matches ( text, &TaskBrowser::command_generator );
00630 
00631         return ( matches );
00632     }
00633 #endif // USE_READLINE
00634 
00635     TaskBrowser::TaskBrowser( RTT::TaskContext* _c )
00636         : RTT::TaskContext("TaskBrowser"),
00637           debug(0),
00638           line_read(0),
00639           lastc(0), storedname(""), storedline(-1),
00640           usehex(false),
00641           macrorecording(false)
00642     {
00643         tb = this;
00644         context = tb;
00645         this->switchTaskContext(_c);
00646 #ifdef USE_READLINE
00647         // we always catch sigwinch ourselves, in order to pass it on to Xenomai if necessary.
00648 #ifdef USE_SIGNALS
00649         rl_catch_sigwinch = 0;
00650 #endif
00651         rl_completion_append_character = '\0'; // avoid adding spaces
00652         rl_attempted_completion_function = &TaskBrowser::orocos_hmi_completion;
00653 
00654         using_history();
00655         if ( read_history(".tb_history") != 0 ) {
00656             read_history("~/.tb_history");
00657         }
00658 #ifdef USE_SIGNALS
00659         struct sigaction sa;
00660         sa.sa_sigaction = &TaskBrowser::rl_sigwinch_handler;
00661         sa.sa_flags = SA_SIGINFO | SA_RESTART;
00662         sigemptyset( &sa.sa_mask );
00663         sigaction(SIGWINCH, &sa, 0);
00664 #endif // USE_SIGNALS
00665 #endif // USE_READLINE
00666 
00667         this->setColorTheme( darkbg );
00668         this->enterTask();
00669     }
00670 
00671     TaskBrowser::~TaskBrowser() {
00672 #ifdef USE_READLINE
00673         if (line_read)
00674             {
00675                 free (line_read);
00676             }
00677         if ( write_history(".tb_history") != 0 ) {
00678             write_history("~/.tb_history");
00679         }
00680 #endif
00681     }
00682 
00686     char getTaskStatusChar(RTT::TaskContext* t)
00687     {
00688         if (t->inFatalError())
00689             return 'F';
00690         if (t->inRunTimeError())
00691             return 'E';
00692         if (t->inException())
00693             return 'X';
00694         if (t->isRunning() )
00695             return 'R'; // Running
00696         if (t->isConfigured() )
00697             return 'S'; // Stopped
00698         return 'U';     // Unconfigured/Preoperational
00699     }
00700 
00701     char getStateMachineStatusChar(RTT::TaskContext* t, string progname)
00702     {
00703         string ps = t->getProvider<Scripting>("scripting")->getStateMachineStatusStr(progname);
00704         return toupper(ps[0]);
00705     }
00706 
00707     char getProgramStatusChar(RTT::TaskContext* t, string progname)
00708     {
00709         string ps = t->getProvider<Scripting>("scripting")->getProgramStatusStr(progname);
00710         return toupper(ps[0]);
00711     }
00712 
00713     void str_trim(string& str, char to_trim)
00714     {
00715         string::size_type pos1 = str.find_first_not_of(to_trim);
00716         string::size_type pos2 = str.find_last_not_of(to_trim);
00717         if (pos1 == string::npos) 
00718             str.clear(); // nothing else present
00719         else
00720             str = str.substr(pos1, pos2 - pos1 + 1);
00721     }
00722 
00723 
00728     void TaskBrowser::loop()
00729     {
00730 #ifdef USE_SIGNALS
00731         // Let readline intercept relevant signals
00732         if(rl_catch_signals == 0)
00733             cerr << "Error: not catching signals !"<<endl;
00734         if (rl_set_signals() != 0)
00735             cerr << "Error setting signals !" <<endl;
00736 #endif
00737         cout << nl<<
00738             coloron <<
00739             "  This console reader allows you to browse and manipulate TaskContexts."<<nl<<
00740             "  You can type in an operation, expression, create or change variables."<<nl;
00741         cout <<"  (type '"<<underline<<"help"<<coloroff<<coloron<<"' for instructions and '"
00742                 <<underline<<"ls"<<coloroff<<coloron<<"' for context info)"<<nl<<nl;
00743 #ifdef USE_READLINE
00744         cout << "    TAB completion and HISTORY is available ('bash' like)" <<nl<<nl;
00745 #else
00746         cout << "    TAB completion and history is NOT available (LGPL-version)" <<nl<<nl;
00747 #endif
00748         cout << "    Use '"<<underline<<"Ctrl-D"<<coloroff<<coloron<<"' or type '"<<underline<<"quit"<<coloroff<<coloron<<"' to exit this program." <<coloroff<<nl<<nl;
00749 
00750         while (1) {
00751             try {
00752                 if (!macrorecording) {
00753                     if ( context == tb )
00754                         cout << green << " Watching " <<coloroff;
00755 
00756                     char state = getTaskStatusChar(taskcontext);
00757 
00758                     // sets prompt for readline:
00759 //                    prompt = green + taskcontext->getName() + coloroff + "[" + state + "]> ";
00760                     prompt = taskcontext->getName() + " [" + state + "]> ";
00761                     // This 'endl' is important because it flushes the whole output to screen of all
00762                     // processing that previously happened, which was using 'nl'.
00763                     cout.flush();
00764 
00765                     // print traces.
00766                     for (PTrace::iterator it = ptraces.begin(); it != ptraces.end(); ++it) {
00767                         RTT::TaskContext* progpeer = it->first.first;
00768                         int line = progpeer->getProvider<Scripting>("scripting")->getProgramLine(it->first.second);
00769                         if ( line != it->second ) {
00770                             it->second = line;
00771                             printProgram( it->first.second, -1, progpeer );
00772                         }
00773                     }
00774 
00775                     for (PTrace::iterator it = straces.begin(); it != straces.end(); ++it) {
00776                         RTT::TaskContext* progpeer = it->first.first;
00777                         int line = progpeer->getProvider<Scripting>("scripting")->getStateMachineLine(it->first.second);
00778                         if ( line != it->second ) {
00779                             it->second = line;
00780                             printProgram( it->first.second, -1, progpeer );
00781                         }
00782                     }
00783                 }
00784                 // Check port status:
00785                 checkPorts();
00786                 std::string command;
00787                 // When using rxvt on windows, the process will receive signals when the arrow keys are used
00788                 // during input. We compile with /EHa to catch these signals and don't print anything.
00789                 try {
00790 #ifdef USE_READLINE
00791                 const char* const commandStr = rl_gets();
00792                 // quit on EOF (Ctrl-D)
00793                 command = commandStr ? commandStr : "quit"; // copy over to string
00794 #else
00795                 cout << prompt;
00796                 getline(cin,command);
00797                 if (!cin) // Ctrl-D
00798                     command = "quit";
00799 #endif
00800                 } catch(std::exception& e) {
00801                     cerr << "The command line reader throwed a std::exception: '"<< e.what()<<"'."<<endl;
00802                 } catch (...) {
00803                     cerr << "The command line reader throwed an exception." <<endlog();
00804                 }
00805                 str_trim( command, ' ');
00806                 cout << coloroff;
00807                 if ( command == "quit" ) {
00808                     // Intercept no Ctrl-C
00809                     cout << endl;
00810                     return;
00811                 } else if ( command == "help") {
00812                     printHelp();
00813                 } else if ( command.find("help ") == 0) {
00814                     printHelp( command.substr(command.rfind(' ')));
00815                 } else if ( command == "#debug") {
00816                     debug = !debug;
00817                 } else if ( command.find("list ") == 0 || command == "list" ) {
00818                     browserAction(command);
00819                 } else if ( command.find("trace ") == 0 || command == "trace" ) {
00820                     browserAction(command);
00821                 } else if ( command.find("untrace ") == 0 || command == "untrace" ) {
00822                     browserAction(command);
00823                 } else if ( command.find("ls") == 0 ) {
00824                     std::string::size_type pos = command.find("ls")+2;
00825                     command = std::string(command, pos, command.length());
00826                     str_trim( command, ' ');
00827                     printInfo( command );
00828                 } else if ( command == "" ) { // nop
00829                 } else if ( command.find("cd ..") == 0  ) {
00830                     this->switchBack( );
00831                 } else if ( command.find("enter") == 0  ) {
00832                     this->enterTask();
00833                 } else if ( command.find("leave") == 0  ) {
00834                     this->leaveTask();
00835                 } else if ( command.find("cd ") == 0  ) {
00836                     std::string::size_type pos = command.find("cd")+2;
00837                     command = std::string(command, pos, command.length());
00838                     this->switchTaskContext( command );
00839                 } else if ( command.find(".") == 0  ) {
00840                     command = std::string(command, 1, command.length());
00841                     this->browserAction( command );
00842                 } else if ( macrorecording) {
00843                     macrotext += command +'\n';
00844                 } else {
00845                     try {
00846                         this->evalCommand( command );
00847                     } catch(std::exception& e) {
00848                         cerr << "The command '"<<command<<"' caused a std::exception: '"<< e.what()<<"' and could not be completed."<<endl;
00849                     } catch(...){
00850                         cerr << "The command '"<<command<<"' caused an unknown exception and could not be completed."<<endl;
00851                     }
00852                     // a command was typed... clear storedline such that a next 'list'
00853                     // shows the 'IP' again.
00854                     storedline = -1;
00855                 }
00856                 //cout <<endl;
00857             } catch(std::exception& e) {
00858                 cerr << "Warning: The command caused a std::exception: '"<< e.what()<<"' in the TaskBrowser's loop() function."<<endl;
00859             } catch(...) {
00860                 cerr << "Warning: The command caused an exception in the TaskBrowser's loop() function." << endl;
00861             }
00862          }
00863     }
00864 
00865     void TaskBrowser::enterTask()
00866     {
00867         if ( context == taskcontext ) {
00868             log(Info) <<"Already in Task "<< taskcontext->getName()<<endlog();
00869             return;
00870         }
00871         context = taskcontext;
00872         log(Info) <<"Entering Task "<< taskcontext->getName()<<endlog();
00873     }
00874 
00875     void TaskBrowser::leaveTask()
00876     {
00877         if ( context == tb ) {
00878             log(Info) <<"Already watching Task "<< taskcontext->getName()<<endlog();
00879             return;
00880         }
00881         context = tb;
00882         log(Info) <<"Watching Task "<< taskcontext->getName()<<endlog();
00883     }
00884 
00885     void TaskBrowser::recordMacro(std::string name)
00886     {
00887         if (macrorecording) {
00888             log(Error)<< "Macro already active." <<endlog();
00889             return;
00890         }
00891         if (context->provides()->hasService("scripting") == false) {
00892             log(Error)<< "Can not create a macro in a TaskContext without scripting service." <<endlog();
00893             return;
00894         }
00895         if ( name.empty() ) {
00896             cerr << "Please specify a macro name." <<endl;
00897             return;
00898         } else {
00899             cout << "Recording macro "<< name <<endl;
00900             cout << "Use program scripting syntax (do, set,...) !" << endl <<endl;
00901             cout << "export function "<< name<<" {"<<endl;
00902         }
00903         macrorecording = true;
00904         macroname = name;
00905     }
00906 
00907     void TaskBrowser::cancelMacro() {
00908         if (!macrorecording) {
00909             log(Warning)<< "Macro recording was not active." <<endlog();
00910             return;
00911         }
00912         cout << "Canceling macro "<< macroname <<endl;
00913         macrorecording = false;
00914         macrotext.clear();
00915     }
00916 
00917     void TaskBrowser::endMacro() {
00918         if (!macrorecording) {
00919             log(Warning)<< "Macro recording was not active." <<endlog();
00920             return;
00921         }
00922         string fname = macroname + ".ops";
00923         macrorecording = false;
00924         cout << "}" <<endl;
00925         cout << "Saving file "<< fname <<endl;
00926         ofstream macrofile( fname.c_str() );
00927         macrofile << "/* TaskBrowser macro '"<<macroname<<"' */" <<endl<<endl;
00928         macrofile << "export function "<<macroname<<" {"<<endl;
00929         macrofile << macrotext.c_str();
00930         macrofile << "}"<<endl;
00931         macrotext.clear();
00932 
00933         cout << "Loading file "<< fname <<endl;
00934         context->getProvider<Scripting>("Scripting")->loadPrograms(fname);
00935     }
00936 
00937     void TaskBrowser::switchBack()
00938     {
00939         if ( taskHistory.size() == 0)
00940             return;
00941 
00942         this->switchTaskContext( taskHistory.front(), false ); // store==false
00943         lastc = 0;
00944         taskHistory.pop_front();
00945     }
00946 
00947     void TaskBrowser::checkPorts()
00948     {
00949         // check periodically if the taskcontext did not change its ports.
00950 
00951         DataFlowInterface::Ports ports;
00952         ports = this->ports()->getPorts();
00953         for( DataFlowInterface::Ports::iterator i=ports.begin(); i != ports.end(); ++i) {
00954             // If our port is no longer connected, try to reconnect.
00955             base::PortInterface* p = *i;
00956             base::PortInterface* tcp = taskcontext->ports()->getPort( p->getName() );
00957             if ( p->connected() == false || tcp == 0 || tcp->connected() == false) {
00958                 this->ports()->removePort( p->getName() );
00959                 delete p;
00960             }
00961         }
00962     }
00963 
00964     void TaskBrowser::setColorTheme(ColorTheme t)
00965     {
00966         // background color palettes:
00967         const char* dbg = "\033[01;";
00968         const char* wbg = "\033[02;";
00969         // colors in palettes:
00970         const char* r = "31m";
00971         const char* g = "32m";
00972         const char* b = "34m";
00973         const char* con = "31m";
00974         const char* coff = "\33[0m";
00975         const char* und  = "\33[4m";
00976 
00977         switch (t)
00978             {
00979             case nocolors:
00980                 green.clear();
00981                 red.clear();
00982                 blue.clear();
00983                 coloron.clear();
00984                 coloroff.clear();
00985                 underline.clear();
00986                 return;
00987                 break;
00988             case darkbg:
00989                 green = dbg;
00990                 red = dbg;
00991                 blue = dbg;
00992                 coloron = dbg;
00993                 coloroff = wbg;
00994                 break;
00995             case whitebg:
00996                 green = wbg;
00997                 red = wbg;
00998                 blue = wbg;
00999                 coloron = wbg;
01000                 coloroff = wbg;
01001                 break;
01002             }
01003         green += g;
01004         red += r;
01005         blue += b;
01006         coloron += con;
01007         coloroff = coff;
01008         underline = und;
01009     }
01010 
01011     void TaskBrowser::switchTaskContext(std::string& c) {
01012         // if nothing new found, return.
01013         peer = taskcontext;
01014         if ( this->findPeer( c + "." ) == 0 ) {
01015             cerr << "No such peer: "<< c <<nl;
01016             return;
01017         }
01018 
01019         if ( peer == taskcontext ) {
01020             cerr << "Already in "<< c <<nl;
01021             return;
01022         }
01023 
01024         if ( peer == tb ) {
01025             cerr << "Can not switch to TaskBrowser." <<nl;
01026             return;
01027         }
01028 
01029         // findPeer has set 'peer' :
01030         this->switchTaskContext( peer );
01031     }
01032 
01033     void TaskBrowser::switchTaskContext(RTT::TaskContext* tc, bool store) {
01034         // put current on the stack :
01035         if (taskHistory.size() == 20 )
01036             taskHistory.pop_back();
01037         if ( taskcontext && store)
01038             taskHistory.push_front( taskcontext );
01039 
01040         // disconnect from current peers.
01041         this->disconnect();
01042 
01043         // cleanup port left-overs.
01044         DataFlowInterface::Ports tports = this->ports()->getPorts();
01045         for( DataFlowInterface::Ports::iterator i=tports.begin(); i != tports.end(); ++i) {
01046             this->ports()->removePort( (*i)->getName() );
01047             delete *i;
01048         }
01049 
01050         // now switch to new one :
01051         if ( context == taskcontext )
01052             context = tc;
01053         taskcontext = tc; // peer is the new taskcontext.
01054         lastc = 0;
01055 
01056         // connect peer.
01057         this->addPeer( taskcontext );
01058 
01059         // map data ports.
01060         // create 'anti-ports' to allow port-level interaction with the peer.
01061         tports = taskcontext->ports()->getPorts();
01062         if ( !tports.empty() )
01063             cout <<nl << "TaskBrowser connects to all data ports of "<<taskcontext->getName()<<endl;
01064         for( DataFlowInterface::Ports::iterator i=tports.begin(); i != tports.end(); ++i) {
01065             if (this->ports()->getPort( (*i)->getName() ) == 0 )
01066                 this->ports()->addPort( *(*i)->antiClone() );
01067         }
01068         RTT::connectPorts(this,taskcontext);
01069 
01070 
01071 
01072         cerr << "   Switched to : " << taskcontext->getName() <<endl;
01073 
01074     }
01075 
01076     RTT::TaskContext* TaskBrowser::findPeer(std::string c) {
01077         // returns the one but last peer, which is the one we want.
01078         std::string s( c );
01079 
01080         our_pos_iter_t parsebegin( s.begin(), s.end(), "teststring" );
01081         our_pos_iter_t parseend;
01082 
01083         CommonParser cp;
01084         scripting::PeerParser pp( peer, cp, true );
01085         bool skipref = true;
01086         try {
01087             parse( parsebegin, parseend, pp.parser(), SKIP_PARSER );
01088         }
01089         catch( ... )
01090             {
01091                 log(Debug) <<"No such peer : "<< c <<endlog();
01092                 return 0;
01093             }
01094         taskobject = pp.taskObject();
01095         peer = pp.peer();
01096         return pp.peer();
01097     }
01098 
01099     void TaskBrowser::browserAction(std::string& act)
01100     {
01101         std::stringstream ss(act);
01102         std::string instr;
01103         ss >> instr;
01104 
01105         if ( instr == "list" ) {
01106             if (context->provides()->hasService("scripting") == false) {
01107                 log(Error)<< "Can not list a program in a TaskContext without scripting service." <<endlog();
01108                 return;
01109             }
01110             int line;
01111             ss >> line;
01112             if (ss) {
01113                 this->printProgram(line);
01114                 return;
01115             }
01116             ss.clear();
01117             string arg;
01118             ss >> arg;
01119             if (ss) {
01120                 ss.clear();
01121                 ss >> line;
01122                 if (ss) {
01123                     // progname and line given
01124                     this->printProgram(arg, line);
01125                     return;
01126                 }
01127                 // only progname given.
01128                 this->printProgram( arg );
01129                 return;
01130             }
01131             // just 'list' :
01132             this->printProgram();
01133             return;
01134         }
01135 
01136         //
01137         // TRACING
01138         //
01139         if ( instr == "trace") {
01140             if (context->provides()->hasService("scripting") == false) {
01141                 log(Error)<< "Can not trace a program in a TaskContext without scripting service." <<endlog();
01142                 return;
01143             }
01144 
01145             string arg;
01146             ss >> arg;
01147             if (ss) {
01148                 bool pi = context->getProvider<Scripting>("scripting")->hasProgram(arg);
01149                 if (pi) {
01150                     ptraces[make_pair(context, arg)] = context->getProvider<Scripting>("scripting")->getProgramLine(arg); // store current line number.
01151                     this->printProgram( arg );
01152                     return;
01153                 }
01154                 pi = context->getProvider<Scripting>("scripting")->hasStateMachine(arg);
01155                 if (pi) {
01156                     straces[make_pair(context, arg)] = context->getProvider<Scripting>("scripting")->getStateMachineLine(arg); // store current line number.
01157                     this->printProgram( arg );
01158                     return;
01159                 }
01160                 cerr <<"No such program or state machine: "<< arg <<endl;
01161                 return;
01162             }
01163 
01164             // just 'trace' :
01165             std::vector<std::string> names;
01166             names = context->getProvider<Scripting>("scripting")->getProgramList();
01167             for (std::vector<std::string>::iterator it = names.begin(); it != names.end(); ++it) {
01168                 bool pi = context->getProvider<Scripting>("scripting")->hasProgram(arg);
01169                 if (pi)
01170                     ptraces[make_pair(context, arg)] = context->getProvider<Scripting>("scripting")->getProgramLine(arg); // store current line number.
01171             }
01172 
01173             names = context->getProvider<Scripting>("scripting")->getStateMachineList();
01174             for (std::vector<std::string>::iterator it = names.begin(); it != names.end(); ++it) {
01175                 bool pi = context->getProvider<Scripting>("scripting")->hasStateMachine(arg);
01176                 if (pi)
01177                     straces[make_pair(context, arg)] = context->getProvider<Scripting>("scripting")->getStateMachineLine(arg); // store current line number.
01178             }
01179 
01180             cerr << "Tracing all programs and state machines in "<< context->getName() << endl;
01181             return;
01182         }
01183 
01184         if ( instr == "untrace") {
01185             if (context->provides()->hasService("scripting") == false) {
01186                 log(Error)<< "Can not untrace a program in a TaskContext without scripting service." <<endlog();
01187                 return;
01188             }
01189             string arg;
01190             ss >> arg;
01191             if (ss) {
01192                 ptraces.erase( make_pair(context, arg) );
01193                 straces.erase( make_pair(context, arg) );
01194                 cerr <<"Untracing "<< arg <<" of "<< context->getName()<<endl;
01195                 return;
01196             }
01197             // just 'untrace' :
01198             std::vector<std::string> names;
01199             names = context->getProvider<Scripting>("scripting")->getProgramList();
01200             for (std::vector<std::string>::iterator it = names.begin(); it != names.end(); ++it) {
01201                 bool pi = context->getProvider<Scripting>("scripting")->hasProgram(arg);
01202                 if (pi)
01203                     ptraces.erase(make_pair(context, arg));
01204             }
01205 
01206             names = context->getProvider<Scripting>("scripting")->getStateMachineList();
01207             for (std::vector<std::string>::iterator it = names.begin(); it != names.end(); ++it) {
01208                 bool pi = context->getProvider<Scripting>("scripting")->hasStateMachine(arg);
01209                 if (pi)
01210                     straces.erase(make_pair(context, arg));
01211             }
01212 
01213             cerr << "Untracing all programs and state machines of "<< context->getName() << endl;
01214             return;
01215         }
01216 
01217         std::string arg;
01218         ss >> arg;
01219         if ( instr == "dark") {
01220             this->setColorTheme(darkbg);
01221             cout << nl << "Setting Color Theme for "+green+"dark"+coloroff+" backgrounds."<<endl;
01222             return;
01223         }
01224         if ( instr == "light") {
01225             this->setColorTheme(whitebg);
01226             cout << nl << "Setting Color Theme for "+green+"light"+coloroff+" backgrounds."<<endl;
01227             return;
01228         }
01229         if ( instr == "nocolors") {
01230             this->setColorTheme(nocolors);
01231             cout <<nl << "Disabling all colors"<<endl;
01232             return;
01233         }
01234         if ( instr == "record") {
01235             recordMacro( arg );
01236             return;
01237         }
01238         if ( instr == "cancel") {
01239             cancelMacro();
01240             return;
01241         }
01242         if ( instr == "end") {
01243             endMacro();
01244             return;
01245         }
01246         if ( instr == "hex") {
01247             usehex = true;
01248             cout << "Switching to hex notation for output (use .nohex to revert)." <<endl;
01249             return;
01250         }
01251         if ( instr == "nohex") {
01252             usehex = false;
01253             cout << "Turning off hex notation for output." <<endl;
01254             return;
01255         }
01256         if ( instr == "provide") {
01257             while ( ss ) {
01258                 cout << "Trying to locate service '" << arg << "'..."<<endl;
01259                 if ( PluginLoader::Instance()->loadService(arg, context) )
01260                     cout << "Service '"<< arg << "' loaded in " << context->getName() << endl;
01261                 else
01262                     cout << "Service not found." <<endl;
01263                 ss >> arg;
01264             }
01265             return;
01266         }
01267         if (instr == "services") {
01268             vector<string> names = PluginLoader::Instance()->listServices();
01269             cout << "Available Services: ";
01270             for (std::vector<std::string>::iterator it = names.begin(); it != names.end(); ++it) {
01271                 cout << " " << *it;
01272             }
01273             cout <<endl;
01274             return;
01275         }
01276         if (instr == "typekits") {
01277             vector<string> names = PluginLoader::Instance()->listTypekits();
01278             cout << "Available Typekits: ";
01279             for (std::vector<std::string>::iterator it = names.begin(); it != names.end(); ++it) {
01280                 cout << " " << *it;
01281             }
01282             cout <<endl;
01283             return;
01284         }
01285         if (instr == "types") {
01286             vector<string> names = TypeInfoRepository::Instance()->getDottedTypes();
01287             cout << "Available data types: ";
01288             for (std::vector<std::string>::iterator it = names.begin(); it != names.end(); ++it) {
01289                 cout << " " << *it;
01290             }
01291             cout <<endl;
01292             return;
01293         }
01294         cerr << "Unknown Browser Action : "<< act <<endl;
01295         cerr << "See 'help' for valid syntax."<<endl;
01296     }
01297 
01298     void TaskBrowser::evaluate(std::string& comm) {
01299         this->evalCommand(comm);
01300     }
01301 
01302     Service::shared_ptr TaskBrowser::stringToService(string const& names) {
01303         Service::shared_ptr serv;
01304         std::vector<std::string> strs;
01305         boost::split(strs, names, boost::is_any_of("."));
01306 
01307         // strs could be empty because of a bug in Boost 1.44 (see https://svn.boost.org/trac/boost/ticket/4751)
01308         if (strs.empty()) return serv;
01309 
01310         string component = strs.front();
01311         if (! context->hasPeer(component) && !context->provides()->hasService(component) ) {
01312             return serv;
01313         }
01314         // We only support help for peer or subservice:
01315         if ( context->hasPeer(component) )
01316             serv = context->getPeer(component)->provides();
01317         else if (context->provides()->hasService(component))
01318             serv = context->provides(component);
01319 
01320         // remove component name:
01321         strs.erase( strs.begin() );
01322 
01323         // iterate over remainders:
01324         while ( !strs.empty() && serv) {
01325             serv = serv->getService( strs.front() );
01326             if (serv)
01327                 strs.erase( strs.begin() );
01328         }
01329         return serv;
01330     }
01331 
01332 
01333 
01334     bool TaskBrowser::printService( string name ) {
01335         bool result = false;
01336         Service::shared_ptr ops = stringToService(name);
01337         ServiceRequester::shared_ptr sr;
01338 
01339         if ( ops || GlobalService::Instance()->hasService( name ) ) // only object name was typed
01340             {
01341                 if ( !ops )
01342                     ops = GlobalService::Instance()->provides(name);
01343                 sresult << nl << "Printing Interface of '"<< coloron << ops->getName() <<coloroff <<"' :"<<nl<<nl;
01344                 vector<string> methods = ops->getNames();
01345                 std::for_each( methods.begin(), methods.end(), boost::bind(&TaskBrowser::printOperation, this, _1, ops) );
01346                 cout << sresult.str();
01347                 sresult.str("");
01348                 result = true;
01349             }
01350         if ( context->requires()->requiresService( name ) ) // only object name was typed
01351             {
01352                 sr = context->requires(name);
01353                 sresult << nl << "Requiring '"<< coloron << sr->getRequestName() <<coloroff <<"' with methods: ";
01354                 vector<string> methods = sr->getOperationCallerNames();
01355                 sresult << coloron;
01356                 std::for_each( methods.begin(), methods.end(), sresult << lambda::_1 <<" " );
01357                 cout << sresult.str() << coloroff << nl;
01358                 sresult.str("");
01359                 result = true;
01360             }
01361         return result;
01362     }
01363 
01364     void TaskBrowser::evalCommand(std::string& comm )
01365     {
01366         // deprecated: use 'help servicename'
01367         bool result = printService(comm);
01368 
01369         // Minor hack : also check if it was an attribute of current TC, for example,
01370         // if both the object and attribute with that name exist. the if
01371         // statement after this one would return and not give the expr parser
01372         // time to evaluate 'comm'.
01373         if ( context->provides()->getValue( comm ) ) {
01374             if (debug)
01375                 cerr << "Found value..."<<nl;
01376                 this->printResult( context->provides()->getValue( comm )->getDataSource().get(), true );
01377                 cout << sresult.str()<<nl;
01378                 sresult.str("");
01379                 return;
01380         }
01381 
01382         if ( result ) {
01383             return;
01384         }
01385 
01386         // Set caller=0 to have correct call/send semantics.
01387         // we're outside the updateHook(). Passing 'this' would
01388         // trigger the EE of the TB, but not our own function.
01389         scripting::Parser _parser( GlobalEngine::Instance() );
01390 
01391         if (debug)
01392             cerr << "Trying ValueStatement..."<<nl;
01393         try {
01394             // Check if it was a method or datasource :
01395             last_expr = _parser.parseValueStatement( comm, context );
01396             // methods and DS'es are processed immediately.
01397             if ( last_expr ) {
01398                 // only print if no ';' was given.
01399                 assert( comm.size() != 0 );
01400                 if ( comm[ comm.size() - 1 ] != ';' ) {
01401                     this->printResult( last_expr.get(), true );
01402                     cout << sresult.str() << nl <<endl;
01403                     sresult.str("");
01404                 } else
01405                     last_expr->evaluate();
01406                 return; // done here
01407             } else if (debug)
01408                 cerr << "returned (null) !"<<nl;
01409             //cout << "    (ok)" <<nl;
01410             //return; //
01411         } catch ( fatal_semantic_parse_exception& pe ) { // incorr args, ...
01412             // way to fatal,  must be reported immediately
01413             if (debug)
01414                 cerr << "fatal_semantic_parse_exception: ";
01415             cerr << pe.what() <<nl;
01416             return;
01417         } catch ( syntactic_parse_exception& pe ) { // wrong content after = sign etc..
01418             // syntactic errors must be reported immediately
01419             if (debug)
01420                 cerr << "syntactic_parse_exception: ";
01421             cerr << pe.what() <<nl;
01422             return;
01423         } catch ( parse_exception_parser_fail &pe )
01424             {
01425                 // ignore, try next parser
01426                 if (debug) {
01427                     cerr << "Ignoring ValueStatement exception :"<<nl;
01428                     cerr << pe.what() <<nl;
01429                 }
01430         } catch ( parse_exception& pe ) {
01431             // syntactic errors must be reported immediately
01432             if (debug)
01433                 cerr << "parse_exception :";
01434             cerr << pe.what() <<nl;
01435             return;
01436         }
01437         if (debug)
01438             cerr << "Trying Expression..."<<nl;
01439         try {
01440             // Check if it was a method or datasource :
01441             last_expr = _parser.parseExpression( comm, context );
01442             // methods and DS'es are processed immediately.
01443             if ( last_expr ) {
01444                 // only print if no ';' was given.
01445                 assert( comm.size() != 0 );
01446                 if ( comm[ comm.size() - 1 ] != ';' ) {
01447                     this->printResult( last_expr.get(), true );
01448                     cout << sresult.str() << nl << endl;
01449                     sresult.str("");
01450                 } else
01451                     last_expr->evaluate();
01452                 return; // done here
01453             } else if (debug)
01454                 cerr << "returned (null) !"<<nl;
01455         } catch ( syntactic_parse_exception& pe ) { // missing brace etc
01456             // syntactic errors must be reported immediately
01457             if (debug)
01458                 cerr << "syntactic_parse_exception :";
01459             cerr << pe.what() <<nl;
01460             return;
01461         } catch ( fatal_semantic_parse_exception& pe ) { // incorr args, ...
01462             // way to fatal,  must be reported immediately
01463             if (debug)
01464                 cerr << "fatal_semantic_parse_exception :";
01465             cerr << pe.what() <<nl;
01466             return;
01467         } catch ( parse_exception_parser_fail &pe )
01468             {
01469                 // We're the last parser!
01470                 if (debug)
01471                     cerr << "Ignoring Expression exception :"<<nl;
01472                 cerr << pe.what() <<nl;
01473 
01474         } catch ( parse_exception& pe ) {
01475                 // We're the last parser!
01476                 if (debug)
01477                     cerr << "Ignoring Expression parse_exception :"<<nl;
01478                 cerr << pe.what() <<nl;
01479         }
01480     }
01481 
01482     void TaskBrowser::printResult( base::DataSourceBase* ds, bool recurse) {
01483         std::string prompt(" = ");
01484         // setup prompt :
01485         sresult <<prompt<< setw(20)<<left;
01486         if ( ds )
01487             doPrint( ds, recurse );
01488         else
01489             sresult << "(null)";
01490         sresult << right;
01491     }
01492 
01493     void TaskBrowser::doPrint( base::DataSourceBase::shared_ptr ds, bool recurse) {
01494         if (!ds) {
01495             sresult << "(null)";
01496             return;
01497         }
01498 
01499         // this is needed for ds's that rely on initialision.
01500         // e.g. eval true once or time measurements.
01501         // becomes only really handy for 'watches' (to deprecate).
01502         ds->reset();
01503         // this is needed to read a ds's value. Otherwise, a cached value may be returned.
01504         ds->evaluate();
01505 
01506         DataSource<RTT::PropertyBag>* dspbag = DataSource<RTT::PropertyBag>::narrow(ds.get());
01507         if (dspbag) {
01508             RTT::PropertyBag bag( dspbag->get() );
01509             if (!recurse) {
01510                 int siz = bag.getProperties().size();
01511                 int wdth = siz ? (20 - (siz / 10 + 1)) : 20;
01512                 sresult <<setw(0)<< siz <<setw( wdth )<< " Properties";
01513             } else {
01514             if ( ! bag.empty() ) {
01515                 sresult <<setw(0)<<nl;
01516                 for( RTT::PropertyBag::iterator it= bag.getProperties().begin(); it!=bag.getProperties().end(); ++it) {
01517                     sresult <<setw(14)<<right<< Types()->toDot( (*it)->getType() )<<" "<<coloron<<setw(14)<< (*it)->getName()<<coloroff;
01518                     base::DataSourceBase::shared_ptr propds = (*it)->getDataSource();
01519                     this->printResult( propds.get(), false );
01520                     sresult <<" ("<<(*it)->getDescription()<<')' << nl;
01521                 }
01522             } else {
01523                 sresult <<prompt<<"(empty RTT::PropertyBag)";
01524             }
01525             }
01526             return;
01527         }
01528 
01529         // Print the members of the type:
01530         base::DataSourceBase::shared_ptr dsb(ds);
01531         if (dsb->getMemberNames().empty() || dsb->getTypeInfo()->isStreamable() ) {
01532             if (debug) cerr << "terminal item " << dsb->getTypeName() << nl;
01533             if (usehex)
01534                 sresult << std::hex << dsb;
01535             else
01536                 sresult << std::dec << dsb;
01537         } else {
01538             sresult << setw(0);
01539             sresult << "{";
01540             vector<string> names = dsb->getMemberNames();
01541             if ( find(names.begin(), names.end(), "capacity") != names.end() &&
01542                     find(names.begin(), names.end(), "size") != names.end() ) {
01543                 // is a container/sequence:
01544                 DataSource<int>::shared_ptr seq_size = dynamic_pointer_cast<DataSource<int> >(dsb->getMember("size"));
01545                 if (seq_size) {
01546                     ValueDataSource<unsigned int>::shared_ptr index = new ValueDataSource<unsigned int>(0);
01547                     // print max 10 items of sequence:
01548                     sresult << " [";
01549                     for (int i=0; i != seq_size->get(); ++i) {
01550                         index->set( i );
01551                         if (i == 10) {
01552                             sresult << "...("<< seq_size->get() - 10 <<" items omitted)...";
01553                             break;
01554                         } else {
01555                             DataSourceBase::shared_ptr element = dsb->getMember(index, DataSourceBase::shared_ptr() );
01556                             doPrint(element, true);
01557                             if (i+1 != seq_size->get())
01558                                 sresult <<", ";
01559                         }
01560                     }
01561                     sresult << " ], "; // size and capacity will follow...
01562                 }
01563             }
01564             for(vector<string>::iterator it = names.begin(); it != names.end(); ) {
01565                 sresult  << *it << " = ";
01566                 doPrint( dsb->getMember(*it), true);
01567                 if (++it != names.end())
01568                     sresult <<", ";
01569             }
01570             sresult <<" }";
01571         }
01572     }
01573 
01574     struct comcol
01575     {
01576         const char* command;
01577         comcol(const char* c) :command(c) {}
01578         std::ostream& operator()( std::ostream& os ) const {
01579             os<<"'"<< TaskBrowser::coloron<< TaskBrowser::underline << command << TaskBrowser::coloroff<<"'";
01580             return os;
01581         }
01582     };
01583 
01584     struct keycol
01585     {
01586         const char* command;
01587         keycol(const char* c) :command(c) {}
01588         std::ostream& operator()( std::ostream& os )const {
01589             os<<"<"<< TaskBrowser::coloron<< TaskBrowser::underline << command << TaskBrowser::coloroff<<">";
01590             return os;
01591         }
01592     };
01593 
01594     struct titlecol
01595     {
01596         const char* command;
01597         titlecol(const char* c) :command(c) {}
01598         std::ostream& operator()( std::ostream& os ) const {
01599             os<<endl<<"["<< TaskBrowser::coloron<< TaskBrowser::underline << command << TaskBrowser::coloroff<<"]";
01600             return os;
01601         }
01602     };
01603 
01604     std::ostream& operator<<(std::ostream& os, comcol f ){
01605         return f(os);
01606     }
01607 
01608     std::ostream& operator<<(std::ostream& os, keycol f ){
01609         return f(os);
01610     }
01611 
01612     std::ostream& operator<<(std::ostream& os, titlecol f ){
01613         return f(os);
01614     }
01615 
01616     void TaskBrowser::printHelp()
01617     {
01618         cout << coloroff;
01619         cout <<titlecol("Task Browsing")<<nl;
01620         cout << "  To switch to another task, type "<<comcol("cd <path-to-taskname>")<<nl;
01621         cout << "  and type "<<comcol("cd ..")<<" to go back to the previous task (History size is 20)."<<nl;
01622         cout << "  Pressing "<<keycol("tab")<<" multiple times helps you to complete your command."<<nl;
01623         cout << "  It is not mandatory to switch to a task to interact with it, you can type the"<<nl;
01624         cout << "  peer-path to the task (dot-separated) and then type command or expression :"<<nl;
01625         cout << "     PeerTask.OtherTask.FinalTask.countTo(3) [enter] "<<nl;
01626         cout << "  Where 'countTo' is a method of 'FinalTask'."<<nl;
01627         cout << "  The TaskBrowser starts by default 'In' the current component. In order to watch"<<nl;
01628         cout << "  the TaskBrowser itself, type "<<comcol("leave")<<" You will notice that it"<<nl;
01629         cout << "  has connected to the data ports of the visited component. Use "<<comcol("enter")<<" to enter"<<nl;
01630         cout << "  the visited component again. The "<<comcol("cd")<<" command works transparantly in both"<<nl;
01631         cout << "  modi."<<nl;
01632 
01633         cout << "  "<<titlecol("Task Context Info")<<nl;
01634         cout << "  To see the contents of a task, type "<<comcol("ls")<<nl;
01635         cout << "  For a detailed argument list (and helpful info) of the object's methods, "<<nl;
01636         cout <<"   type the name of one of the listed task objects : " <<nl;
01637         cout <<"      this [enter]" <<nl<<nl;
01638         cout <<"  factor( int number ) : bool" <<nl;
01639         cout <<"   Factor a value into its primes." <<nl;
01640         cout <<"   number : The number to factor in primes." <<nl;
01641         cout <<"  isRunning( ) : bool" <<nl;
01642         cout <<"   Is this RTT::TaskContext started ?" <<nl;
01643         cout <<"  loadProgram( const& std::string Filename ) : bool" <<nl;
01644         cout <<"   Load an Orocos Program Script from a file." <<nl;
01645         cout <<"   Filename : An ops file." <<nl;
01646         cout <<"   ..."<<nl;
01647 
01648         cout << "   A status character shows the TaskState of a component."<<nl;
01649         cout << "     'E':RunTimeError, 'S':Stopped, 'R':Running, 'U':PreOperational (Unconfigured)"<<nl;
01650         cout << "     'X':Exception, 'F':FatalError" << nl;
01651 
01652         cout <<titlecol("Expressions")<<nl;
01653         cout << "  You can evaluate any script expression by merely typing it :"<<nl;
01654         cout << "     1+1 [enter]" <<nl;
01655         cout << "   = 2" <<nl;
01656         cout << "  or inspect the status of a program :"<<nl;
01657         cout << "     myProgram.isRunning [enter]" <<nl;
01658         cout << "   = false" <<nl;
01659         cout << "  and display the contents of complex data types (vector, array,...) :"<<nl;
01660         cout << "     array(6)" <<nl;
01661         cout << "   = {0, 0, 0, 0, 0, 0}" <<nl;
01662 
01663         cout <<titlecol("Changing Attributes and Properties")<<nl;
01664         cout << "  To change the value of a Task's attribute, type "<<comcol("varname = <newvalue>")<<nl;
01665         cout << "  If you provided a correct assignment, the browser will inform you of the success"<<nl;
01666         cout <<"   with the set value." <<nl;
01667 
01668         cout <<titlecol("Operations")<<nl;
01669         cout << "  An Operation is sent or called (evaluated) "<<nl;
01670         cout << "  immediately and print the result. An example could be :"<<nl;
01671         cout << "     someTask.bar.getNumberOfBeers(\"Palm\") [enter] "<<nl;
01672         cout << "   = 99" <<nl;
01673         cout << "  You can ask help on an operation by using the 'help' command: "<<nl;
01674         cout << "     help start"<<nl;
01675         cout << "    start( ) : bool"<<nl;
01676         cout << "      Start this TaskContext (= startHook() + updateHook() )." <<nl;
01677 
01678         cout <<titlecol("Program and scripting::StateMachine Scripts")<<nl;
01679         cout << "  To load a program script use the scripting service."<<nl;
01680         cout << "   Use "<<comcol(".provide scripting")<< " to load the scripting service in a TaskContext."<<nl;
01681         cout << "  You can use "<<comcol("ls progname")<<nl;
01682         cout << "   to see the programs operations and variables. You can manipulate each one of these"<<nl;
01683         cout << "   using the service object of the program."<<nl;
01684 
01685         cout << "  To print a program or state machine listing, use "<<comcol("list progname [linenumber]")<<nl;
01686         cout << "   to list the contents of the current program lines being executed,"<<nl;
01687         cout << "   or 10 lines before or after <linenumber>. When only "<<comcol("list [n]")<<nl;
01688         cout << "   is typed, 20 lines of the last listed program are printed from line <n> on "<<nl;
01689         cout << "   ( default : list next 20 lines after previous list )."<<nl;
01690 
01691         cout << "  To trace a program or state machine listing, use "<<comcol("trace [progname]")<<" this will"<<nl;
01692         cout << "   cause the TaskBrowser to list the contents of a traced program,"<<nl;
01693         cout << "   each time the line number of the traced program changes."<<nl;
01694         cout << "   Disable tracing with "<<comcol("untrace [progname]")<<""<<nl;
01695         cout << "   If no arguments are given to "<<comcol("trace")<<" and "<<comcol("untrace")<<", it applies to all programs."<<nl;
01696 
01697         cout << "   A status character shows which line is being executed."<<nl;
01698         cout << "   For programs : 'E':Error, 'S':Stopped, 'R':Running, 'P':Paused"<<nl;
01699         cout << "   For state machines : <the same as programs> + 'A':Active, 'I':Inactive"<<nl;
01700 
01701         cout <<titlecol("Changing Colors")<<nl;
01702         cout << "  You can inform the TaskBrowser of your background color by typing "<<comcol(".dark")<<nl;
01703         cout << "  "<<comcol(".light")<<", or "<<comcol(".nocolors")<<" to increase readability."<<nl;
01704 
01705         cout <<titlecol("Output Formatting")<<nl;
01706         cout << "  Use the commands "<<comcol(".hex") << " or " << comcol(".nohex") << " to turn hexadecimal "<<nl;
01707         cout << "  notation of integers on or off."<<nl;
01708 
01709         cout <<titlecol("Macro Recording / RTT::Command line history")<<nl;
01710         cout << "  You can browse the commandline history by using the up-arrow key or press "<<comcol("Ctrl r")<<nl;
01711         cout << "  and a search term. Hit enter to execute the current searched command."<<nl;
01712         cout << "  Macros can be recorded using the "<<comcol(".record 'macro-name'")<<" command."<<nl;
01713         cout << "  You can cancel the recording by typing "<<comcol(".cancel")<<" ."<<nl;
01714         cout << "  You can save and load the macro by typing "<<comcol(".end")<<" . The macro becomes"<<nl;
01715         cout << "  available as a command with name 'macro-name' in the current TaskContext." << nl;
01716         cout << "  While you enter the macro, it is not executed, as you must use scripting syntax which"<<nl;
01717         cout << "  may use loop or conditional statements, variables etc."<<nl;
01718 
01719         cout <<titlecol("Connecting Ports")<<nl;
01720         cout << "  You can instruct the TaskBrowser to connect to the ports of the current Peer by"<<nl;
01721         cout << "  typing "<<comcol(".connect [port-name]")<<", which will temporarily create connections"<<nl;
01722         cout << "  to all ports if [port-name] is omitted or to the specified port otherwise."<<nl;
01723         cout << "  The TaskBrowser disconnects these ports when it visits another component, but the"<<nl;
01724         cout << "  created connection objects remain in place (this is more or less a bug)!"<<nl;
01725 
01726         cout <<titlecol("Plugins, Typekits and Services")<<nl;
01727         cout << "  Use "<<comcol(".provide [servicename]")<< " to load a service in a TaskContext."<<nl;
01728         cout << "  For example, to add XML marshalling, type: "<<comcol(".provide marshalling")<< "."<<nl;
01729         cout << "  Use "<<comcol(".services")<< " to get a list of available services."<<nl;
01730         cout << "  Use "<<comcol(".typekits")<< " to get a list of available typekits."<<nl;
01731         cout << "  Use "<<comcol(".types")<< " to get a list of available data types."<<nl;
01732     }
01733 
01734     void TaskBrowser::printHelp( string helpstring ) {
01735         peer = context;
01736         // trim garbage:
01737         str_trim(helpstring, ' ');
01738         str_trim(helpstring, '.');
01739 
01740         if ( printService(helpstring))
01741             return;
01742 
01743         if ( findPeer( helpstring ) ) {
01744             try {
01745                 // findPeer resolved the taskobject holding 'helpstring'.
01746                 sresult << nl;
01747                 if (helpstring.rfind('.') != string::npos )
01748                     printOperation( helpstring.substr(helpstring.rfind('.')+1 ), taskobject );
01749                 else
01750                     printOperation( helpstring, taskobject );
01751                 cout << sresult.str();
01752             } catch (...) {
01753                 cerr<< "  help: No such operation known: '"<< helpstring << "'"<<nl;
01754             }
01755         } else {
01756             cerr<< "  help: No such operation known (peer not found): '"<< helpstring << "'"<<nl;
01757         }
01758         sresult.str("");
01759     }
01760 
01761     void TaskBrowser::printProgram(const std::string& progname, int cl /*= -1*/, RTT::TaskContext* progpeer /* = 0 */) {
01762         string ps;
01763         char s;
01764         stringstream txtss;
01765         int ln;
01766         int start;
01767         int end;
01768         bool found(false);
01769 
01770         if (progpeer == 0 )
01771             progpeer = context;
01772 
01773         // if program exists, display.
01774         if ( progpeer->getProvider<Scripting>("scripting")->hasProgram( progname ) ) {
01775             s = getProgramStatusChar(progpeer, progname);
01776             txtss.str( progpeer->getProvider<Scripting>("scripting")->getProgramText(progname) );
01777             ln = progpeer->getProvider<Scripting>("scripting")->getProgramLine(progname);
01778             if ( cl < 0 ) cl = ln;
01779             start = cl < 10 ? 1 : cl - 10;
01780             end   = cl + 10;
01781             this->listText( txtss, start, end, ln, s);
01782             found = true;
01783         }
01784 
01785         // If statemachine exists, display.
01786         if ( progpeer->getProvider<Scripting>("scripting")->hasStateMachine( progname ) ) {
01787             s = getStateMachineStatusChar(progpeer, progname);
01788             txtss.str( progpeer->getProvider<Scripting>("scripting")->getStateMachineText(progname) );
01789             ln = progpeer->getProvider<Scripting>("scripting")->getStateMachineLine(progname);
01790             if ( cl < 0 ) cl = ln;
01791             start = cl <= 10 ? 1 : cl - 10;
01792             end   = cl + 10;
01793             this->listText( txtss, start, end, ln, s);
01794             found = true;
01795         }
01796         if ( !found ) {
01797             cerr << "Error : No such program or state machine found : "<<progname;
01798             cerr << " in "<< progpeer->getName() <<"."<<endl;
01799             return;
01800         }
01801         storedname = progname;
01802     }
01803 
01804     void TaskBrowser::printProgram(int cl /* = -1 */) {
01805         string ps;
01806         char s;
01807         stringstream txtss;
01808         int ln;
01809         int start;
01810         int end;
01811         bool found(false);
01812         if ( context->getProvider<Scripting>("scripting")->hasProgram( storedname ) ) {
01813             s = getProgramStatusChar(context, storedname);
01814             txtss.str( context->getProvider<Scripting>("scripting")->getProgramText(storedname) );
01815             ln = context->getProvider<Scripting>("scripting")->getProgramLine(storedname);
01816             if ( cl < 0 ) cl = storedline;
01817             if (storedline < 0 ) cl = ln -10;
01818             start = cl;
01819             end   = cl + 20;
01820             this->listText( txtss, start, end, ln, s);
01821             found = true;
01822         }
01823         if ( context->getProvider<Scripting>("scripting")->hasStateMachine(storedname) ) {
01824             s = getStateMachineStatusChar(context, storedname);
01825             txtss.str( context->getProvider<Scripting>("scripting")->getStateMachineText(storedname) );
01826             ln = context->getProvider<Scripting>("scripting")->getStateMachineLine(storedname);
01827             if ( cl < 0 ) cl = storedline;
01828             if (storedline < 0 ) cl = ln -10;
01829             start = cl;
01830             end   = cl+20;
01831             this->listText( txtss, start, end, ln, s);
01832             found = true;
01833         }
01834         if ( !found )
01835             cerr << "Error : No such program or state machine found : "<<storedname<<endl;
01836     }
01837 
01838     void TaskBrowser::listText(stringstream& txtss,int start, int end, int ln, char s) {
01839         int curln = 1;
01840         string line;
01841         while ( start > 1 && curln != start ) { // consume lines
01842             getline( txtss, line, '\n' );
01843             if ( ! txtss )
01844                 break; // no more lines, break.
01845             ++curln;
01846         }
01847         while ( end > start && curln != end ) { // print lines
01848             getline( txtss, line, '\n' );
01849             if ( ! txtss )
01850                 break; // no more lines, break.
01851             if ( curln == ln ) {
01852                 cout << s<<'>';
01853             }
01854             else
01855                 cout << "  ";
01856             cout<< setw(int(log(double(end)))) <<right << curln<< left;
01857             cout << ' ' << line <<endl;
01858             ++curln;
01859         }
01860         storedline = curln;
01861         // done !
01862     }
01863 
01864     void TaskBrowser::printInfo(const std::string& peerp)
01865     {
01866         // this sets this->peer to the peer given
01867         peer = context;
01868         taskobject = peer->provides();
01869         if ( !peerp.empty() && peerp != "." && this->findPeer( peerp+"." ) == 0 ) {
01870             cerr << "No such peer or object: " << peerp << endl;
01871             return;
01872         }
01873 
01874         if ( !peer || !peer->ready()) {
01875             cout << nl << " Connection to peer "+peerp+" lost (peer->ready() == false)." <<endlog();
01876             return;
01877         }
01878 
01879         //                      sresult << *it << "["<<getTaskStatusChar(peer->getPeer(*it))<<"] ";
01880 
01881 
01882         if ( peer->provides() == taskobject )
01883             sresult <<nl<<" Listing TaskContext "<< green << peer->getName()<<coloroff << "["<<getTaskStatusChar(peer)<<"] :"<<nl;
01884         else
01885             sresult <<nl<<" Listing Service "<< green << taskobject->getName()<<coloroff<< "["<<getTaskStatusChar(peer)<<"] :"<<nl;
01886 
01887         sresult <<nl<<" Configuration Properties: ";
01888         RTT::PropertyBag* bag = taskobject->properties();
01889         if ( bag && bag->size() != 0 ) {
01890             // Print Properties:
01891             for( RTT::PropertyBag::iterator it = bag->begin(); it != bag->end(); ++it) {
01892                 base::DataSourceBase::shared_ptr pds = (*it)->getDataSource();
01893                 sresult << nl << setw(11)<< right << Types()->toDot( (*it)->getType() )<< " "
01894                      << coloron <<setw(14)<<left<< (*it)->getName() << coloroff;
01895                 this->printResult( pds.get(), false ); // do not recurse
01896                 sresult<<" ("<< (*it)->getDescription() <<')';
01897             }
01898         } else {
01899             sresult << "(none)";
01900         }
01901         sresult <<nl;
01902 
01903         // Print "this" interface (without detail) and then list objects...
01904         sresult <<nl<< " Provided Interface:";
01905 
01906         sresult <<nl<< "  Attributes   : ";
01907         std::vector<std::string> objlist = taskobject->getAttributeNames();
01908         if ( !objlist.empty() ) {
01909             sresult << nl;
01910             // Print Attributes:
01911             for( std::vector<std::string>::iterator it = objlist.begin(); it != objlist.end(); ++it) {
01912                 base::DataSourceBase::shared_ptr pds = taskobject->getValue(*it)->getDataSource();
01913                 sresult << setw(11)<< right << Types()->toDot( pds->getType() )<< " "
01914                      << coloron <<setw( 14 )<<left<< *it << coloroff;
01915                 this->printResult( pds.get(), false ); // do not recurse
01916                 sresult <<nl;
01917             }
01918         } else {
01919             sresult << coloron << "(none)";
01920         }
01921 
01922         sresult <<coloroff<<nl<< "  Operations      : "<<coloron;
01923         objlist = taskobject->getNames();
01924         if ( !objlist.empty() ) {
01925             std::copy(objlist.begin(), objlist.end(), std::ostream_iterator<std::string>(sresult, " "));
01926         } else {
01927             sresult << "(none)";
01928         }
01929         sresult << coloroff << nl;
01930 
01931         sresult <<nl<< " Data Flow Ports: ";
01932         objlist = taskobject->getPortNames();
01933         if ( !objlist.empty() ) {
01934             for(vector<string>::iterator it = objlist.begin(); it != objlist.end(); ++it) {
01935                 base::PortInterface* port = taskobject->getPort(*it);
01936                 bool writer = dynamic_cast<OutputPortInterface*>(port) ? true : false;
01937                 // Port type R/W
01938                 sresult << nl << " " << ( !writer ?
01939                     " In" : "Out");
01940                 // Port data type + name
01941                 if ( !port->connected() )
01942                     sresult << "(U) " << setw(11)<<right<< Types()->toDot( port->getTypeInfo()->getTypeName() );
01943                 else
01944                     sresult << "(C) " << setw(11)<<right<< Types()->toDot( port->getTypeInfo()->getTypeName() );
01945                 sresult << " "
01946                      << coloron <<setw( 14 )<<left<< *it << coloroff;
01947 
01948                 InputPortInterface* iport = dynamic_cast<InputPortInterface*>(port);
01949                 if (iport) {
01950                     sresult << " <= ( use '"<< iport->getName() << ".read(sample)' to read a sample from this port)";
01951                 }
01952                 OutputPortInterface* oport = dynamic_cast<OutputPortInterface*>(port);
01953                 if (oport) {
01954                     if ( oport->keepsLastWrittenValue()) {
01955                         DataSourceBase::shared_ptr dsb = oport->getDataSource();
01956                         dsb->evaluate(); // read last written value.
01957                         sresult << " => " << dsb;
01958                     } else
01959                         sresult << " => (keepsLastWrittenValue() == false. Enable it for this port in order to see it in the TaskBrowser.)";
01960                 }
01961 #if 0
01962                 // only show if we're connected to it
01963                 if (peer == taskcontext && peer->provides() == taskobject) {
01964                     // Lookup if we have an input with that name and
01965                     // consume the last sample this port produced.
01966                     InputPortInterface* iport = dynamic_cast<InputPortInterface*>(ports()->getPort(port->getName()));
01967                     if (iport) {
01968                         // consume sample
01969                         iport->getDataSource()->evaluate();
01970                         // display
01971                         if ( peer == this)
01972                             sresult << " <= " << DataSourceBase::shared_ptr( iport->getDataSource());
01973                         else
01974                             sresult << " => " << DataSourceBase::shared_ptr( iport->getDataSource());
01975                     }
01976                     OutputPortInterface* oport = dynamic_cast<OutputPortInterface*>(ports()->getPort(port->getName()));
01977                     if (oport) {
01978                         // display last written value:
01979                         DataSourceBase::shared_ptr ds = oport->getDataSource();
01980                         if (ds) {
01981                             if ( peer == this)
01982                                 sresult << " => " << ds;
01983                             else
01984                                 sresult << " <= " << ds << " (sent from TaskBrowser)";
01985                         } else {
01986                             sresult << "(no last written value kept)";
01987                         }
01988                     }
01989                 } else {
01990                     sresult << "(TaskBrowser not connected to this port)";
01991                 }
01992 #endif
01993                 // Port description (see Service)
01994 //                     if ( peer->provides(*it) )
01995 //                         sresult << " ( "<< taskobject->provides(*it)->getDescription() << " ) ";
01996             }
01997         } else {
01998             sresult << "(none)";
01999         }
02000         sresult << coloroff << nl;
02001 
02002         objlist = taskobject->getProviderNames();
02003         sresult <<nl<< " Services: "<<nl;
02004         if ( !objlist.empty() ) {
02005             for(vector<string>::iterator it = objlist.begin(); it != objlist.end(); ++it)
02006                 sresult <<coloron<< "  " << setw(14) << *it <<coloroff<< " ( "<< taskobject->provides(*it)->doc() << " ) "<<nl;
02007         } else {
02008             sresult <<coloron<< "(none)" <<coloroff <<nl;
02009         }
02010 
02011         // RTT::TaskContext specific:
02012         if ( peer->provides() == taskobject ) {
02013 
02014             objlist = peer->requires()->getOperationCallerNames();
02015             sresult <<nl<< " Requires Operations :";
02016             if ( !objlist.empty() ) {
02017                 for(vector<string>::iterator it = objlist.begin(); it != objlist.end(); ++it)
02018                     sresult <<coloron<< "  " << *it <<coloroff << '[' << (peer->requires()->getOperationCaller(*it)->ready() ? "R]" : "!]");
02019                 sresult << nl;
02020             } else {
02021                 sresult <<coloron<< "  (none)" <<coloroff <<nl;
02022             }
02023             objlist = peer->requires()->getRequesterNames();
02024             sresult <<     " Requests Services   :";
02025             if ( !objlist.empty() ) {
02026                 for(vector<string>::iterator it = objlist.begin(); it != objlist.end(); ++it)
02027                     sresult <<coloron<< "  " << *it <<coloroff << '[' << (peer->requires(*it)->ready() ? "R]" : "!]");
02028                 sresult << nl;
02029             } else {
02030                 sresult <<coloron<< "  (none)" <<coloroff <<nl;
02031             }
02032 
02033             if (peer->provides()->hasService("scripting")) {
02034                 objlist = peer->getProvider<Scripting>("scripting")->getProgramList();
02035                 if ( !objlist.empty() ) {
02036                     sresult << " Programs     : "<<coloron;
02037                     for(vector<string>::iterator it = objlist.begin(); it != objlist.end(); ++it)
02038                         sresult << *it << "["<<getProgramStatusChar(peer,*it)<<"] ";
02039                     sresult << coloroff << nl;
02040                 }
02041 
02042                 objlist = peer->getProvider<Scripting>("scripting")->getStateMachineList();
02043                 if ( !objlist.empty() ) {
02044                     sresult << " StateMachines: "<<coloron;
02045                     for(vector<string>::iterator it = objlist.begin(); it != objlist.end(); ++it)
02046                         sresult << *it << "["<<getStateMachineStatusChar(peer,*it)<<"] ";
02047                     sresult << coloroff << nl;
02048                 }
02049             }
02050 
02051             // if we are in the TB, display the peers of our connected task:
02052             if ( context == tb )
02053                 sresult <<nl<< " "<<peer->getName()<<" Peers : "<<coloron;
02054             else
02055                 sresult << nl <<" Peers        : "<<coloron;
02056 
02057             objlist = peer->getPeerList();
02058             if ( !objlist.empty() )
02059                 for(vector<string>::iterator it = objlist.begin(); it != objlist.end(); ++it) {
02060                     if( peer->getPeer(*it) )
02061                         sresult << *it << "["<<getTaskStatusChar(peer->getPeer(*it))<<"] ";
02062                     else
02063                         sresult << *it << "[X] ";
02064           }
02065             else
02066                 sresult << "(none)";
02067         }
02068         sresult <<coloroff<<nl;
02069         cout << sresult.str();
02070         sresult.str("");
02071     }
02072 
02073     void TaskBrowser::printOperation( const std::string m, Service::shared_ptr the_ops )
02074     {
02075         std::vector<ArgumentDescription> args;
02076         Service::shared_ptr ops;
02077         try {
02078             args = the_ops->getArgumentList( m ); // may throw !
02079             ops = the_ops;
02080         } catch(...) {
02081             args = GlobalService::Instance()->getArgumentList( m ); // may throw !
02082             ops = GlobalService::Instance();
02083         }
02084         sresult <<" " << coloron << m << coloroff<< "( ";
02085         for (std::vector<ArgumentDescription>::iterator it = args.begin(); it != args.end(); ++it) {
02086             sresult << Types()->toDot( it->type ) <<" ";
02087             sresult << coloron << it->name << coloroff;
02088             if ( it+1 != args.end() )
02089                 sresult << ", ";
02090             else
02091                 sresult << " ";
02092         }
02093         sresult << ") : "<< Types()->toDot( ops->getResultType(m) )<<nl;
02094         sresult << "   " << ops->getDescription( m )<<nl;
02095         for (std::vector<ArgumentDescription>::iterator it = args.begin(); it != args.end(); ++it)
02096             sresult <<"   "<< it->name <<" : " << it->description << nl;
02097     }
02098 
02099 }