00001 #ifndef NO_GPL
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #else
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055 #endif
00056
00057
00058 #include <rtt/Logger.hpp>
00059 #include <rtt/MultiVector.hpp>
00060 #include <rtt/TypeStream.hpp>
00061 #include "TaskBrowser.hpp"
00062
00063 #include "rtt/TryCommand.hpp"
00064 #include <rtt/TaskContext.hpp>
00065 #include <rtt/scripting/parser-debug.hpp>
00066 #include <rtt/scripting/Parser.hpp>
00067 #include <rtt/scripting/ProgramLoader.hpp>
00068 #include <rtt/scripting/parse_exception.hpp>
00069 #include <rtt/scripting/PeerParser.hpp>
00070
00071 #include <iostream>
00072 #include <fstream>
00073 #include <sstream>
00074 #include <iomanip>
00075 #include <deque>
00076 #include <stdio.h>
00077
00078 #if defined(HAS_READLINE) && !defined(NO_GPL)
00079 #define USE_READLINE
00080 #endif
00081 #if defined(HAS_EDITLINE)
00082
00083 #define USE_READLINE
00084 #define USE_EDITLINE
00085 #endif
00086
00087 #ifdef USE_READLINE
00088 # ifdef USE_EDITLINE
00089 # include <editline/readline.h>
00090 # include <editline/history.h>
00091 # else
00092 # include <readline/readline.h>
00093 # include <readline/history.h>
00094 # endif
00095 #endif
00096
00097 #include <boost/bind.hpp>
00098 #include <boost/lambda/lambda.hpp>
00099
00100 #include <signal.h>
00101
00102 namespace OCL
00103 {
00104 using namespace RTT;
00105 using namespace RTT::detail;
00106 #ifdef USE_READLINE
00107 std::vector<std::string> TaskBrowser::candidates;
00108 std::vector<std::string> TaskBrowser::completes;
00109 std::vector<std::string>::iterator TaskBrowser::complete_iter;
00110 std::string TaskBrowser::component;
00111 std::string TaskBrowser::peerpath;
00112 std::string TaskBrowser::text;
00113 #endif
00114 TaskContext* TaskBrowser::taskcontext = 0;
00115 OperationInterface* TaskBrowser::taskobject = 0;
00116 TaskContext* TaskBrowser::peer = 0;
00117 TaskContext* TaskBrowser::tb = 0;
00118 TaskContext* TaskBrowser::context = 0;
00119
00120 using boost::bind;
00121 using namespace RTT;
00122 using namespace std;
00123
00124 string TaskBrowser::red;
00125 string TaskBrowser::green;
00126 string TaskBrowser::blue;
00127 std::deque<TaskContext*> taskHistory;
00128 std::string TaskBrowser::prompt(" (type 'ls' for context info) :");
00129 std::string TaskBrowser::coloron;
00130 std::string TaskBrowser::underline;
00131 std::string TaskBrowser::coloroff;
00132
00133
00137 static std::ostream&
00138 nl(std::ostream& __os)
00139 { return __os.put(__os.widen('\n')); }
00140
00141 #ifdef _POSIX_VERSION
00142
00143 void ctrl_c_catcher(int sig)
00144 {
00145 ::signal(sig, SIG_IGN);
00146 #if defined( USE_READLINE ) && !defined(USE_EDITLINE)
00147
00148
00149
00150 rl_free_line_state();
00151
00152 #endif
00153 ::signal(SIGINT, ctrl_c_catcher);
00154 }
00155 #endif
00156
00157 #ifdef USE_READLINE
00158 char *TaskBrowser::rl_gets ()
00159 {
00160
00161
00162 if (line_read)
00163 {
00164 #ifdef _WIN32
00165
00176 free(line_read);
00177 #else
00178 free (line_read);
00179 #endif
00180 line_read = 0;
00181 }
00182
00183
00184 std::string p;
00185 if ( !macrorecording ) {
00186 p = prompt;
00187 } else {
00188 p = "> ";
00189 }
00190 #ifndef _WIN32 // does not work on win32
00191 #if !defined(USE_EDITLINE)
00192 if (rl_set_signals() != 0)
00193 cerr << "Error setting signals !" <<endl;
00194 #endif
00195 #endif
00196 line_read = readline ( p.c_str() );
00197
00198
00199
00200 if (line_read && *line_read) {
00201
00202 string s = line_read;
00203 if (s != "quit")
00204 add_history (line_read);
00205 }
00206 return (line_read);
00207 }
00208
00209 char* TaskBrowser::dupstr( const char *s )
00210 {
00211 char * rv;
00212
00213 rv = (char*) malloc( strlen( s ) + 1 );
00214 strncpy( rv, s, strlen(s) + 1 );
00215 return rv;
00216 }
00217
00218 char *TaskBrowser::command_generator( const char *_text, int state )
00219 {
00220
00221 if ( !state )
00222 {
00223
00224 text = _text;
00225
00226 completes.clear();
00227 find_completes();
00228 complete_iter = completes.begin();
00229 }
00230 else
00231 ++complete_iter;
00232
00233
00234 if ( complete_iter == completes.end() )
00235 return 0;
00236
00237 return dupstr( complete_iter->c_str() );
00238 }
00239
00244 void TaskBrowser::find_completes() {
00245 std::string::size_type pos;
00246 std::string::size_type startpos;
00247 std::string line( rl_line_buffer, rl_point );
00248
00249
00250 if ( line.find(std::string("cd ")) == 0 || line.find(std::string("ls ")) == 0) {
00251
00252
00253 pos = line.find(" ");
00254 startpos = line.find_last_of(". ");
00255
00256
00257 peer = taskcontext;
00258 if ( pos+1 != line.length() )
00259 peer = findPeer( line.substr(pos+1) );
00260
00261 if (!peer)
00262 return;
00263
00264 TaskContext::PeerList v = peer->getPeerList();
00265 for (TaskContext::PeerList::iterator i = v.begin(); i != v.end(); ++i) {
00266 std::string path;
00267 if ( !( pos+1 > startpos) )
00268 path = line.substr(pos+1, startpos - pos);
00269
00270 if ( *i == line.substr(startpos+1) )
00271 completes.push_back( path + *i + ".");
00272 else
00273 if ( startpos == std::string::npos || startpos+1 == line.length() || i->find( line.substr(startpos+1)) == 0 )
00274 completes.push_back( path + *i );
00275 }
00276
00277 if (line.find(std::string("cd ")) == 0)
00278 return;
00279
00280 v = peer->getObjectList();
00281 for (TaskContext::PeerList::iterator i = v.begin(); i != v.end(); ++i) {
00282 std::string path;
00283 if ( !( pos+1 > startpos) )
00284 path = line.substr(pos+1, startpos - pos);
00285
00286 if ( *i == line.substr(startpos+1) )
00287 completes.push_back( path + *i + ".");
00288 else
00289 if ( startpos == std::string::npos || startpos+1 == line.length() || i->find( line.substr(startpos+1)) == 0 )
00290 completes.push_back( path + *i );
00291 }
00292 return;
00293 }
00294
00295
00296 if ( line.find(std::string(".")) == 0 ) {
00297
00298 std::vector<std::string> tbcoms;
00299 tbcoms.push_back(".loadProgram ");
00300 tbcoms.push_back(".unloadProgram ");
00301 tbcoms.push_back(".loadStateMachine ");
00302 tbcoms.push_back(".unloadStateMachine ");
00303 tbcoms.push_back(".light");
00304 tbcoms.push_back(".dark");
00305 tbcoms.push_back(".nocolors");
00306 tbcoms.push_back(".connect");
00307 tbcoms.push_back(".record");
00308 tbcoms.push_back(".end");
00309 tbcoms.push_back(".cancel");
00310
00311
00312 for( std::vector<std::string>::iterator it = tbcoms.begin();
00313 it != tbcoms.end();
00314 ++it)
00315 if ( it->find(line) == 0 )
00316 completes.push_back( *it );
00317 return;
00318 }
00319
00320 if ( line.find(std::string("list ")) == 0
00321 || line.find(std::string("trace ")) == 0
00322 || line.find(std::string("untrace ")) == 0) {
00323 stringstream ss( line.c_str() );
00324 string lcommand;
00325 ss >> lcommand;
00326 lcommand += ' ';
00327 std::vector<std::string> progs;
00328
00329
00330 progs = context->scripting()->getPrograms();
00331
00332 for( std::vector<std::string>::iterator it = progs.begin();
00333 it != progs.end();
00334 ++it) {
00335 string res = lcommand + *it;
00336 if ( res.find(line) == 0 )
00337 completes.push_back( *it );
00338 }
00339 progs = context->scripting()->getStateMachines();
00340 for( std::vector<std::string>::iterator it = progs.begin();
00341 it != progs.end();
00342 ++it) {
00343 string res = lcommand + *it;
00344 if ( res.find(line) == 0 )
00345 completes.push_back( *it );
00346 }
00347
00348 return;
00349 }
00350
00351 startpos = text.find_last_of(",( ");
00352 if ( startpos == std::string::npos )
00353 startpos = 0;
00354
00355
00356 find_peers(startpos);
00357
00358
00359
00360
00361
00362
00363 std::string comp = component;
00364
00365
00366
00367
00368
00369 find_ops();
00370
00371
00372
00373 if ( line.empty() ) {
00374 completes.push_back("cd ");
00375 completes.push_back("cd ..");
00376 completes.push_back("ls");
00377 completes.push_back("help");
00378 completes.push_back("quit");
00379 completes.push_back("list");
00380 completes.push_back("trace");
00381 completes.push_back("untrace");
00382 if (taskcontext == context)
00383 completes.push_back("leave");
00384 else
00385 completes.push_back("enter");
00386
00387 }
00388
00389
00390 if ( !text.empty() ) {
00391 if ( std::string( "cd " ).find(text) == 0 )
00392 completes.push_back("cd ");
00393 if ( std::string( "ls" ).find(text) == 0 )
00394 completes.push_back("ls");
00395 if ( std::string( "cd .." ).find(text) == 0 )
00396 completes.push_back("cd ..");
00397 if ( std::string( "help" ).find(text) == 0 )
00398 completes.push_back("help");
00399 if ( std::string( "quit" ).find(text) == 0 )
00400 completes.push_back("quit");
00401 if ( std::string( "list " ).find(text) == 0 )
00402 completes.push_back("list ");
00403 if ( std::string( "trace " ).find(text) == 0 )
00404 completes.push_back("trace ");
00405 if ( std::string( "untrace " ).find(text) == 0 )
00406 completes.push_back("untrace ");
00407
00408 if (taskcontext == context && string("leave").find(text) == 0)
00409 completes.push_back("leave");
00410
00411 if (context == tb && string("enter").find(text) == 0)
00412 completes.push_back("enter");
00413 }
00414 }
00415
00416 void TaskBrowser::find_ops()
00417 {
00418
00419
00420 std::vector<std::string> attrs;
00421 attrs = taskobject->attributes()->names();
00422 for (std::vector<std::string>::iterator i = attrs.begin(); i!= attrs.end(); ++i ) {
00423 if ( i->find( component ) == 0 && !component.empty() )
00424 completes.push_back( peerpath + *i );
00425 }
00426
00427 if (taskobject == peer && peer->properties() != 0 ) {
00428 std::vector<std::string> props;
00429 peer->properties()->list(props);
00430 for (std::vector<std::string>::iterator i = props.begin(); i!= props.end(); ++i ) {
00431 if ( i->find( component ) == 0 && !component.empty() ) {
00432 completes.push_back( peerpath + *i );
00433 }
00434 }
00435 }
00436
00437
00438 std::vector<std::string> comps;
00439 comps = taskobject->commands()->getNames();
00440 for (std::vector<std::string>::iterator i = comps.begin(); i!= comps.end(); ++i ) {
00441 if ( i->find( component ) == 0 )
00442 completes.push_back( peerpath + *i );
00443 }
00444
00445 comps = taskobject->methods()->getNames();
00446 for (std::vector<std::string>::iterator i = comps.begin(); i!= comps.end(); ++i ) {
00447 if ( i->find( component ) == 0 )
00448 completes.push_back( peerpath + *i );
00449 }
00450
00451 comps = taskobject->events()->getNames();
00452 for (std::vector<std::string>::iterator i = comps.begin(); i!= comps.end(); ++i ) {
00453 if ( i->find( component ) == 0 )
00454 completes.push_back( peerpath + *i );
00455 }
00456 }
00457
00458 void TaskBrowser::find_peers( std::string::size_type startpos )
00459 {
00460 peerpath.clear();
00461 peer = context;
00462 taskobject = context;
00463
00464 std::string to_parse = text.substr(startpos);
00465 startpos = 0;
00466 std::string::size_type endpos = 0;
00467
00468 component.clear();
00469 peerpath.clear();
00470 while (endpos != std::string::npos )
00471 {
00472 bool itemfound = false;
00473 endpos = to_parse.find(".");
00474 if ( endpos == startpos ) {
00475 component.clear();
00476 break;
00477 }
00478 std::string item = to_parse.substr(startpos, endpos);
00479
00480 if ( taskobject->getObject( item ) ) {
00481 taskobject = peer->getObject(item);
00482 itemfound = true;
00483 } else
00484 if ( peer->hasPeer( item ) ) {
00485 peer = peer->getPeer( item );
00486 taskobject = peer;
00487 itemfound = true;
00488 }
00489 if ( itemfound ) {
00490 peerpath += to_parse.substr(startpos, endpos) + ".";
00491 if ( endpos != std::string::npos )
00492 to_parse = to_parse.substr(endpos + 1);
00493 else
00494 to_parse.clear();
00495 startpos = 0;
00496 }
00497 else {
00498
00499
00500 component = item;
00501 break;
00502 }
00503 }
00504
00505
00506
00507
00508
00509
00510
00511
00512
00513 TaskContext::PeerList v;
00514 if ( taskobject == peer ) {
00515
00516 v = peer->getPeerList();
00517 for (TaskContext::PeerList::iterator i = v.begin(); i != v.end(); ++i) {
00518 if ( i->find( component ) == 0 ) {
00519 completes.push_back( peerpath + *i );
00520 completes.push_back( peerpath + *i + "." );
00521
00522 }
00523 }
00524 }
00525
00526 v = taskobject->getObjectList();
00527 for (TaskContext::PeerList::iterator i = v.begin(); i != v.end(); ++i) {
00528 if ( i->find( component ) == 0 ) {
00529 completes.push_back( peerpath + *i );
00530 if ( *i != "this" )
00531 completes.push_back( peerpath + *i + "." );
00532
00533 }
00534 }
00535 return;
00536 }
00537
00538 char ** TaskBrowser::orocos_hmi_completion ( const char *text, int start, int end )
00539 {
00540 char **matches;
00541 matches = ( char ** ) 0;
00542
00543 matches = rl_completion_matches ( text, &TaskBrowser::command_generator );
00544
00545 return ( matches );
00546 }
00547 #endif // USE_READLINE
00548
00549 TaskBrowser::TaskBrowser( TaskContext* _c )
00550 : TaskContext("TaskBrowser"),
00551 command(0),
00552 debug(0),
00553 line_read(0),
00554 lastc(0), storedname(""), storedline(-1),
00555 macrorecording(false)
00556 {
00557 tb = this;
00558 context = tb;
00559 this->switchTaskContext(_c);
00560 #ifdef USE_READLINE
00561 rl_completion_append_character = '\0';
00562 rl_attempted_completion_function = &TaskBrowser::orocos_hmi_completion;
00563
00564 if ( read_history(".tb_history") != 0 ) {
00565 read_history("~/.tb_history");
00566 }
00567 #endif
00568
00569 #ifdef _WIN32
00570 this->setColorTheme( nocolors );
00571 #else
00572 this->setColorTheme( darkbg );
00573 #endif
00574 this->enterTask();
00575 }
00576
00577 TaskBrowser::~TaskBrowser() {
00578 #ifdef USE_READLINE
00579 if (line_read)
00580 {
00581 free (line_read);
00582 }
00583 if ( write_history(".tb_history") != 0 ) {
00584 write_history("~/.tb_history");
00585 }
00586 #endif
00587 }
00588
00592 char getTaskStatusChar(TaskContext* t)
00593 {
00594 if (t->isRunning() )
00595 return 'R';
00596 if (t->isConfigured() )
00597 return 'S';
00598 return 'U';
00599 }
00600
00601 char getStateMachineStatusChar(TaskContext* t, string progname)
00602 {
00603 string ps = t->scripting()->getStateMachineStatus(progname);
00604 return toupper(ps[0]);
00605 }
00606
00607 char getProgramStatusChar(TaskContext* t, string progname)
00608 {
00609 string ps = t->scripting()->getProgramStatus(progname);
00610 return toupper(ps[0]);
00611 }
00612
00613 void str_trim(string& str, char to_trim)
00614 {
00615 string::size_type pos1 = str.find_first_not_of(to_trim);
00616 string::size_type pos2 = str.find_last_not_of(to_trim);
00617 str = str.substr(pos1 == string::npos ? 0 : pos1,
00618 pos2 == string::npos ? str.length() - 1 : pos2 - pos1 + 1);
00619 }
00620
00621
00626 void TaskBrowser::loop()
00627 {
00628 #ifdef _POSIX_VERSION
00629
00630 ::signal( SIGINT, ctrl_c_catcher );
00631 #if defined(USE_READLINE) && !defined(USE_EDITLINE)
00632
00633 if(rl_catch_signals == 0)
00634 cerr << "Error: not catching signals !"<<endl;
00635 if (rl_set_signals() != 0)
00636 cerr << "Error setting signals !" <<endl;
00637
00638 #if defined(OROCOS_TARGET_XENOMAI) && CONFIG_XENO_VERSION_MAJOR == 2 && CONFIG_XENO_VERSION_MINOR == 5
00639
00640 xeno_sigshadow_install();
00641 #endif
00642 #endif
00643 #endif
00644 cout << nl<<
00645 coloron <<
00646 " This console reader allows you to browse and manipulate TaskContexts."<<nl<<
00647 " You can type in a command, event, method, expression or change variables."<<nl;
00648 cout <<" (type '"<<underline<<"help"<<coloroff<<coloron<<"' for instructions)"<<nl;
00649 #if defined( USE_READLINE )
00650 cout << " TAB completion and HISTORY is available ('bash' like)" <<coloroff<<nl<<nl;
00651 #else
00652 cout << " TAB completion and history is NOT available (LGPL-version)" <<coloroff<<nl<<nl;
00653 #endif
00654 while (1)
00655 {
00656 if (!macrorecording) {
00657 if ( context == tb )
00658 cout << green << " Watching " <<coloroff;
00659 else
00660 cout << red << " In " << coloroff;
00661
00662 char state = getTaskStatusChar(taskcontext);
00663
00664 cout << "Task "<<green<< taskcontext->getName() <<coloroff<< "["<< state <<"]. (Status of last Command : ";
00665 if ( command == 0 )
00666 cout << "none";
00667 else if ( command->done() )
00668 cout <<green + "done";
00669 else if ( command->valid() )
00670 cout << blue+"busy";
00671 else if ( command->executed() )
00672 cout << red+"fail";
00673 else if ( command->accepted() )
00674 cout << blue+"queued";
00675 cout << coloroff << " )";
00676
00677
00678 cout << endl;
00679
00680
00681 for (PTrace::iterator it = ptraces.begin(); it != ptraces.end(); ++it) {
00682 TaskContext* progpeer = it->first.first;
00683 int line = progpeer->scripting()->getProgramLine(it->first.second);
00684 if ( line != it->second ) {
00685 it->second = line;
00686 printProgram( it->first.second, -1, progpeer );
00687 }
00688 }
00689
00690 for (PTrace::iterator it = straces.begin(); it != straces.end(); ++it) {
00691 TaskContext* progpeer = it->first.first;
00692 int line = progpeer->scripting()->getStateMachineLine(it->first.second);
00693 if ( line != it->second ) {
00694 it->second = line;
00695 printProgram( it->first.second, -1, progpeer );
00696 }
00697 }
00698 }
00699
00700 checkPorts();
00701 #ifdef _POSIX_VERSION
00702
00703 ::signal( SIGINT, ctrl_c_catcher );
00704 #endif
00705 #ifdef USE_READLINE
00706 const char* const commandStr = rl_gets();
00707
00708 std::string command( commandStr ? commandStr : "quit" );
00709 #else
00710 std::string command;
00711 cout << prompt;
00712 getline(cin,command);
00713 if (!cin)
00714 command = "quit";
00715 #endif
00716 str_trim( command, ' ');
00717 #ifdef _POSIX_VERSION
00718 ::signal( SIGINT, SIG_DFL );
00719 #endif
00720 cout << coloroff;
00721 if ( command == "quit" ) {
00722
00723 cout << endl;
00724 return;
00725 } else if ( command == "help") {
00726 printHelp();
00727 } else if ( command == "#debug") {
00728 debug = !debug;
00729 } else if ( command.find("list ") == 0 || command == "list" ) {
00730 browserAction(command);
00731 } else if ( command.find("trace ") == 0 || command == "trace" ) {
00732 browserAction(command);
00733 } else if ( command.find("untrace ") == 0 || command == "untrace" ) {
00734 browserAction(command);
00735 } else if ( command.find("ls") == 0 ) {
00736 std::string::size_type pos = command.find("ls")+2;
00737 command = std::string(command, pos, command.length());
00738 printInfo( command );
00739 } else if ( command == "" ) {
00740 } else if ( command.find("cd ..") == 0 ) {
00741 this->switchBack( );
00742 } else if ( command.find("enter") == 0 ) {
00743 this->enterTask();
00744 } else if ( command.find("leave") == 0 ) {
00745 this->leaveTask();
00746 } else if ( command.find("cd ") == 0 ) {
00747 std::string::size_type pos = command.find("cd")+2;
00748 command = std::string(command, pos, command.length());
00749 this->switchTaskContext( command );
00750 } else if ( command.find(".") == 0 ) {
00751 command = std::string(command, 1, command.length());
00752 this->browserAction( command );
00753 } else if ( macrorecording) {
00754 macrotext += command +'\n';
00755 } else {
00756 try {
00757 this->evalCommand( command );
00758 } catch(...){
00759 cerr << "The command '"<<command<<"' caused an unknown exception and could not be completed."<<endl;
00760 }
00761
00762
00763 storedline = -1;
00764 }
00765 cout <<endl;
00766 }
00767 }
00768
00769 void TaskBrowser::enterTask()
00770 {
00771 if ( context == taskcontext ) {
00772 log(Info) <<"Already in Task "<< taskcontext->getName()<<endlog();
00773 return;
00774 }
00775 context = taskcontext;
00776 log(Info) <<"Entering Task "<< taskcontext->getName()<<endlog();
00777 }
00778
00779 void TaskBrowser::leaveTask()
00780 {
00781 if ( context == tb ) {
00782 log(Info) <<"Already watching Task "<< taskcontext->getName()<<endlog();
00783 return;
00784 }
00785 context = tb;
00786 log(Info) <<"Watching Task "<< taskcontext->getName()<<endlog();
00787 }
00788
00789 void TaskBrowser::recordMacro(std::string name)
00790 {
00791 if ( name.empty() ) {
00792 cerr << "Please specify a macro name." <<endl;
00793 return;
00794 } else {
00795 cout << "Recording macro "<< name <<endl;
00796 cout << "Use program scripting syntax (do, set,...) !" << endl <<endl;
00797 cout << "export function "<< name<<" {"<<endl;
00798 }
00799 macrorecording = true;
00800 macroname = name;
00801 }
00802
00803 void TaskBrowser::cancelMacro() {
00804 cout << "Canceling macro "<< macroname <<endl;
00805 macrorecording = false;
00806 }
00807
00808 void TaskBrowser::endMacro() {
00809 string fname = macroname + ".ops";
00810 macrorecording = false;
00811 cout << "}" <<endl;
00812 cout << "Saving file "<< fname <<endl;
00813 ofstream macrofile( fname.c_str() );
00814 macrofile << "/* TaskBrowser macro '"<<macroname<<"' */" <<endl<<endl;
00815 macrofile << "export function "<<macroname<<" {"<<endl;
00816 macrofile << macrotext.c_str();
00817 macrofile << "}"<<endl;
00818
00819 cout << "Loading file "<< fname <<endl;
00820 ProgramLoader loader;
00821 if ( loader.loadProgram( fname, context ) ) {
00822 cout << "Done."<<endl;
00823 } else
00824 cout << "Failed."<<endl;
00825 }
00826
00827 void TaskBrowser::switchBack()
00828 {
00829 if ( taskHistory.size() == 0)
00830 return;
00831 if ( !taskcontext->engine()->commands()->isProcessed( lastc ) ) {
00832 Logger::log()<<Logger::Warning
00833 << "Previous command was not yet processed by previous Processor." <<Logger::nl
00834 << " Can not track command status across tasks."<< endlog();
00835
00836 command = 0;
00837 } else {
00838 delete command;
00839 command = 0;
00840 }
00841
00842 this->switchTaskContext( taskHistory.front(), false );
00843 lastc = 0;
00844 taskHistory.pop_front();
00845 }
00846
00847 void TaskBrowser::checkPorts()
00848 {
00849
00850
00851 DataFlowInterface::Ports ports;
00852 ports = this->ports()->getPorts();
00853 for( DataFlowInterface::Ports::iterator i=ports.begin(); i != ports.end(); ++i) {
00854
00855 PortInterface* p = *i;
00856 PortInterface* tcp = taskcontext->ports()->getPort( p->getName() );
00857 if ( p->ready() == false || tcp == 0 || tcp->ready() == false) {
00858 this->ports()->removePort( p->getName() );
00859 delete p;
00860 }
00861 }
00862 }
00863
00864 void TaskBrowser::setColorTheme(ColorTheme t)
00865 {
00866
00867 const char* dbg = "\033[01;";
00868 const char* wbg = "\033[02;";
00869
00870 const char* r = "31m";
00871 const char* g = "32m";
00872 const char* b = "34m";
00873 const char* con = "31m";
00874 const char* coff = "\33[0m";
00875 const char* und = "\33[4m";
00876
00877 switch (t)
00878 {
00879 case nocolors:
00880 green.clear();
00881 red.clear();
00882 blue.clear();
00883 coloron.clear();
00884 coloroff.clear();
00885 underline.clear();
00886 return;
00887 break;
00888 case darkbg:
00889 green = dbg;
00890 red = dbg;
00891 blue = dbg;
00892 coloron = dbg;
00893 coloroff = wbg;
00894 break;
00895 case whitebg:
00896 green = wbg;
00897 red = wbg;
00898 blue = wbg;
00899 coloron = wbg;
00900 coloroff = wbg;
00901 break;
00902 }
00903 green += g;
00904 red += r;
00905 blue += b;
00906 coloron += con;
00907 coloroff = coff;
00908 underline = und;
00909 }
00910
00911 void TaskBrowser::switchTaskContext(std::string& c) {
00912
00913 peer = taskcontext;
00914 if ( this->findPeer( c + "." ) == 0 ) {
00915 cerr << "No such peer: "<< c <<nl;
00916 return;
00917 }
00918
00919 if ( peer == taskcontext ) {
00920 cerr << "Already in "<< c <<nl;
00921 return;
00922 }
00923
00924 if ( peer == tb ) {
00925 cerr << "Can not switch to TaskBrowser." <<nl;
00926 return;
00927 }
00928
00929
00930 this->switchTaskContext( peer );
00931 }
00932
00933 void TaskBrowser::switchTaskContext(TaskContext* tc, bool store) {
00934
00935 if (taskHistory.size() == 20 )
00936 taskHistory.pop_back();
00937 if ( taskcontext && store)
00938 taskHistory.push_front( taskcontext );
00939
00940
00941
00942 if ( taskcontext && !taskcontext->engine()->commands()->isProcessed( lastc ) ) {
00943 Logger::log()<<Logger::Warning
00944 << "Previous command was not yet processed by previous Processor." <<Logger::nl
00945 << " Can not track command status across tasks."<< endlog();
00946
00947 command = 0;
00948 } else {
00949 delete command;
00950 command = 0;
00951 }
00952
00953
00954 this->disconnect();
00955
00956
00957 DataFlowInterface::Ports ports = this->ports()->getPorts();
00958 for( DataFlowInterface::Ports::iterator i=ports.begin(); i != ports.end(); ++i) {
00959 this->ports()->removePort( (*i)->getName() );
00960 delete *i;
00961 }
00962
00963
00964 if ( context == taskcontext )
00965 context = tc;
00966 taskcontext = tc;
00967 lastc = 0;
00968
00969
00970 this->addPeer( taskcontext );
00971
00972 cerr << " Switched to : " << taskcontext->getName() <<endl;
00973
00974 }
00975
00976 TaskContext* TaskBrowser::findPeer(std::string c) {
00977
00978 std::string s( c );
00979
00980 our_pos_iter_t parsebegin( s.begin(), s.end(), "teststring" );
00981 our_pos_iter_t parseend;
00982
00983 CommonParser cp;
00984 PeerParser pp( peer, cp, true );
00985 bool &skipref = cp.skipeol;
00986 try {
00987 parse( parsebegin, parseend, pp.parser(), SKIP_PARSER );
00988 }
00989 catch( ... )
00990 {
00991 log(Debug) <<"No such peer : "<< c <<endlog();
00992 return 0;
00993 }
00994 taskobject = pp.taskObject();
00995 assert(taskobject);
00996 peer = pp.peer();
00997 return pp.peer();
00998 }
00999
01000 void TaskBrowser::browserAction(std::string& act)
01001 {
01002 std::stringstream ss(act);
01003 std::string instr;
01004 ss >> instr;
01005
01006 if ( instr == "list" ) {
01007 int line;
01008 ss >> line;
01009 if (ss) {
01010 this->printProgram(line);
01011 return;
01012 }
01013 ss.clear();
01014 string arg;
01015 ss >> arg;
01016 if (ss) {
01017 ss.clear();
01018 ss >> line;
01019 if (ss) {
01020
01021 this->printProgram(arg, line);
01022 return;
01023 }
01024
01025 this->printProgram( arg );
01026 return;
01027 }
01028
01029 this->printProgram();
01030 return;
01031 }
01032
01033
01034
01035
01036 if ( instr == "trace") {
01037 string arg;
01038 ss >> arg;
01039 if (ss) {
01040 bool pi = context->scripting()->hasProgram(arg);
01041 if (pi) {
01042 ptraces[make_pair(context, arg)] = context->scripting()->getProgramLine(arg);
01043 this->printProgram( arg );
01044 return;
01045 }
01046 pi = context->scripting()->hasStateMachine(arg);
01047 if (pi) {
01048 straces[make_pair(context, arg)] = context->scripting()->getStateMachineLine(arg);
01049 this->printProgram( arg );
01050 return;
01051 }
01052 cerr <<"No such program or state machine: "<< arg <<endl;
01053 return;
01054 }
01055
01056
01057 std::vector<std::string> names;
01058 names = context->scripting()->getPrograms();
01059 for (std::vector<std::string>::iterator it = names.begin(); it != names.end(); ++it) {
01060 bool pi = context->scripting()->hasProgram(arg);
01061 if (pi)
01062 ptraces[make_pair(context, arg)] = context->scripting()->getProgramLine(arg);
01063 }
01064
01065 names = context->scripting()->getStateMachines();
01066 for (std::vector<std::string>::iterator it = names.begin(); it != names.end(); ++it) {
01067 bool pi = context->scripting()->hasStateMachine(arg);
01068 if (pi)
01069 straces[make_pair(context, arg)] = context->scripting()->getStateMachineLine(arg);
01070 }
01071
01072 cerr << "Tracing all programs and state machines in "<< context->getName() << endl;
01073 return;
01074 }
01075
01076 if ( instr == "untrace") {
01077 string arg;
01078 ss >> arg;
01079 if (ss) {
01080 ptraces.erase( make_pair(context, arg) );
01081 straces.erase( make_pair(context, arg) );
01082 cerr <<"Untracing "<< arg <<" of "<< context->getName()<<endl;
01083 return;
01084 }
01085
01086 std::vector<std::string> names;
01087 names = context->scripting()->getPrograms();
01088 for (std::vector<std::string>::iterator it = names.begin(); it != names.end(); ++it) {
01089 bool pi = context->scripting()->hasProgram(arg);
01090 if (pi)
01091 ptraces.erase(make_pair(context, arg));
01092 }
01093
01094 names = context->scripting()->getStateMachines();
01095 for (std::vector<std::string>::iterator it = names.begin(); it != names.end(); ++it) {
01096 bool pi = context->scripting()->hasStateMachine(arg);
01097 if (pi)
01098 straces.erase(make_pair(context, arg));
01099 }
01100
01101 cerr << "Untracing all programs and state machines of "<< context->getName() << endl;
01102 return;
01103 }
01104
01105 std::string arg;
01106 ss >> arg;
01107 ProgramLoader loader;
01108 if ( instr == "loadProgram") {
01109 if ( loader.loadProgram( arg, context ) )
01110 cout << "Done."<<endl;
01111 else
01112 cout << "Failed."<<endl;
01113 return;
01114 }
01115 if ( instr == "unloadProgram") {
01116 if ( loader.unloadProgram( arg, context ) )
01117 cout << "Done."<<endl;
01118 else
01119 cout << "Failed."<<endl;
01120 return;
01121 }
01122
01123 if ( instr == "loadStateMachine") {
01124 if ( loader.loadStateMachine( arg, context ) )
01125 cout << "Done."<<endl;
01126 else
01127 cout << "Failed."<<endl;
01128 return;
01129 }
01130 if ( instr == "unloadStateMachine") {
01131 if ( loader.unloadStateMachine( arg, context ) )
01132 cout << "Done."<<endl;
01133 else
01134 cout << "Failed."<<endl;
01135 return;
01136 }
01137 if ( instr == "dark") {
01138 this->setColorTheme(darkbg);
01139 cout << nl << "Setting Color Theme for "+green+"dark"+coloroff+" backgrounds."<<endl;
01140 return;
01141 }
01142 if ( instr == "light") {
01143 this->setColorTheme(whitebg);
01144 cout << nl << "Setting Color Theme for "+green+"light"+coloroff+" backgrounds."<<endl;
01145 return;
01146 }
01147 if ( instr == "nocolors") {
01148 this->setColorTheme(nocolors);
01149 cout <<nl << "Disabling all colors"<<endl;
01150 return;
01151 }
01152 if ( instr == "connect") {
01153 if (arg.empty() ) {
01154 cout <<nl << "TaskBrowser connects to all ports of "<<taskcontext->getName()<<endl;
01155
01156 DataFlowInterface::Ports ports = taskcontext->ports()->getPorts();
01157 for( DataFlowInterface::Ports::iterator i=ports.begin(); i != ports.end(); ++i) {
01158 if (this->ports()->getPort( (*i)->getName() ) == 0 )
01159 this->ports()->addPort( (*i)->antiClone() );
01160 }
01161 RTT::connectPorts(this,taskcontext);
01162 }
01163 else {
01164 cout <<nl << "TaskBrowser connects to port '"<<arg <<"' of "<<taskcontext->getName()<<endl;
01165
01166 DataFlowInterface::Ports ports = taskcontext->ports()->getPorts();
01167 for( DataFlowInterface::Ports::iterator i=ports.begin(); i != ports.end(); ++i) {
01168 if ( (*i)->getName() == arg && this->ports()->getPort( (*i)->getName() ) == 0 ) {
01169 this->ports()->addPort( (*i)->antiClone() );
01170 this->ports()->getPort( arg )->connectTo( *i );
01171 assert( this->ports()->getPort( arg )->connected() );
01172 return;
01173 }
01174 }
01175 }
01176 return;
01177 }
01178 if ( instr == "record") {
01179 recordMacro( arg );
01180 return;
01181 }
01182 if ( instr == "cancel") {
01183 cancelMacro();
01184 return;
01185 }
01186 if ( instr == "end") {
01187 endMacro();
01188 return;
01189 }
01190 cerr << "Unknown Browser Action : "<< act <<endl;
01191 cerr << "See 'help' for valid syntax."<<endl;
01192 }
01193
01194 void TaskBrowser::evaluate(std::string& comm) {
01195 this->evalCommand(comm);
01196 }
01197
01198 void TaskBrowser::evalCommand(std::string& comm )
01199 {
01200 cout << " Got :"<< comm <<nl;
01201
01202 OperationInterface* ops = context->getObject( comm );
01203 if ( ops )
01204 {
01205 sresult << nl << "Printing Interface of '"<< coloron << ops->getName() <<coloroff <<"' :"<<nl<<nl;
01206 std::vector<std::string> methods = ops->commands()->getNames();
01207 std::for_each( methods.begin(), methods.end(), boost::bind(&TaskBrowser::printCommand, this, _1, ops) );
01208 methods = ops->methods()->getNames();
01209 std::for_each( methods.begin(), methods.end(), boost::bind(&TaskBrowser::printMethod, this, _1, ops) );
01210 if (comm == "this") {
01211 methods = taskcontext->events()->getNames();
01212 std::for_each( methods.begin(), methods.end(), boost::bind(&TaskBrowser::printEvent, this, _1, taskcontext->events()) );
01213 }
01214 cout << sresult.str();
01215 sresult.str("");
01216
01217 }
01218
01219
01220
01221
01222 if ( context->attributes()->getValue( comm ) ) {
01223 this->printResult( context->attributes()->getValue( comm )->getDataSource().get(), true );
01224 cout << sresult.str();
01225 sresult.str("");
01226 return;
01227 }
01228
01229 if ( ops ) {
01230 return;
01231 }
01232
01233 Parser _parser;
01234
01235 if (debug)
01236 cerr << "Trying ValueChange..."<<nl;
01237 try {
01238
01239 DataSourceBase::shared_ptr ds = _parser.parseValueChange( comm, context );
01240
01241 if ( ds.get() != 0 ) {
01242 this->printResult( ds.get(), false );
01243 cout << sresult.str() << nl;
01244 sresult.str("");
01245 return;
01246 } else if (debug)
01247 cerr << "returned zero !"<<nl;
01248 } catch ( fatal_semantic_parse_exception& pe ) {
01249
01250 if (debug)
01251 cerr << "fatal_semantic_parse_exception: ";
01252 cerr << pe.what() <<nl;
01253 return;
01254 } catch ( syntactic_parse_exception& pe ) {
01255
01256 if (debug)
01257 cerr << "syntactic_parse_exception: ";
01258 cerr << pe.what() <<nl;
01259 return;
01260 } catch ( parse_exception_parser_fail &pe )
01261 {
01262
01263 if (debug) {
01264 cerr << "Ignoring ValueChange exception :"<<nl;
01265 cerr << pe.what() <<nl;
01266 }
01267 } catch ( parse_exception& pe ) {
01268
01269 if (debug)
01270 cerr << "parse_exception :";
01271 cerr << pe.what() <<nl;
01272 return;
01273 }
01274 if (debug)
01275 cerr << "Trying Expression..."<<nl;
01276 try {
01277
01278 DataSourceBase::shared_ptr ds = _parser.parseExpression( comm, context );
01279
01280 if ( ds.get() != 0 ) {
01281 this->printResult( ds.get(), true );
01282 cout << sresult.str() << nl;
01283 sresult.str("");
01284 return;
01285 } else if (debug)
01286 cerr << "returned zero !"<<nl;
01287 } catch ( syntactic_parse_exception& pe ) {
01288
01289 if (debug)
01290 cerr << "syntactic_parse_exception :";
01291 cerr << pe.what() <<nl;
01292 return;
01293 } catch ( fatal_semantic_parse_exception& pe ) {
01294
01295 if (debug)
01296 cerr << "fatal_semantic_parse_exception :";
01297 cerr << pe.what() <<nl;
01298 return;
01299 } catch ( parse_exception_parser_fail &pe )
01300 {
01301
01302 if (debug) {
01303 cerr << "Ignoring Expression exception :"<<nl;
01304 cerr << pe.what() <<nl;
01305 }
01306 } catch ( parse_exception& pe ) {
01307
01308 if (debug) {
01309 cerr << "Ignoring Expression parse_exception :"<<nl;
01310 cerr << pe.what() <<nl;
01311 }
01312 }
01313 if (debug)
01314 cerr << "Trying Command..."<<nl;
01315 try {
01316 CommandInterface* com = _parser.parseCommand( comm, context, true ).first;
01317
01318 if ( com && dynamic_cast<DispatchInterface*>(com) == 0 ) {
01319 string prompt =" = ";
01320 sresult <<prompt<< setw(20)<<left;
01321 sresult << com->execute() << right;
01322 cout << sresult.str();
01323 sresult.str("");
01324 delete com;
01325 return;
01326 }
01327 if ( command && !command->executed() ) {
01328 cerr << "Warning : previous command is not yet processed by Processor." <<nl;
01329 } else {
01330 delete command;
01331 }
01332 command = dynamic_cast<DispatchInterface*>(com);
01333 } catch ( parse_exception& pe ) {
01334 if (debug)
01335 cerr << "CommandParser parse_exception :"<<nl;
01336 cerr << pe.what() <<nl;
01337 return;
01338 } catch (...) {
01339 cerr << "Illegal Input."<<nl;
01340 return;
01341 }
01342
01343 if ( command == 0 ) {
01344 cerr << "Uncaught : Illegal command."<<nl;
01345 return;
01346 }
01347
01348 command->readArguments();
01349 if ( command->dispatch() == false ) {
01350 cerr << "Command not accepted by "<<context->getName()<<"'s Processor !" << nl;
01351 delete command;
01352 command = 0;
01353 accepted = 0;
01354 }
01355 }
01356
01357 void TaskBrowser::printResult( DataSourceBase* ds, bool recurse) {
01358 std::string prompt(" = ");
01359
01360 sresult <<prompt<< setw(20)<<left;
01361 if ( ds )
01362 doPrint( ds, recurse );
01363 else
01364 sresult << "(null)";
01365 sresult << right;
01366 }
01367
01368 void TaskBrowser::doPrint( DataSourceBase* ds, bool recurse) {
01369
01370
01371
01372 ds->reset();
01373
01374 DataSource<PropertyBag>* dspbag = DataSource<PropertyBag>::narrow(ds);
01375 if (dspbag) {
01376 PropertyBag bag( dspbag->get() );
01377 if (!recurse) {
01378 int siz = bag.getProperties().size();
01379 int wdth = siz ? (20 - (siz / 10 + 1)) : 20;
01380 sresult <<setw(0)<< siz <<setw( wdth )<< " Properties";
01381 } else {
01382 if ( ! bag.empty() ) {
01383 sresult <<setw(0)<<nl;
01384 for( PropertyBag::iterator it= bag.getProperties().begin(); it!=bag.getProperties().end(); ++it) {
01385 sresult <<setw(14)<<right<<(*it)->getType()<<" "<<coloron<<setw(14)<< (*it)->getName()<<coloroff;
01386 DataSourceBase::shared_ptr propds = (*it)->getDataSource();
01387 this->printResult( propds.get(), false );
01388 sresult <<" ("<<(*it)->getDescription()<<')' << nl;
01389 }
01390 } else {
01391 sresult <<prompt<<"(empty PropertyBag)";
01392 }
01393 }
01394 return;
01395 }
01396
01397 DataSourceBase::shared_ptr dsb(ds);
01398 dsb->evaluate();
01399 sresult << dsb;
01400 }
01401
01402 struct comcol
01403 {
01404 const char* command;
01405 comcol(const char* c) :command(c) {}
01406 std::ostream& operator()( std::ostream& os ) const {
01407 os<<"'"<< TaskBrowser::coloron<< TaskBrowser::underline << command << TaskBrowser::coloroff<<"'";
01408 return os;
01409 }
01410 };
01411
01412 struct keycol
01413 {
01414 const char* command;
01415 keycol(const char* c) :command(c) {}
01416 std::ostream& operator()( std::ostream& os )const {
01417 os<<"<"<< TaskBrowser::coloron<< TaskBrowser::underline << command << TaskBrowser::coloroff<<">";
01418 return os;
01419 }
01420 };
01421
01422 struct titlecol
01423 {
01424 const char* command;
01425 titlecol(const char* c) :command(c) {}
01426 std::ostream& operator()( std::ostream& os ) const {
01427 os<<endl<<"["<< TaskBrowser::coloron<< TaskBrowser::underline << command << TaskBrowser::coloroff<<"]";
01428 return os;
01429 }
01430 };
01431
01432 std::ostream& operator<<(std::ostream& os, comcol f ){
01433 return f(os);
01434 }
01435
01436 std::ostream& operator<<(std::ostream& os, keycol f ){
01437 return f(os);
01438 }
01439
01440 std::ostream& operator<<(std::ostream& os, titlecol f ){
01441 return f(os);
01442 }
01443
01444 void TaskBrowser::printHelp()
01445 {
01446 cout << coloroff;
01447 cout <<titlecol("Task Browsing")<<nl;
01448 cout << " To switch to another task, type "<<comcol("cd <path-to-taskname>")<<nl;
01449 cout << " and type "<<comcol("cd ..")<<" to go back to the previous task (History size is 20)."<<nl;
01450 cout << " Pressing "<<keycol("tab")<<" multiple times helps you to complete your command."<<nl;
01451 cout << " It is not mandatory to switch to a task to interact with it, you can type the"<<nl;
01452 cout << " peer-path to the task (dot-separated) and then type command or expression :"<<nl;
01453 cout << " PeerTask.OtherTask.FinalTask.countTo(3) [enter] "<<nl;
01454 cout << " Where 'countTo' is a method of 'FinalTask'."<<nl;
01455 cout << " The TaskBrowser starts by default 'In' the current component. In order to watch"<<nl;
01456 cout << " the TaskBrowser itself, type "<<comcol("leave")<<" You will notice that it"<<nl;
01457 cout << " has connected to the data ports of the visited component. Use "<<comcol("enter")<<" to enter"<<nl;
01458 cout << " the visited component again. The "<<comcol("cd")<<" command works transparantly in both"<<nl;
01459 cout << " modi."<<nl;
01460
01461 cout << " "<<titlecol("Task Context Info")<<nl;
01462 cout << " To see the contents of a task, type "<<comcol("ls")<<nl;
01463 cout << " For a detailed argument list (and helpful info) of the object's methods, "<<nl;
01464 cout <<" type the name of one of the listed task objects : " <<nl;
01465 cout <<" this [enter]" <<nl<<nl;
01466 cout <<" Command : bool factor( int number )" <<nl;
01467 cout <<" Factor a value into its primes." <<nl;
01468 cout <<" number : The number to factor in primes." <<nl;
01469 cout <<" Method : bool isRunning( )" <<nl;
01470 cout <<" Is this TaskContext started ?" <<nl;
01471 cout <<" Method : bool loadProgram( const& std::string Filename )" <<nl;
01472 cout <<" Load an Orocos Program Script from a file." <<nl;
01473 cout <<" Filename : An ops file." <<nl;
01474 cout <<" ..."<<nl;
01475
01476 cout <<titlecol("Expressions")<<nl;
01477 cout << " You can evaluate any script expression by merely typing it :"<<nl;
01478 cout << " 1+1 [enter]" <<nl;
01479 cout << " = 2" <<nl;
01480 cout << " or inspect the status of a program :"<<nl;
01481 cout << " programs.myProgram.isRunning [enter]" <<nl;
01482 cout << " = false" <<nl;
01483 cout << " and display the contents of complex data types (vector, array,...) :"<<nl;
01484 cout << " array(6)" <<nl;
01485 cout << " = {0, 0, 0, 0, 0, 0}" <<nl;
01486
01487 cout <<titlecol("Changing Attributes and Properties")<<nl;
01488 cout << " To change the value of a Task's attribute, type "<<comcol("varname = <newvalue>")<<nl;
01489 cout << " If you provided a correct assignment, the browser will inform you of the success"<<nl;
01490 cout <<" with '= true'." <<nl;
01491
01492 cout <<titlecol("Commands")<<nl;
01493 cout << " A Command is 'sent' to a task, which will process it in its own context (thread)."<<nl;
01494 cout << " A command consists of an object, followed by a dot ('.'), the command "<<nl;
01495 cout << " name, followed by the parameters. An example could be :"<<nl;
01496 cout << " otherTask.bar.orderBeers(\"Palm\", 5) [enter] "<<nl;
01497 cout << " The prompt will inform you about the status of the last command you entered. "<<nl;
01498 cout << " It is allowed to enter a new command while the previous is still busy. "<<nl;
01499
01500 cout <<titlecol("Methods")<<nl;
01501 cout << " Methods 'look' the same as commands, but they are evaluated"<<nl;
01502 cout << " immediately and print the result. An example could be :"<<nl;
01503 cout << " someTask.bar.getNumberOfBeers(\"Palm\") [enter] "<<nl;
01504 cout << " = 99" <<nl;
01505
01506 cout <<titlecol("Events")<<nl;
01507 cout << " Events behave as methods, they are emitted immediately."<<nl;
01508 cout << " An example emitting an event :"<<nl;
01509 cout << " someTask.notifyUserState(\"Drunk\") [enter] "<<nl;
01510 cout << " = (void)" <<nl;
01511
01512 cout <<titlecol("Program and StateMachine Scripts")<<nl;
01513 cout << " To load a program script from local disc, type "<<comcol(".loadProgram <filename>")<<nl;
01514 cout << " To load a state machine script from local disc, type "<<comcol(".loadStateMachine <filename>")<<nl;
01515 cout << " ( notice the starting dot '.' )"<<nl;
01516 cout << " Likewise, "<<comcol(".loadProgram <ProgramName>")<<" and "<<comcol(".unloadStateMachine <StateMachineName>")<<nl;
01517 cout << " are available (notice it is the program's name, not the filename)."<<nl;
01518 cout << " You can use "<<comcol("ls progname")<<nl;
01519 cout << " to see the programs commands, methods and variables. You can manipulate each one of these,."<<nl;
01520 cout << " as if the program is a Task itself (see all items above)."<<nl;
01521
01522 cout << " To print a program or state machine listing, use "<<comcol("list progname [linenumber]")<<nl;
01523 cout << " to list the contents of the current program lines being executed,"<<nl;
01524 cout << " or 10 lines before or after <linenumber>. When only "<<comcol("list [n]")<<nl;
01525 cout << " is typed, 20 lines of the last listed program are printed from line <n> on "<<nl;
01526 cout << " ( default : list next 20 lines after previous list )."<<nl;
01527
01528 cout << " To trace a program or state machine listing, use "<<comcol("trace [progname]")<<" this will"<<nl;
01529 cout << " cause the TaskBrowser to list the contents of a traced program,"<<nl;
01530 cout << " each time the line number of the traced program changes."<<nl;
01531 cout << " Disable tracing with "<<comcol("untrace [progname]")<<""<<nl;
01532 cout << " If no arguments are given to "<<comcol("trace")<<" and "<<comcol("untrace")<<", it applies to all programs."<<nl;
01533
01534 cout << " A status character shows which line is being executed."<<nl;
01535 cout << " For programs : 'E':Error, 'S':Stopped, 'R':Running, 'P':Paused"<<nl;
01536 cout << " For state machines : <the same as programs> + 'A':Active, 'I':Inactive"<<nl;
01537
01538 cout <<titlecol("Changing Colors")<<nl;
01539 cout << " You can inform the TaskBrowser of your background color by typing "<<comcol(".dark")<<nl;
01540 cout << " "<<comcol(".light")<<", or "<<comcol(".nocolors")<<" to increase readability."<<nl;
01541
01542 cout <<titlecol("Macro Recording / Command line history")<<nl;
01543 cout << " You can browse the commandline history by using the up-arrow key or press "<<comcol("Ctrl r")<<nl;
01544 cout << " and a search term. Hit enter to execute the current searched command."<<nl;
01545 cout << " Macros can be recorded using the "<<comcol(".record 'macro-name'")<<" command."<<nl;
01546 cout << " You can cancel the recording by typing "<<comcol(".cancel")<<" ."<<nl;
01547 cout << " You can save and load the macro by typing "<<comcol(".end")<<" . The macro becomes"<<nl;
01548 cout << " available as a command with name 'macro-name' in the current TaskContext." << nl;
01549 cout << " While you enter the macro, it is not executed, as you must use scripting syntax which"<<nl;
01550 cout << " may use loop or conditional statements, variables etc."<<nl;
01551
01552 cout <<titlecol("Connecting Ports")<<nl;
01553 cout << " You can instruct the TaskBrowser to connect to the ports of the current Peer by"<<nl;
01554 cout << " typing "<<comcol(".connect [port-name]")<<", which will temporarily create connections"<<nl;
01555 cout << " to all ports if [port-name] is omitted or to the specified port otherwise."<<nl;
01556 cout << " The TaskBrowser disconnects these ports when it visits another component, but the"<<nl;
01557 cout << " created connection objects remain in place (this is more or less a bug)!"<<nl;
01558 }
01559
01560 void TaskBrowser::printProgram(const std::string& progname, int cl , TaskContext* progpeer ) {
01561 string ps;
01562 char s;
01563 stringstream txtss;
01564 int ln;
01565 int start;
01566 int end;
01567 bool found(false);
01568
01569 if (progpeer == 0 )
01570 progpeer = context;
01571
01572
01573 if ( progpeer->scripting()->hasProgram( progname ) ) {
01574 s = getProgramStatusChar(progpeer, progname);
01575 txtss.str( progpeer->scripting()->getProgramText(progname) );
01576 ln = progpeer->scripting()->getProgramLine(progname);
01577 if ( cl < 0 ) cl = ln;
01578 start = cl < 10 ? 1 : cl - 10;
01579 end = cl + 10;
01580 this->listText( txtss, start, end, ln, s);
01581 found = true;
01582 }
01583
01584
01585 if ( progpeer->scripting()->hasStateMachine( progname ) ) {
01586 s = getStateMachineStatusChar(progpeer, progname);
01587 txtss.str( progpeer->scripting()->getStateMachineText(progname) );
01588 ln = progpeer->scripting()->getStateMachineLine(progname);
01589 if ( cl < 0 ) cl = ln;
01590 start = cl <= 10 ? 1 : cl - 10;
01591 end = cl + 10;
01592 this->listText( txtss, start, end, ln, s);
01593 found = true;
01594 }
01595 if ( !found ) {
01596 cerr << "Error : No such program or state machine found : "<<progname;
01597 cerr << " in "<< progpeer->getName() <<"."<<endl;
01598 return;
01599 }
01600 storedname = progname;
01601 }
01602
01603 void TaskBrowser::printProgram(int cl ) {
01604 string ps;
01605 char s;
01606 stringstream txtss;
01607 int ln;
01608 int start;
01609 int end;
01610 bool found(false);
01611 if ( context->scripting()->hasProgram( storedname ) ) {
01612 s = getProgramStatusChar(context, storedname);
01613 txtss.str( context->scripting()->getProgramText(storedname) );
01614 ln = context->scripting()->getProgramLine(storedname);
01615 if ( cl < 0 ) cl = storedline;
01616 if (storedline < 0 ) cl = ln -10;
01617 start = cl;
01618 end = cl + 20;
01619 this->listText( txtss, start, end, ln, s);
01620 found = true;
01621 }
01622 if ( context->scripting()->hasStateMachine(storedname) ) {
01623 s = getStateMachineStatusChar(context, storedname);
01624 txtss.str( context->scripting()->getStateMachineText(storedname) );
01625 ln = context->scripting()->getStateMachineLine(storedname);
01626 if ( cl < 0 ) cl = storedline;
01627 if (storedline < 0 ) cl = ln -10;
01628 start = cl;
01629 end = cl+20;
01630 this->listText( txtss, start, end, ln, s);
01631 found = true;
01632 }
01633 if ( !found )
01634 cerr << "Error : No such program or state machine found : "<<storedname<<endl;
01635 }
01636
01637 void TaskBrowser::listText(stringstream& txtss,int start, int end, int ln, char s) {
01638 int curln = 1;
01639 string line;
01640 while ( start > 1 && curln != start ) {
01641 getline( txtss, line, '\n' );
01642 if ( ! txtss )
01643 break;
01644 ++curln;
01645 }
01646 while ( end > start && curln != end ) {
01647 getline( txtss, line, '\n' );
01648 if ( ! txtss )
01649 break;
01650 if ( curln == ln ) {
01651 cout << s<<'>';
01652 }
01653 else
01654 cout << " ";
01655 cout<< setw(int(log(double(end)))) <<right << curln<< left;
01656 cout << ' ' << line <<endl;
01657 ++curln;
01658 }
01659 storedline = curln;
01660 // done !
01661 }
01662
01663 void TaskBrowser::printInfo(const std::string& peerp)
01664 {
01665 // this sets this->peer to the peer given
01666 peer = context;
01667 if ( this->findPeer( peerp+"." ) == 0 ) {
01668 cerr << "No such peer or object: " << peerp << endl;
01669 return;
01670 }
01671
01672 if ( !peer || !peer->ready()) {
01673 cout << nl << " Connection to peer "+peerp+" lost (peer->ready() == false)." <<endlog();
01674 return;
01675 }
01676
01677 if ( peer == taskobject )
01678 sresult <<nl<<" Listing TaskContext "<< green << peer->getName()<<coloroff<< " :"<<nl;
01679 else
01680 sresult <<nl<<" Listing TaskObject "<< green << taskobject->getName()<<coloroff<< " :"<<nl;
01681
01682 // Only print Properties for TaskContexts
01683 if ( peer == taskobject ) {
01684 sresult <<nl<<" Configuration Properties: ";
01685 PropertyBag* bag = peer->properties();
01686 if ( bag && bag->size() != 0 ) {
01687 // Print Properties:
01688 for( PropertyBag::iterator it = bag->begin(); it != bag->end(); ++it) {
01689 DataSourceBase::shared_ptr pds = (*it)->getDataSource();
01690 sresult << nl << setw(11)<< right << (*it)->getType()<< " "
01691 << coloron <<setw(14)<<left<< (*it)->getName() << coloroff;
01692 this->printResult( pds.get(), false ); // do not recurse
01693 sresult<<" ("<< (*it)->getDescription() <<')';
01694 }
01695 } else {
01696 sresult << "(none)";
01697 }
01698 sresult <<nl;
01699 }
01700
01701 // Print "this" interface (without detail) and then list objects...
01702 sresult <<nl<< " Execution Interface:";
01703
01704 sresult <<nl<< " Attributes : ";
01705 std::vector<std::string> objlist = taskobject->attributes()->names();
01706 if ( !objlist.empty() ) {
01707 sresult << nl;
01708 // Print Attributes:
01709 for( std::vector<std::string>::iterator it = objlist.begin(); it != objlist.end(); ++it) {
01710 DataSourceBase::shared_ptr pds = taskobject->attributes()->getValue(*it)->getDataSource();
01711 sresult << setw(11)<< right << pds->getType()<< " "
01712 << coloron <<setw( 14 )<<left<< *it << coloroff;
01713 this->printResult( pds.get(), false ); // do not recurse
01714 sresult <<nl;
01715 }
01716 } else {
01717 sresult << coloron << "(none)";
01718 }
01719
01720 sresult <<coloroff<<nl<< " Methods : "<<coloron;
01721 objlist = taskobject->methods()->getNames();
01722 if ( !objlist.empty() ) {
01723 copy(objlist.begin(), objlist.end(), std::ostream_iterator<std::string>(sresult, " "));
01724 } else {
01725 sresult << "(none)";
01726 }
01727 sresult <<coloroff<<nl<< " Commands : "<<coloron;
01728 objlist = taskobject->commands()->getNames();
01729 if ( !objlist.empty() ) {
01730 copy(objlist.begin(), objlist.end(), std::ostream_iterator<std::string>(sresult, " "));
01731 } else {
01732 sresult << "(none)";
01733 }
01734 sresult <<coloroff<<nl<< " Events : "<<coloron;
01735 objlist = taskobject->events()->getEvents();
01736 if ( !objlist.empty() ) {
01737 copy(objlist.begin(), objlist.end(), std::ostream_iterator<std::string>(sresult, " "));
01738 } else {
01739 sresult << "(none)";
01740 }
01741 sresult << coloroff << nl;
01742
01743 if ( peer == taskobject ) {
01744 sresult <<nl<< " Data Flow Ports: ";
01745 objlist = peer->ports()->getPortNames();
01746 if ( !objlist.empty() ) {
01747 for(vector<string>::iterator it = objlist.begin(); it != objlist.end(); ++it) {
01748 PortInterface* port = peer->ports()->getPort(*it);
01749 PortInterface::PortType pt = port->getPortType();
01750 // Port type R/W
01751 sresult << nl << " " << (pt == PortInterface::ReadPort ?
01752 " R" : pt == PortInterface::WritePort ? " W" : "RW");
01753 // Port data type + name
01754 if ( !port->ready() || !port->connection() )
01755 sresult << "(U) " << setw(11)<<right<< port->getTypeInfo()->getTypeName();
01756 else
01757 sresult << "(C) " << setw(11)<<right<< port->getTypeInfo()->getTypeName();
01758 sresult << " "
01759 << coloron <<setw( 14 )<<left<< *it << coloroff;
01760 if ( port->ready() )
01761 sresult << " = " <<port->connection()->getDataSource();
01762 else {
01763 ConnectionInterface::shared_ptr c = port->createConnection();
01764 if ( c )
01765 sresult << " = " << c->getDataSource();
01766 }
01767 // Port description
01768 // if ( peer->getObject(*it) )
01769 // sresult << " ( "<< taskobject->getObject(*it)->getDescription() << " ) ";
01770 }
01771 } else {
01772 sresult << "(none)";
01773 }
01774 sresult << coloroff << nl;
01775 }
01776
01777 objlist = taskobject->getObjectList();
01778 sresult <<nl<< " Task Objects: "<<nl;
01779 if ( !objlist.empty() ) {
01780 for(vector<string>::iterator it = objlist.begin(); it != objlist.end(); ++it)
01781 sresult <<coloron<< " " << setw(14) << *it <<coloroff<< " ( "<< taskobject->getObject(*it)->getDescription() << " ) "<<nl;
01782 } else {
01783 sresult <<coloron<< "(none)" <<coloroff <<nl;
01784 }
01785
01786 // TaskContext specific:
01787 if ( peer == taskobject ) {
01788
01789 objlist = peer->scripting()->getPrograms();
01790 if ( !objlist.empty() ) {
01791 sresult << " Programs : "<<coloron;
01792 for(vector<string>::iterator it = objlist.begin(); it != objlist.end(); ++it)
01793 sresult << *it << "["<<getProgramStatusChar(peer,*it)<<"] ";
01794 sresult << coloroff << nl;
01795 }
01796
01797 objlist = peer->scripting()->getStateMachines();
01798 if ( !objlist.empty() ) {
01799 sresult << " StateMachines: "<<coloron;
01800 for(vector<string>::iterator it = objlist.begin(); it != objlist.end(); ++it)
01801 sresult << *it << "["<<getStateMachineStatusChar(peer,*it)<<"] ";
01802 sresult << coloroff << nl;
01803 }
01804
01805 // if we are in the TB, display the peers of our connected task:
01806 if ( context == tb )
01807 sresult <<nl<< " "<<peer->getName()<<" Peers : "<<coloron;
01808 else
01809 sresult << nl <<" Peers : "<<coloron;
01810
01811 objlist = peer->getPeerList();
01812 if ( !objlist.empty() )
01813 for(vector<string>::iterator it = objlist.begin(); it != objlist.end(); ++it) {
01814 assert( peer->getPeer(*it) );
01815 sresult << *it << "["<<getTaskStatusChar(peer->getPeer(*it))<<"] ";
01816 }
01817 else
01818 sresult << "(none)";
01819 }
01820 sresult <<coloroff<<nl;
01821 cout << sresult.str();
01822 sresult.str("");
01823 }
01824
01825 void TaskBrowser::printCommand( const std::string m, OperationInterface* ops )
01826 {
01827 std::vector<ArgumentDescription> args;
01828 args = ops->commands()->getArgumentList( m );
01829 sresult << " Command : bool " << coloron << m << coloroff<< "( ";
01830 for (std::vector<ArgumentDescription>::iterator it = args.begin(); it != args.end(); ++it) {
01831 sresult << it->type <<" ";
01832 sresult << coloron << it->name << coloroff;
01833 if ( it+1 != args.end() )
01834 sresult << ", ";
01835 else
01836 sresult << " ";
01837 }
01838 sresult << ")"<<nl;
01839 sresult << " " << ops->commands()->getDescription( m )<<nl;
01840 for (std::vector<ArgumentDescription>::iterator it = args.begin(); it != args.end(); ++it)
01841 sresult <<" "<< it->name <<" : " << it->description << nl;
01842 }
01843
01844 void TaskBrowser::printMethod( const std::string m, OperationInterface* ops )
01845 {
01846 std::vector<ArgumentDescription> args;
01847 args = ops->methods()->getArgumentList( m );
01848 sresult << " Method : "<< ops->methods()->getResultType(m)<<" " << coloron << m << coloroff<< "( ";
01849 for (std::vector<ArgumentDescription>::iterator it = args.begin(); it != args.end(); ++it) {
01850 sresult << it->type <<" ";
01851 sresult << coloron << it->name << coloroff;
01852 if ( it+1 != args.end() )
01853 sresult << ", ";
01854 else
01855 sresult << " ";
01856 }
01857 sresult << ")"<<nl;
01858 sresult << " " << ops->methods()->getDescription( m )<<nl;
01859 for (std::vector<ArgumentDescription>::iterator it = args.begin(); it != args.end(); ++it)
01860 sresult <<" "<< it->name <<" : " << it->description << nl;
01861 }
01862
01863 void TaskBrowser::printEvent( const std::string m, EventService* ops )
01864 {
01865 std::vector<ArgumentDescription> args;
01866 args = ops->getArgumentList( m );
01867 sresult << " Event : "<< ops->getResultType(m)<<" " << coloron << m << coloroff<< "( ";
01868 for (std::vector<ArgumentDescription>::iterator it = args.begin(); it != args.end(); ++it) {
01869 sresult << it->type <<" ";
01870 sresult << coloron << it->name << coloroff;
01871 if ( it+1 != args.end() )
01872 sresult << ", ";
01873 else
01874 sresult << " ";
01875 }
01876 sresult << ")"<<nl;
01877 sresult << " " << ops->getDescription( m )<<nl;
01878 for (std::vector<ArgumentDescription>::iterator it = args.begin(); it != args.end(); ++it)
01879 sresult <<" "<< it->name <<" : " << it->description << nl;
01880 }
01881
01882 }