$search
00001 /**************************************************************** 00002 * 00003 * Copyright (c) 2011, 2012 00004 * 00005 * School of Engineering, Cardiff University, UK 00006 * 00007 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00008 * 00009 * Project name: srs EU FP7 (www.srs-project.eu) 00010 * ROS stack name: srs 00011 * ROS package name: srs_knowledge 00012 * Description: 00013 * 00014 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00015 * 00016 * @author Ze Ji, email: jiz1@cf.ac.uk 00017 * 00018 * Date of creation: Oct 2011: 00019 * ToDo: 00020 * 00021 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00022 * 00023 * Redistribution and use in source and binary forms, with or without 00024 * modification, are permitted provided that the following conditions are met: 00025 * 00026 * * Redistributions of source code must retain the above copyright 00027 * notice, this list of conditions and the following disclaimer. 00028 * * Redistributions in binary form must reproduce the above copyright 00029 * notice, this list of conditions and the following disclaimer in the 00030 * documentation and/or other materials provided with the distribution. 00031 * * Neither the name of the school of Engineering, Cardiff University nor 00032 * the names of its contributors may be used to endorse or promote products 00033 * derived from this software without specific prior written permission. 00034 * 00035 * This program is free software: you can redistribute it and/or modify 00036 * it under the terms of the GNU Lesser General Public License LGPL as 00037 * published by the Free Software Foundation, either version 3 of the 00038 * License, or (at your option) any later version. 00039 * 00040 * This program is distributed in the hope that it will be useful, 00041 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00042 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00043 * GNU Lesser General Public License LGPL for more details. 00044 * 00045 * You should have received a copy of the GNU Lesser General Public 00046 * License LGPL along with this program. 00047 * If not, see <http://www.gnu.org/licenses/>. 00048 * 00049 ****************************************************************/ 00050 00051 package org.srs.srs_knowledge.task; 00052 00053 import java.io.*; 00054 import java.util.StringTokenizer; 00055 import java.util.ArrayList; 00056 import java.util.Iterator; 00057 import ros.pkg.srs_knowledge.msg.*; 00058 import ros.pkg.geometry_msgs.msg.Pose2D; 00059 import ros.pkg.geometry_msgs.msg.Pose; 00060 import org.srs.srs_knowledge.knowledge_engine.*; 00061 import com.hp.hpl.jena.rdf.model.*; 00062 import com.hp.hpl.jena.query.QueryExecutionFactory; 00063 import com.hp.hpl.jena.query.ResultSet; 00064 import com.hp.hpl.jena.query.QueryExecution; 00065 import com.hp.hpl.jena.query.QuerySolution; 00066 import com.hp.hpl.jena.ontology.Individual; 00067 import org.srs.srs_knowledge.task.*; 00068 00069 import ros.pkg.srs_symbolic_grounding.srv.*; 00070 //import ros.pkg.srs_symbolic_grounding.msg.*; 00071 00072 import ros.*; 00073 import ros.communication.*; 00074 00075 import org.json.simple.JSONArray; 00076 import org.json.simple.JSONObject; 00077 import org.json.simple.JSONValue; 00078 import org.json.simple.parser.ParseException; 00079 import org.json.simple.parser.JSONParser; 00080 00081 import org.srs.srs_knowledge.utils.*; 00082 import ros.pkg.srs_msgs.msg.SRSSpatialInfo; 00083 00084 public class SearchObjectTask extends org.srs.srs_knowledge.task.Task 00085 { 00086 //private GetObjectTask.GraspType graspType = GetObjectTask.GraspType.MOVE_AND_GRASP; 00087 public SearchObjectTask(String targetContent) 00088 { 00089 //this.nodeHandle = n; 00090 // this.userPose = userPose; 00091 // this.init(taskType, targetContent, userPose); 00092 //this.initTask(targetContent); 00093 00094 if (this.initTask(targetContent)) { 00095 System.out.println("Search Object Task constructed successfully -- " + targetContent); 00096 } 00097 else { 00098 System.out.println("Task not constructed successfully"); 00099 } 00100 } 00101 00102 /* 00103 public SearchObjectTask(String targetContent, GetObjectTask.GraspType graspMode) 00104 { 00105 this.graspType = graspMode; 00106 //this.nodeHandle = n; 00107 // this.userPose = userPose; 00108 // this.init(taskType, targetContent, userPose); 00109 this.initTask(targetContent); 00110 } 00111 */ 00112 00113 @Override 00114 protected boolean constructTask() { 00115 return createSearchObjectTask(); 00116 } 00117 00118 private boolean createSearchObjectTask() { 00119 /* 00120 // query for tables 00121 // move to tables (near -- use grounding) 00122 // detect milk 00123 */ 00124 System.out.println("Create New GET OBJECT Task --- "); 00125 00126 try { 00127 workspaces = OntoQueryUtil.getWorkspaceOfObject(this.targetContent, OntoQueryUtil.ObjectNameSpace, OntoQueryUtil.GlobalNameSpace, KnowledgeEngine.ontoDB); 00128 } 00129 catch(Exception e) { 00130 System.out.println(e.getMessage() + "\n" + e.toString()); 00131 return false; 00132 } 00133 00134 for(Individual u : workspaces) { 00135 System.out.println(u.getLocalName()); 00136 try{ 00137 //System.out.println("Created HLActionSeq "); 00138 HighLevelActionSequence subSeq = createSubSequenceForSingleWorkspace(u); 00139 allSubSeqs.add(subSeq); 00140 00141 } 00142 catch(RosException e) { 00143 System.out.println("ROSEXCEPTION -- when calling symbolic grounding for scanning positions. \t" + e.getMessage() + "\t" + e.toString()); 00144 00145 } 00146 catch(Exception e) { 00147 System.out.println(e.getMessage()); 00148 System.out.println(e.toString()); 00149 } 00150 } 00151 00152 if(allSubSeqs.size() > 0) { 00153 currentSubAction = 0; 00154 return true; 00155 } 00156 else { 00157 currentSubAction = -1; // no sub_highlevel_action in list 00158 return false; 00159 } 00160 } 00161 00162 00163 private HighLevelActionSequence createSubSequenceForSingleWorkspace(Individual workspace) throws RosException, Exception { 00164 HighLevelActionSequence actionList = new HighLevelActionSequence(); 00165 00166 // create MoveAndDetectionActionUnit 00167 //SRSFurnitureGeometry spatialInfo = new SRSFurnitureGeometry(); 00168 ros.pkg.srs_msgs.msg.SRSSpatialInfo spatialInfo = new ros.pkg.srs_msgs.msg.SRSSpatialInfo(); 00169 com.hp.hpl.jena.rdf.model.Statement stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "xCoord", workspace); 00170 00171 spatialInfo.pose.position.x = stm.getFloat(); 00172 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "yCoord", workspace); 00173 spatialInfo.pose.position.y = stm.getFloat(); 00174 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "zCoord", workspace); 00175 spatialInfo.pose.position.z = stm.getFloat(); 00176 00177 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "widthOfObject", workspace); 00178 spatialInfo.w = stm.getFloat(); 00179 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "heightOfObject", workspace); 00180 spatialInfo.h = stm.getFloat(); 00181 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "lengthOfObject", workspace); 00182 spatialInfo.l = stm.getFloat(); 00183 00184 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "qu", workspace); 00185 spatialInfo.pose.orientation.w = stm.getFloat(); 00186 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "qx", workspace); 00187 spatialInfo.pose.orientation.x = stm.getFloat(); 00188 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "qy", workspace); 00189 spatialInfo.pose.orientation.y = stm.getFloat(); 00190 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "qz", workspace); 00191 spatialInfo.pose.orientation.z = stm.getFloat(); 00192 00193 // call symbolic grounding service for target pose 00194 ArrayList<Pose2D> posList; 00195 try { 00196 posList = calculateScanPositions(spatialInfo); 00197 //System.out.println(posList.size()); 00198 } 00199 catch(RosException e) { 00200 System.out.println(e.toString()); 00201 System.out.println(e.getMessage()); 00202 throw e; 00203 } 00204 00205 Iterator<Individual> itInd = KnowledgeEngine.ontoDB.getInstancesOfClass(OntoQueryUtil.GlobalNameSpace + this.targetContent); 00206 int hhid = -1000; 00207 if(itInd.hasNext()) { 00208 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "houseHoldObjectID", (Individual)itInd.next()); 00209 hhid = OntoQueryUtil.getIntOfStatement(stm); 00210 } 00211 00212 // TODO: 00213 MoveAndDetectionActionUnit mdAction = new MoveAndDetectionActionUnit(posList, targetContent, hhid, workspace.asResource().getLocalName()); 00214 00215 // create MoveAndGraspActionUnit 00216 //MoveAndGraspActionUnit mgAction = new MoveAndGraspActionUnit(null, targetContent, hhid, "side", workspace.asResource().getLocalName()); 00217 00218 // create PutOnTrayActionUnit 00219 //PutOnTrayActionUnit trayAction = new PutOnTrayActionUnit("side"); 00220 00221 // FoldArmActionUnit 00222 //FoldArmActionUnit foldArmAction = new FoldArmActionUnit(); 00223 00224 // create BackToUserActionUnit 00225 00226 //Pose2D posUser = OntoQueryUtil.parsePose2D(userPose); 00227 //MoveActionUnit mau = new MoveActionUnit(posUser); 00228 00229 // create FinishActionUnit 00230 FinishActionUnit fau = new FinishActionUnit(true); 00231 //MoveActionUnit mau1 = new MoveActionUnit(OntoQueryUtil.parsePose2D("home")); 00232 //actionList.appendHighLevelAction(mau1); 00233 00234 actionList.appendHighLevelAction(mdAction); 00235 //actionList.appendHighLevelAction(mgAction); 00236 //actionList.appendHighLevelAction(trayAction); 00237 //actionList.appendHighLevelAction(foldArmAction); 00238 //actionList.appendHighLevelAction(mau); 00239 actionList.appendHighLevelAction(fau); 00240 00241 //System.out.println("ActionList size is " + actionList.getSizeOfHighLevelActionList()); 00242 00243 // set parameters for the workspace information 00244 actionList.setParameter("workspaceURI", workspace.asResource().getURI()); 00245 actionList.setParameter("workspace", workspace.asResource().getLocalName()); 00246 actionList.setParameter("workspaceNameSpace", workspace.asResource().getNameSpace()); 00247 00248 return actionList; 00249 } 00250 00251 private CUAction handleFailedMessage() { 00252 // 00253 updateTargetOfFailedAct(); 00254 00255 currentSubAction++; 00256 00257 //System.out.println("HANDLE FAILED MESSAGE.... CURRENTSUBACTION IS AT: " + currentSubAction); 00258 00259 if(currentSubAction >= allSubSeqs.size()) { 00260 return null; 00261 } 00262 HighLevelActionSequence nextHLActSeq = allSubSeqs.get(currentSubAction); 00263 00264 // if(nextHLActSeq.hasNextHighLevelActionUnit()) { 00265 HighLevelActionUnit nextHighActUnit = nextHLActSeq.getCurrentHighLevelActionUnit(); 00266 if(nextHighActUnit != null) { 00267 int tempI = nextHighActUnit.getNextCUActionIndex(true); 00268 // TODO: COULD BE DONE RECURSIVELY. BUT TOO COMPLEX UNNECESSARY AND DIFFICULT TO DEBUG. 00269 // SO STUPID CODE HERE 00270 00271 if(tempI == HighLevelActionUnit.COMPLETED_SUCCESS || tempI == HighLevelActionUnit.COMPLETED_FAIL || tempI == HighLevelActionUnit.INVALID_INDEX) { 00272 CUAction ca = new CUAction(); 00273 ca.status = -1; 00274 return ca; 00275 } 00276 else { 00277 //System.out.println("GET NEXT CU ACTION AT: " + tempI); 00278 CUAction ca = nextHighActUnit.getCUActionAt(tempI); 00279 if(ca == null) { 00280 System.out.println("CUACTION IS NULL......."); 00281 } 00282 return ca; 00283 } 00284 } 00285 00286 return null; 00287 } 00288 00289 private boolean updateDBObjectPose() { 00290 00291 return true; 00292 } 00293 00294 private ArrayList<Pose2D> calculateScanPositions(ros.pkg.srs_msgs.msg.SRSSpatialInfo furnitureInfo) throws RosException { 00295 ArrayList<Pose2D> posList = new ArrayList<Pose2D>(); 00296 ServiceClient<SymbolGroundingScanBasePose.Request, SymbolGroundingScanBasePose.Response, SymbolGroundingScanBasePose> sc = 00297 KnowledgeEngine.nodeHandle.serviceClient("symbol_grounding_scan_base_pose" , new SymbolGroundingScanBasePose(), false); 00298 00299 SymbolGroundingScanBasePose.Request rq = new SymbolGroundingScanBasePose.Request(); 00300 rq.parent_obj_geometry = furnitureInfo; 00301 00302 SymbolGroundingScanBasePose.Response res = sc.call(rq); 00303 posList = res.scan_base_pose_list; 00304 sc.shutdown(); 00305 return posList; 00306 } 00307 00308 private Pose2D calculateGraspPosition(ros.pkg.srs_msgs.msg.SRSSpatialInfo furnitureInfo, Pose targetPose) throws RosException { 00309 Pose2D pos = new Pose2D(); 00310 00311 ServiceClient<SymbolGroundingGraspBasePoseExperimental.Request, SymbolGroundingGraspBasePoseExperimental.Response, SymbolGroundingGraspBasePoseExperimental> sc = KnowledgeEngine.nodeHandle.serviceClient("symbol_grounding_grasp_base_pose_experimental" , new SymbolGroundingGraspBasePoseExperimental(), false); 00312 00313 SymbolGroundingGraspBasePoseExperimental.Request rq = new SymbolGroundingGraspBasePoseExperimental.Request(); 00314 rq.parent_obj_geometry = furnitureInfo; 00315 rq.target_obj_pose = targetPose; 00316 00317 SymbolGroundingGraspBasePoseExperimental.Response res = sc.call(rq); 00318 boolean obstacleCheck = res.obstacle_check; 00319 double reach = res.reach; 00320 pos = res.grasp_base_pose; 00321 00322 sc.shutdown(); 00323 if(obstacleCheck) { 00324 return null; 00325 } 00326 return pos; 00327 } 00328 00329 private ros.pkg.srs_msgs.msg.SRSSpatialInfo getFurnitureGeometryOf(Individual workspace) { 00330 //SRSFurnitureGeometry spatialInfo = new SRSFurnitureGeometry(); 00331 ros.pkg.srs_msgs.msg.SRSSpatialInfo spatialInfo = new ros.pkg.srs_msgs.msg.SRSSpatialInfo(); 00332 com.hp.hpl.jena.rdf.model.Statement stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "xCoord", workspace); 00333 spatialInfo.pose.position.x = stm.getFloat(); 00334 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "yCoord", workspace); 00335 spatialInfo.pose.position.y = stm.getFloat(); 00336 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "zCoord", workspace); 00337 spatialInfo.pose.position.z = stm.getFloat(); 00338 00339 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "widthOfObject", workspace); 00340 spatialInfo.w = stm.getFloat(); 00341 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "heightOfObject", workspace); 00342 spatialInfo.h = stm.getFloat(); 00343 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "lengthOfObject", workspace); 00344 spatialInfo.l = stm.getFloat(); 00345 00346 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "qu", workspace); 00347 spatialInfo.pose.orientation.w = stm.getFloat(); 00348 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "qx", workspace); 00349 spatialInfo.pose.orientation.x = stm.getFloat(); 00350 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "qy", workspace); 00351 spatialInfo.pose.orientation.y = stm.getFloat(); 00352 stm = KnowledgeEngine.ontoDB.getPropertyOf(OntoQueryUtil.GlobalNameSpace, "qz", workspace); 00353 spatialInfo.pose.orientation.z = stm.getFloat(); 00354 return spatialInfo; 00355 } 00356 00357 private boolean initTask(String targetContent) { 00358 acts = new ArrayList<ActionTuple>(); 00359 00360 setTaskTarget(targetContent); 00361 System.out.println("TASK.JAVA: Created CurrentTask " + "get " 00362 + targetContent); 00363 return constructTask(); 00364 } 00365 00366 @Override 00367 public boolean replan(OntologyDB onto, OntoQueryUtil ontoQuery) { 00368 return false; 00369 } 00370 00371 @Override 00372 public boolean isEmpty() { 00373 try { 00374 if(allSubSeqs.size() == 0) { 00375 return true; 00376 } 00377 } 00378 catch(NullPointerException e) { 00379 System.out.println(e.getMessage() + "\n" + e.toString()); 00380 return true; 00381 } 00382 return false; 00383 } 00384 00385 private void updateTargetOfFailedAct() { 00386 HighLevelActionSequence currentHLActSeq = allSubSeqs.get(currentSubAction); 00387 HighLevelActionUnit currentActUnit = currentHLActSeq.getCurrentHighLevelActionUnit(); 00388 if(currentActUnit.getActionType().equals("MoveAndDetection")) { 00389 //this.recentDetectedObject = ActionFeedback.toPose(fb); 00390 00391 // update the knowledge (post-processing) 00392 String currentWorkSpace = (String)currentHLActSeq.getParameter("workspaceURI"); 00393 String mapNameSpace = OntoQueryUtil.ObjectNameSpace; 00394 String prefix = "PREFIX srs: <http://www.srs-project.eu/ontologies/srs.owl#>\n" 00395 + "PREFIX rdf: <http://www.w3.org/1999/02/22-rdf-syntax-ns#>\n" 00396 + "PREFIX mapNamespacePrefix: <" + mapNameSpace + ">\n"; 00397 String queryString = "SELECT DISTINCT ?obj WHERE { \n" 00398 + "?obj srs:spatiallyRelated <" + currentWorkSpace + "> . \n" 00399 + " ?obj a srs:" + this.targetContent + " . \n" 00400 + "}"; 00401 // + " <" + currentWorkSpace + "> a srs:FurniturePiece . \n" 00402 00403 ArrayList<QuerySolution> rset = KnowledgeEngine.ontoDB.executeQueryRaw(prefix + queryString); 00404 if(rset.size() == 0) { 00405 System.out.println("<<<< NO OBJECT INSTANCE FOUND >>>"); 00406 } 00407 else { 00408 //System.out.println("<<<< FOUND OBJECT INSTANCES ON WORKSPACE " + this.targetContent + " >>>"); 00409 //Individual targetInd = KnowledgeEngine.ontoDB.getIndividual(target); 00410 //Iterator targetIt = KnowledgeEngine.ontoDB.getInstancesOfClass(OntoQueryUtil.GlobalNameSpace + this.targetContent); 00411 for (QuerySolution qs : rset) { 00412 String temp = qs.get("obj").toString(); 00413 //System.out.println("<<<<< " + temp + " >>>>>"); 00414 00415 //System.out.println( temp.getNameSpace() + " " + temp.getLocalName()); 00416 OntoQueryUtil.removeAllSubPropertiesOf(temp, OntoQueryUtil.GlobalNameSpace + "spatiallyRelated"); 00417 Pose tmpPose = new Pose(); 00418 tmpPose.position.x = -1000; 00419 tmpPose.position.y = -1000; 00420 tmpPose.position.z = -1000; 00421 tmpPose.orientation.x = -1000; 00422 tmpPose.orientation.y = -1000; 00423 tmpPose.orientation.z = -1000; 00424 tmpPose.orientation.w = -1000; 00425 00426 // update its pose 00427 try{ 00428 OntoQueryUtil.updatePoseOfObject(tmpPose, OntoQueryUtil.GlobalNameSpace, temp.trim()); 00429 OntoQueryUtil.computeOnSpatialRelation(); 00430 } 00431 catch(Exception e) { 00432 System.out.println(e.getMessage()); 00433 } 00434 00435 } 00436 } 00437 } 00438 else if(currentActUnit.getActionType().equals("MoveAndGrasp")) { 00439 // do nothing 00440 } 00441 else if(currentActUnit.getActionType().equals("PutOnTray")) { 00442 // do nothing 00443 } 00444 } 00445 00449 // TODO: NOT COMPLETED... 00450 @Override 00451 public CUAction getNextCUActionNew(boolean stateLastAction, String jsonFeedback) { 00452 System.out.println("===> Get Next CUACTION -- from GetObjectTask.java"); 00453 CUAction ca = new CUAction(); 00454 if(allSubSeqs.size() == 0 ) { 00455 System.out.println("Sequence size is zero"); 00456 return null; // ??? 00457 } 00458 if(currentSubAction >= 0 && currentSubAction < allSubSeqs.size()) { 00459 // get the current SubActionSequence item 00460 System.out.println("Sequence size is " + allSubSeqs.size()); 00461 HighLevelActionSequence subActSeq = allSubSeqs.get(currentSubAction); 00462 00463 HighLevelActionUnit highAct = subActSeq.getCurrentHighLevelActionUnit(); 00464 // decide if the current SubActionSequence is finished or stuck somewhere? 00465 // if successfully finished, then finished 00466 // if stuck (fail), move to the next subActionSequence 00467 if(highAct != null) { 00468 00469 // TODO: 00470 updateDBObjectPose(); 00471 00472 int ni = highAct.getNextCUActionIndex(stateLastAction); 00473 switch(ni) { 00474 case HighLevelActionUnit.COMPLETED_SUCCESS: 00475 System.out.println("COMPLETED_SUCCESS"); 00476 lastStepActUnit = highAct; 00477 00478 CUAction retact = null; 00479 try { 00480 retact = handleSuccessMessageNew(new ActionFeedback(jsonFeedback)); 00481 } 00482 catch(ParseException pe) { 00483 System.out.println(pe.toString()); 00484 return null; 00485 } 00486 00487 return retact; 00488 case HighLevelActionUnit.COMPLETED_FAIL: 00489 // The whole task finished (failure). 00490 lastStepActUnit = null; 00491 System.out.println("COMPLETED_FAIL"); 00492 return handleFailedMessage(); 00493 case HighLevelActionUnit.INVALID_INDEX: 00494 // The whole task finished failure. Should move to a HighLevelActionUnit in subActSeq of finsihing 00495 lastStepActUnit = null; 00496 System.out.println("INVALID_INDEX"); 00497 //currentSubAction++; 00498 return handleFailedMessage(); 00499 default: 00500 System.out.println(highAct.getActionType()); 00501 if(!highAct.ifParametersSet()) { 00502 System.out.println("Parameters not set"); 00503 lastStepActUnit = null; 00504 return handleFailedMessage(); 00505 } 00506 ca = highAct.getCUActionAt(ni); 00507 // since it is going to use String list to represent action info. So cation type is always assumed to be generic, hence the first item in the list actionInfo should contain the action type information... 00508 // WARNING: No error checking here 00509 //lastActionType = ca.generic.actionInfo.get(0); 00510 lastActionType = (String)(SRSJSONParser.decodeJsonActionInfo(ca.generic.jsonActionInfo).get("action")); 00511 00512 return ca; 00513 } 00514 } 00515 else { 00516 return null; 00517 } 00518 // or if still pending CUAction is available, return CUAction 00519 } 00520 else if (currentSubAction == -1) { 00521 } 00522 00523 return ca; 00524 } 00525 00529 private void updateTargetOfSucceededActNew(ActionFeedback fb) { 00530 HighLevelActionSequence currentHLActSeq = allSubSeqs.get(currentSubAction); 00531 HighLevelActionUnit currentActUnit = currentHLActSeq.getCurrentHighLevelActionUnit(); 00532 if(currentActUnit.getActionType().equals("MoveAndDetection")) { 00533 //this.recentDetectedObject = ActionFeedback.toPose(fb); 00534 this.recentDetectedObject = fb.getDetectedObjectPose(); 00535 BoundingBoxDim bbDim = InformationRetrieval.retrieveBoundingBoxInfo(OntoQueryUtil.GlobalNameSpace + this.targetContent); 00536 ros.pkg.srs_msgs.msg.SRSSpatialInfo spaObj = new ros.pkg.srs_msgs.msg.SRSSpatialInfo(); 00537 spaObj.l = bbDim.l; 00538 spaObj.h = bbDim.h; 00539 spaObj.w = bbDim.w; 00540 00541 spaObj.pose = this.recentDetectedObject; 00542 00543 // update the knowledge (post-processing) 00544 00545 // if there exists one same object on the same workspace, update it --- simple solution 00546 //String ws = SpatialCalculator.workspaceHolding(spaObj); 00547 00548 String neighbour = SpatialCalculator.nearestObject(spaObj.pose, OntoQueryUtil.GlobalNameSpace + this.targetContent); 00549 if(!neighbour.trim().equals("")) { 00550 //System.out.println("Found neighbour of " + neighbour); 00551 // update its pose 00552 try{ 00553 OntoQueryUtil.updatePoseOfObject(spaObj.pose, OntoQueryUtil.GlobalNameSpace, neighbour.trim()); 00554 OntoQueryUtil.computeOnSpatialRelation(); 00555 } 00556 catch(Exception e) { 00557 System.out.println(e.getMessage()); 00558 } 00559 } 00560 00561 // if there does not exist such an object, then insert a new one 00562 // bounding box can be obtained from HHDB 00563 // TODO 00564 00565 } 00566 else if(currentActUnit.getActionType().equals("MoveAndGrasp")) { 00567 // look for the object at the pose 00568 // update its relationship with the Robot, and remove its pose information 00569 // Individual rob = KnowledgeEngine.ontoDB.getIndividual(OntoQueryUtil.ObjectNameSpace + OntoQueryUtil.RobotName); 00570 String mapNameSpace = OntoQueryUtil.ObjectNameSpace; 00571 String prefix = "PREFIX srs: <http://www.srs-project.eu/ontologies/srs.owl#>\n" 00572 + "PREFIX rdf: <http://www.w3.org/1999/02/22-rdf-syntax-ns#>\n" 00573 + "PREFIX mapNamespacePrefix: <" + mapNameSpace + ">\n"; 00574 String queryString = "SELECT DISTINCT ?gripper WHERE { " 00575 + "<" + mapNameSpace + OntoQueryUtil.RobotName + ">" 00576 + " srs:hasPart ?gripper . " 00577 + " ?gripper a srs:RobotGripper . " 00578 + "}"; 00579 00580 try { 00581 String targetObj = SpatialCalculator.nearestObject(this.recentDetectedObject, OntoQueryUtil.GlobalNameSpace + this.targetContent); 00582 //System.out.println("TARGET OBJECT IS ::: " + targetObj); 00583 if(!targetObj.trim().equals("")) { 00584 00585 Pose tmpPose = new Pose(); 00586 tmpPose.position.x = -1000; 00587 tmpPose.position.y = -1000; 00588 tmpPose.position.z = -1000; 00589 tmpPose.orientation.x = -1000; 00590 tmpPose.orientation.y = -1000; 00591 tmpPose.orientation.z = -1000; 00592 tmpPose.orientation.w = -1000; 00593 00594 // update its pose 00595 try{ 00596 OntoQueryUtil.updatePoseOfObject(tmpPose, OntoQueryUtil.GlobalNameSpace, targetObj.trim()); 00597 OntoQueryUtil.computeOnSpatialRelation(); 00598 } 00599 catch(Exception e) { 00600 System.out.println(e.getMessage()); 00601 } 00602 } 00603 00604 00605 // OntoQueryUtil.updatePoseOfObject(tmpPose, OntoQueryUtil.GlobalNameSpace, OntoQueryUtil.ObjectNameSpace, this.targetContent); 00606 ArrayList<QuerySolution> rset = KnowledgeEngine.ontoDB.executeQueryRaw(prefix + queryString); 00607 if(rset.size() == 0) { 00608 //System.out.println("<<<< NO GRIPPER INSTANCE FOUND >>>"); 00609 } 00610 else { 00611 //System.out.println("<<<< FOUND GRIPPER INSTANCE >>>"); 00612 Individual targetInd = KnowledgeEngine.ontoDB.getIndividual(targetObj); 00613 00614 OntoQueryUtil.removeAllSubPropertiesOf(targetObj, OntoQueryUtil.GlobalNameSpace + "spatiallyRelated"); 00615 QuerySolution qs = rset.get(0); 00616 00617 String gripper = qs.get("gripper").toString(); 00618 //System.out.println("<<<<< " + gripper + " >>>>>"); 00619 00620 Individual gripInd = KnowledgeEngine.ontoDB.getIndividual(gripper); 00621 Property proExist = KnowledgeEngine.ontoDB.getProperty(OntoQueryUtil.GlobalNameSpace + "spatiallyRelated"); 00622 00623 Property pro = KnowledgeEngine.ontoDB.getProperty(OntoQueryUtil.GlobalNameSpace + "grippedBy"); 00624 00625 targetInd.setPropertyValue(pro, gripInd); 00626 } 00627 } 00628 catch (Exception e) { 00629 //System.out.println(" ================== " + e.getMessage() + " " + e.toString()); 00630 } 00631 } 00632 else if(currentActUnit.getActionType().equals("PutOnTray")) { 00633 // look for the object at the pose 00634 00635 // update its relationship with the Robot, and remove its pose information 00636 String mapNameSpace = OntoQueryUtil.ObjectNameSpace; 00637 String prefix = "PREFIX srs: <http://www.srs-project.eu/ontologies/srs.owl#>\n" 00638 + "PREFIX rdf: <http://www.w3.org/1999/02/22-rdf-syntax-ns#>\n" 00639 + "PREFIX mapNamespacePrefix: <" + mapNameSpace + ">\n"; 00640 String queryString = "SELECT DISTINCT ?tray WHERE { " 00641 + "<" + mapNameSpace + OntoQueryUtil.RobotName + ">" 00642 + " srs:hasPart ?tray . " 00643 + " ?tray a srs:COBTray . " 00644 + "}"; 00645 00646 try { 00647 String targetObj = SpatialCalculator.nearestObject(this.recentDetectedObject, OntoQueryUtil.GlobalNameSpace + this.targetContent); 00648 // System.out.println("TARGET OBJECT IS ::: " + targetObj); 00649 if(!targetObj.trim().equals("")) { 00650 00651 Pose tmpPose = new Pose(); 00652 tmpPose.position.x = -1000; 00653 tmpPose.position.y = -1000; 00654 tmpPose.position.z = -1000; 00655 tmpPose.orientation.x = -1000; 00656 tmpPose.orientation.y = -1000; 00657 tmpPose.orientation.z = -1000; 00658 tmpPose.orientation.w = -1000; 00659 00660 // update its pose 00661 try{ 00662 OntoQueryUtil.updatePoseOfObject(tmpPose, OntoQueryUtil.GlobalNameSpace, targetObj.trim()); 00663 OntoQueryUtil.computeOnSpatialRelation(); 00664 } 00665 catch(Exception e) { 00666 //System.out.println(e.getMessage()); 00667 } 00668 } 00669 00670 00671 // OntoQueryUtil.updatePoseOfObject(tmpPose, OntoQueryUtil.GlobalNameSpace, OntoQueryUtil.ObjectNameSpace, this.targetContent); 00672 ArrayList<QuerySolution> rset = KnowledgeEngine.ontoDB.executeQueryRaw(prefix + queryString); 00673 if(rset.size() == 0) { 00674 //System.out.println("<<<< NO TRAY INSTANCE FOUND >>>"); 00675 } 00676 else { 00677 //System.out.println("<<<< FOUND TRAY INSTANCE >>>"); 00678 Individual targetInd = KnowledgeEngine.ontoDB.getIndividual(targetObj); 00679 00680 OntoQueryUtil.removeAllSubPropertiesOf(targetObj, OntoQueryUtil.GlobalNameSpace + "spatiallyRelated"); 00681 QuerySolution qs = rset.get(0); 00682 00683 String gripper = qs.get("tray").toString(); 00684 //System.out.println("<<<<< " + gripper + " >>>>>"); 00685 00686 Individual gripInd = KnowledgeEngine.ontoDB.getIndividual(gripper); 00687 Property proExist = KnowledgeEngine.ontoDB.getProperty(OntoQueryUtil.GlobalNameSpace + "spatiallyRelated"); 00688 00689 Property pro = KnowledgeEngine.ontoDB.getProperty(OntoQueryUtil.GlobalNameSpace + "aboveOf"); 00690 00691 targetInd.setPropertyValue(pro, gripInd); 00692 } 00693 } 00694 catch (Exception e) { 00695 System.out.println(" ================== " + e.getMessage() + " ---- " + e.toString()); 00696 } 00697 00698 } 00699 } 00700 00701 private CUAction handleSuccessMessageNew(ActionFeedback fb) { 00702 // TODO: 00703 updateTargetOfSucceededActNew(fb); 00704 00705 HighLevelActionSequence currentHLActSeq = allSubSeqs.get(currentSubAction); 00706 00707 if(currentHLActSeq.hasNextHighLevelActionUnit()) { 00708 HighLevelActionUnit nextHighActUnit = currentHLActSeq.getNextHighLevelActionUnit(); 00709 // set feedback? 00710 if(nextHighActUnit.getActionType().equals("MoveAndGrasp") && !nextHighActUnit.ifParametersSet()) { 00711 00712 Pose2D posBase = calculateGraspPosFromFBNew(fb); 00713 if(posBase == null) { 00714 return handleFailedMessage(); 00715 } 00716 00717 String jsonMove = SRSJSONParser.encodeMoveAction("move", posBase.x, posBase.y, posBase.theta); 00718 if(!nextHighActUnit.setParameters("move", jsonMove, "")) { 00719 //currentSubAction++; 00720 return handleFailedMessage(); 00721 } 00722 /* 00723 ArrayList<String> basePos = constructArrayFromPose2D(posBase); 00724 if(!nextHighActUnit.setParameters(basePos)) { 00725 //currentSubAction++; 00726 return handleFailedMessage(); 00727 } 00728 */ 00729 } 00730 00731 if(nextHighActUnit != null) { 00732 int tempI = nextHighActUnit.getNextCUActionIndex(true); 00733 // TODO: COULD BE DONE RECURSIVELY. BUT TOO COMPLEX UNNECESSARY AND DIFFICULT TO DEBUG. 00734 // SO STUPID CODE HERE 00735 00736 if(tempI == HighLevelActionUnit.COMPLETED_SUCCESS) { 00737 CUAction ca = new CUAction(); 00738 ca.status = 1; 00739 return ca; 00740 } 00741 else if(tempI == HighLevelActionUnit.COMPLETED_FAIL || tempI == HighLevelActionUnit.INVALID_INDEX) { 00742 CUAction ca = new CUAction(); 00743 ca.status = -1; 00744 return ca; 00745 } 00746 else { 00747 return nextHighActUnit.getCUActionAt(tempI); 00748 } 00749 } 00750 } 00751 return null; 00752 } 00753 00754 private Pose2D calculateGraspPosFromFBNew(ActionFeedback fb) { 00755 //calculateGraspPosition(SRSFurnitureGeometry furnitureInfo, Pose targetPose) 00756 // call symbol grounding to get parameters for the MoveAndGrasp action 00757 try { 00758 //SRSFurnitureGeometry furGeo = getFurnitureGeometryOf(workspaces.get(currentSubAction)); 00759 ros.pkg.srs_msgs.msg.SRSSpatialInfo furGeo = getFurnitureGeometryOf(workspaces.get(currentSubAction)); 00760 //ros.pkg.srs_symbolic_grounding.msg.SRSSpatialInfo furGeo = newGetFurnitureGeometryOf(workspaces.get(currentSubAction)); 00761 // TODO: recentDetectedObject should be updated accordingly when the MoveAndDetection action finished successfully 00762 //recentDetectedObject = ActionFeedback.toPose(fb); 00763 recentDetectedObject = fb.getDetectedObjectPose(); 00764 if(recentDetectedObject == null) { 00765 return null; 00766 } 00767 00768 Pose2D pos = calculateGraspPosition(furGeo, recentDetectedObject); 00769 //Pose2D pos = newCalculateGraspPosition(furGeo, recentDetectedObject); 00770 return pos; 00771 } 00772 catch (Exception e) { 00773 System.out.println(e.getMessage() + " ++ " + e.toString()); 00774 return null; 00775 } 00776 00777 } 00778 00779 00780 private ArrayList<Individual> workspaces = new ArrayList<Individual>(); 00781 private int currentSubAction; 00782 private Pose recentDetectedObject; // required by MoveAndGraspActionUnit 00783 private String lastActionType; // used to handle feedback from last action executed 00784 //private String userPose; 00785 private HighLevelActionUnit lastStepActUnit; 00786 }