TaoExample.cpp
Go to the documentation of this file.
00001 /*
00002  * Filename: TaoExample.cpp
00003  *   Author: Igor Makhtes
00004  *     Date: Dec 26, 2013
00005  *
00006  * The MIT License (MIT)
00007  *
00008  * Copyright (c) 2013 Cogniteam Ltd.
00009  *
00010  * Permission is hereby granted, free of charge, to any person obtaining a copy
00011  * of this software and associated documentation files (the "Software"), to deal
00012  * in the Software without restriction, including without limitation the rights
00013  * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
00014  * copies of the Software, and to permit persons to whom the Software is
00015  * furnished to do so, subject to the following conditions:
00016  *
00017  * The above copyright notice and this permission notice shall be included in
00018  * all copies or substantial portions of the Software.
00019  *
00020  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00021  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00022  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
00023  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00024  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00025  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
00026  * THE SOFTWARE.
00027  */
00028 
00029 #include <iostream>
00030 #include <boost/bind.hpp>
00031 #include <boost/thread.hpp>
00032 #include <boost/foreach.hpp>
00033 #include <ros/ros.h>
00034 
00035 #include <decision_making/TAO.h>
00036 #include <decision_making/TAOStdProtocols.h>
00037 #include <decision_making/ROSTask.h>
00038 #include <decision_making/DecisionMaking.h>
00039 
00040 using namespace std;
00041 using namespace decision_making;
00042 
00043 #define foreach BOOST_FOREACH
00044 
00045 TAO_HEADER(Tao2)
00046 TAO_HEADER(Tao3)
00047 
00048 #define TAO_STOP_CONDITION(X) TAO_STOP_CONDITION_AND_PRINT_EVENTS(X)
00049 
00050 TAO(Tao1)
00051 {
00052         cout<<"[STR: Tao1]"<<endl;
00053         struct T{~T(){ cout<<"[END: Tao1]"<<endl; }} t;
00054     TAO_PLANS{
00055         Plan1,
00056         Plan2,
00057         Plan3
00058     }
00059     TAO_START_PLAN(Plan1);
00060     TAO_BGN{
00061         TAO_PLAN( Plan1 ){
00062             TAO_START_CONDITION(true);
00063             TAO_ALLOCATE(AllocFirstReady){
00064                 TAO_SUBPLAN(Tao2);
00065                 TAO_SUBPLAN(Tao3);
00066             }
00067             TAO_CALL_TASK(C);
00068             TAO_CLEANUP_BGN
00069             {
00070                 TAO_CALL_TASK(testTask);
00071             }
00072             TAO_CLEANUP_END
00073             TAO_STOP_CONDITION(event == TAO_EVENT(/FAIL))
00074             TAO_NEXT(NextFirstReady){
00075                 TAO_NEXT_PLAN(Plan3);
00076                 TAO_NEXT_PLAN(Plan2);
00077             }
00078         }
00079         TAO_PLAN( Plan2 ){
00080             TAO_START_CONDITION(true);
00081             TAO_CALL_TASK(testTask);
00082             TAO_ALLOCATE(AllocFirstReady){
00083                 TAO_SUBPLAN(Tao2);
00084                 TAO_SUBPLAN(Tao3);
00085             }
00086             TAO_STOP_CONDITION(true);
00087             TAO_NEXT_EMPTY
00088         }
00089         TAO_PLAN( Plan3 ){
00090             TAO_START_CONDITION(true);
00091             //TAO_RESULT(SUCCESS, TaskResult::SUCCESS());
00092             TAO_ALLOCATE_EMPTY
00093             TAO_STOP_CONDITION(true);
00094             TAO_NEXT(NextFirstReady){
00095                 TAO_NEXT_PLAN(Plan1);
00096                 TAO_NEXT_PLAN(Plan2);
00097             }
00098         }
00099     }
00100     TAO_END
00101 }
00102 
00103 TAO(Tao2)
00104 {
00105         cout<<"[STR: Tao2]"<<endl;
00106         struct T{~T(){ cout<<"[END: Tao2]"<<endl; }} t;
00107     TAO_PLANS{
00108         Plan1,
00109         Plan2
00110     }
00111     TAO_START_PLAN(Plan2);
00112     TAO_BGN
00113     {
00114         TAO_PLAN( Plan1 ){
00115             TAO_START_CONDITION(true);
00116             TAO_CALL_TASK(testTask);
00117             TAO_ALLOCATE_EMPTY
00118             TAO_CLEANUP_BGN
00119             {
00120                 TAO_CALL_TASK(RRR);
00121             }
00122             TAO_CLEANUP_END
00123             TAO_STOP_CONDITION(event == TAO_EVENT(/FAIL));
00124             TAO_NEXT(NextFirstReady){
00125                 TAO_NEXT_PLAN(Plan2);
00126             }
00127         }
00128         TAO_PLAN( Plan2 ){
00129                 cout<<"[start Tao2/Plan2 "<< (justCondition?"condition check":"") <<"]"<<endl;
00130             TAO_START_CONDITION(true);
00131             TAO_CALL_TASK(testTask);
00132             TAO_ALLOCATE_EMPTY
00133             TAO_CLEANUP_BGN
00134                         {
00135                                 cout<<"[stop Tao2/Plan2]"<<endl;
00136                         }
00137                         TAO_CLEANUP_END
00138                         TAO_STOP_CONDITION(true);
00139             TAO_NEXT_EMPTY
00140         }
00141     }
00142     TAO_END
00143 }
00144 
00145 TAO(Tao3)
00146 {
00147         cout<<"[STR: Tao3]"<<endl;
00148         struct T{~T(){ cout<<"[END: Tao3]"<<endl; }} t;
00149     TAO_PLANS{
00150         Plan1,
00151         Plan2
00152     }
00153     TAO_START_PLAN(Plan1);
00154     TAO_BGN{
00155         TAO_PLAN( Plan1 ){
00156             TAO_START_CONDITION(true);
00157             TAO_CALL_TASK(testTask);
00158             TAO_CLEANUP_BGN
00159             {
00160                 TAO_CALL_TASK(testTask);
00161             }
00162             TAO_CLEANUP_END
00163 
00164             TAO_ALLOCATE(AllocFirstReady){
00165                 TAO_SUBPLAN(Tao2);
00166             }
00167 
00168             TAO_STOP_CONDITION(event == TAO_EVENT(/FAIL))
00169             TAO_NEXT(NextFirstReady){
00170                 TAO_NEXT_PLAN(Plan2);
00171             }
00172         }
00173         TAO_PLAN( Plan2 ){
00174             TAO_START_CONDITION(true);
00175             TAO_CALL_TASK(testTask);
00176             TAO_ALLOCATE_EMPTY
00177             TAO_STOP_CONDITION(true);
00178             TAO_NEXT_EMPTY
00179         }
00180     }
00181     TAO_END
00182 }
00183 
00184 decision_making::TaskResult testTask(string name, const FSMCallContext& context, EventQueue& eventQueue) {
00185         cout<<"[testTask from "<<context.str()<<"]"<<endl;
00186     sleep(1);
00187     return TaskResult::SUCCESS();
00188 }
00189 
00190 int main(int argc, char **argv) {
00191 
00192     ros::init(argc, argv, "tao_example");
00193 
00194     ROS_INFO("Starting...");
00195 
00196     ros_decision_making_init(argc, argv);
00197     ros::NodeHandle nodeHandle;
00198     RosEventQueue eventQueue;
00199 
00200     ros::AsyncSpinner spinner(1);
00201     spinner.start();
00202 
00203     LocalTasks::registrate("testTask", testTask);
00204 
00205     eventQueue.async_spin();
00206     ROS_INFO("Starting tao example...");
00207     TaoTao1(NULL, &eventQueue);
00208     eventQueue.close();
00209 
00210     ROS_INFO("Tao stopped");
00211         return 0;
00212 }


decision_making_examples
Author(s):
autogenerated on Wed Aug 26 2015 11:17:01