Go to the documentation of this file.00001
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
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051 package org.srs.srs_knowledge.task;
00052
00053 import java.io.*;
00054 import java.util.StringTokenizer;
00055
00056 import java.util.ArrayList;
00057 import ros.pkg.srs_knowledge.msg.*;
00058 import ros.pkg.geometry_msgs.msg.Pose2D;
00059 import org.srs.srs_knowledge.knowledge_engine.*;
00060 import org.srs.srs_knowledge.task.Task;
00061 import java.util.HashMap;
00062
00069 public abstract class HighLevelActionUnit {
00070 public abstract String getActionType();
00071 public static final int COMPLETED_SUCCESS = -10;
00072 public static final int COMPLETED_FAIL = -11;
00073 public static final int INVALID_INDEX = -100;
00074
00075 public int getNumOfActions() {
00076 return actionUnits.size();
00077 }
00078
00079 public int getCurrentCUActionIndex() {
00080
00081 return currentActionInd;
00082 }
00083
00084 public int getNextCUActionIndex(boolean statusLastStep) {
00085
00086 if(currentActionInd == -1) {
00087 return 0;
00088 }
00089
00090
00091 if ( currentActionInd >= 0 && currentActionInd < actionUnits.size() ) {
00092 if(statusLastStep) {
00093 return nextActionMapIfSuccess[currentActionInd];
00094 }
00095 else {
00096 return nextActionMapIfFail[currentActionInd];
00097 }
00098 }
00099 else {
00100 return INVALID_INDEX;
00101 }
00102 }
00103
00104 public CUAction getCUActionAt(int ind) {
00105
00106 currentActionInd = ind;
00107 if (ind < 0) {
00108 System.out.println("Invalid index " + ind);
00109 return null;
00110 }
00111
00112 CUAction ca = new CUAction();
00113
00114 if(ind == COMPLETED_FAIL) {
00115 GenericAction genericAction = new GenericAction();
00116
00117
00118 genericAction.jsonActionInfo = SRSJSONParser.encodeCustomAction("finish_fail", null);
00119 ca.generic = genericAction;
00120 ca.actionType = "generic";
00121
00122 ca.status = -1;
00123
00124 return ca;
00125 }
00126 else if (ind == COMPLETED_SUCCESS){
00127 GenericAction genericAction = new GenericAction();
00128
00129 genericAction.jsonActionInfo = SRSJSONParser.encodeCustomAction("finish_success", null);
00130
00131 ca.generic = genericAction;
00132 ca.actionType = "generic";
00133
00134 ca.status = 1;
00135
00136 return ca;
00137 }
00138 else if (ind == INVALID_INDEX) {
00139 GenericAction genericAction = new GenericAction();
00140
00141 genericAction.jsonActionInfo = SRSJSONParser.encodeCustomAction("no_action", null);
00142
00143 ca.generic = genericAction;
00144 ca.actionType = "generic";
00145
00146 ca.status = -1;
00147 return ca;
00148 }
00149
00150 GenericAction genericAction = new GenericAction();
00151 try {
00152 genericAction = actionUnits.get(ind);
00153 }
00154 catch(IndexOutOfBoundsException e) {
00155 return null;
00156 }
00157
00158 ca.generic = genericAction;
00159
00160 ca.actionType = "generic";
00161 return ca;
00162 }
00163
00164 public boolean addFeedback(String key, ActionFeedback fb) {
00165 if(fb == null) {
00166 return false;
00167 }
00168 feedbacks.put(key, fb);
00169 return true;
00170 }
00171
00172 public ActionFeedback getFeedback(String key) {
00173 return feedbacks.get(key);
00174 }
00175
00176
00177
00178 public abstract boolean ifParametersSet();
00179
00180 public boolean setParameters(String action, String para, String reservedParam) {
00181 return this.ifParametersSet;
00182 }
00183
00184 protected String actionType = "";
00185 protected ArrayList<GenericAction> actionUnits = new ArrayList<GenericAction>();
00186 protected int[] nextActionMapIfFail;
00187 protected int[] nextActionMapIfSuccess;
00188 protected HashMap<String, ActionFeedback> feedbacks;
00189
00190 protected int currentActionInd = -1;
00191 protected boolean ifParametersSet;
00192 }