interpreter.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 #
00033 # Author: Ioan Sucan
00034 
00035 import rospy
00036 from moveit_commander import RobotCommander, MoveGroupCommander, PlanningSceneInterface, MoveItCommanderException
00037 from geometry_msgs.msg import PoseStamped
00038 import re
00039 import time
00040 import os.path
00041 
00042 class MoveGroupInfoLevel:
00043     FAIL = 1
00044     WARN = 2
00045     SUCCESS = 3
00046     INFO = 4
00047     DEBUG = 5
00048 
00049 class MoveGroupCommandInterpreter(object):
00050     """
00051     Interpreter for simple commands
00052     """
00053 
00054     DEFAULT_FILENAME = "move_group.cfg"
00055     GO_DIRS = {"up" : (2,1), "down" : (2, -1), "z" : (2, 1),
00056                "left" : (1, 1), "right" : (1, -1), "y" : (1, 1),
00057                "forward" : (0, 1), "backward" : (0, -1), "back" : (0, -1), "x" : (0, 1) }
00058 
00059     def __init__(self):
00060         self._gdict = {}
00061         self._group_name = ""
00062         self._prev_group_name = ""
00063         self._planning_scene_interface = PlanningSceneInterface()
00064         self._robot = RobotCommander()
00065         self._last_plan = None
00066         self._db_host = None
00067         self._db_port = 33829
00068         self._trace = False
00069 
00070     def get_active_group(self):
00071         if len(self._group_name) > 0:
00072             return self._gdict[self._group_name]
00073         else:
00074             return None
00075 
00076     def get_loaded_groups(self):
00077         return self._gdict.keys()
00078 
00079     def execute(self, cmd):
00080         cmd = self.resolve_command_alias(cmd)
00081         result = self.execute_generic_command(cmd)
00082         if result != None:
00083             return result
00084         else:
00085             if len(self._group_name) > 0:
00086                 return self.execute_group_command(self._gdict[self._group_name], cmd)
00087             else:
00088                 return (MoveGroupInfoLevel.INFO, self.get_help() + "\n\nNo groups initialized yet. You must call the 'use' or the 'load' command first.\n")
00089 
00090     def execute_generic_command(self, cmd):
00091         if os.path.isfile("cmd/" + cmd):
00092             cmd = "load cmd/" + cmd
00093         cmdlow = cmd.lower()
00094         if cmdlow.startswith("use"):
00095             if cmdlow == "use":
00096                 return (MoveGroupInfoLevel.INFO, "\n".join(self.get_loaded_groups()))
00097             clist = cmd.split()
00098             clist[0] = clist[0].lower()
00099             if len(clist) == 2:
00100                 if clist[0] == "use":
00101                     if clist[1] == "previous":
00102                         clist[1] = self._prev_group_name
00103                         if len(clist[1]) == 0:
00104                             return (MoveGroupInfoLevel.DEBUG, "OK")
00105                     if self._gdict.has_key(clist[1]):
00106                         self._prev_group_name = self._group_name
00107                         self._group_name = clist[1]
00108                         return (MoveGroupInfoLevel.DEBUG, "OK")
00109                     else:
00110                         try:
00111                             mg = MoveGroupCommander(clist[1])
00112                             self._gdict[clist[1]] = mg
00113                             self._group_name = clist[1]
00114                             return (MoveGroupInfoLevel.DEBUG, "OK")
00115                         except MoveItCommanderException as e:
00116                             return (MoveGroupInfoLevel.FAIL, "Initializing " + clist[1] + ": " + str(e))
00117                         except:
00118                             return (MoveGroupInfoLevel.FAIL, "Unable to initialize " + clist[1])
00119         elif cmdlow.startswith("trace"):
00120             if cmdlow == "trace":
00121                 return (MoveGroupInfoLevel.INFO, "trace is on" if self._trace else "trace is off")
00122             clist = cmdlow.split()
00123             if clist[0] == "trace" and clist[1] == "on":
00124                 self._trace = True
00125                 return (MoveGroupInfoLevel.DEBUG, "OK")
00126             if clist[0] == "trace" and clist[1] == "off":
00127                 self._trace = False
00128                 return (MoveGroupInfoLevel.DEBUG, "OK")
00129         elif cmdlow.startswith("load"):
00130             filename = self.DEFAULT_FILENAME
00131             clist = cmd.split()
00132             if len(clist) > 2:
00133                 return (MoveGroupInfoLevel.WARN, "Unable to parse load command")
00134             if len(clist) == 2:
00135                 filename = clist[1]
00136                 if not os.path.isfile(filename):
00137                     filename = "cmd/" + filename
00138             line_num = 0
00139             line_content = ""
00140             try:
00141                 f = open(filename, 'r')
00142                 for line in f:
00143                     line_num += 1
00144                     line = line.rstrip()
00145                     line_content = line
00146                     if self._trace:
00147                         print ("%s:%d:  %s" % (filename, line_num, line_content))
00148                     comment = line.find("#")
00149                     if comment != -1:
00150                       line = line[0:comment].rstrip()
00151                     if line != "":
00152                       self.execute(line.rstrip())
00153                     line_content = ""
00154                 return (MoveGroupInfoLevel.DEBUG, "OK")
00155             except MoveItCommanderException as e:  
00156                 if line_num > 0:
00157                     return (MoveGroupInfoLevel.WARN, "Error at %s:%d:  %s\n%s" % (filename, line_num, line_content, str(e)))
00158                 else:
00159                     return (MoveGroupInfoLevel.WARN, "Processing " + filename + ": " + str(e))
00160             except:
00161                 if line_num > 0:
00162                     return (MoveGroupInfoLevel.WARN, "Error at %s:%d:  %s" % (filename, line_num, line_content))
00163                 else:
00164                     return (MoveGroupInfoLevel.WARN, "Unable to load " + filename)
00165         elif cmdlow.startswith("save"):
00166             filename = self.DEFAULT_FILENAME
00167             clist = cmd.split()
00168             if len(clist) > 2:
00169                 return (MoveGroupInfoLevel.WARN, "Unable to parse save command")
00170             if len(clist) == 2:
00171                 filename = clist[1]
00172             try:
00173                 f = open(filename, 'w')
00174                 for gr in self._gdict.keys():
00175                     f.write("use " + gr + "\n")
00176                     known = self._gdict[gr].get_remembered_joint_values()
00177                     for v in known.keys():
00178                         f.write(v + " = [" + " ".join([str(x) for x in known[v]]) + "]\n")
00179                 if self._db_host != None:
00180                     f.write("database " + self._db_host + " " + str(self._db_port) + "\n")
00181                 return (MoveGroupInfoLevel.DEBUG, "OK")
00182             except:
00183                 return (MoveGroupInfoLevel.WARN, "Unable to save " + filename)
00184         else:
00185             return None
00186 
00187     def execute_group_command(self, g, cmdorig):
00188         cmd = cmdorig.lower()
00189 
00190         if cmd == "stop":
00191             g.stop()
00192             return (MoveGroupInfoLevel.DEBUG, "OK")
00193 
00194         if cmd == "id":
00195             return (MoveGroupInfoLevel.INFO, g.get_name())
00196 
00197         if cmd == "help":
00198             return (MoveGroupInfoLevel.INFO, self.get_help())
00199 
00200         if cmd == "vars":
00201             known = g.get_remembered_joint_values()
00202             return (MoveGroupInfoLevel.INFO, "[" + " ".join(known.keys()) + "]")
00203 
00204         if cmd == "joints":
00205             joints = g.get_joints()
00206             return (MoveGroupInfoLevel.INFO, "\n" + "\n".join([str(i) + " = " + joints[i] for i in range(len(joints))]) + "\n")
00207 
00208         if cmd == "show":
00209             return self.command_show(g)
00210 
00211         if cmd == "current":
00212             return self.command_current(g)
00213 
00214         if cmd == "ground":
00215             pose = PoseStamped()
00216             pose.pose.position.x = 0
00217             pose.pose.position.y = 0
00218             # offset such that the box is 0.1 mm below ground (to prevent collision with the robot itself)
00219             pose.pose.position.z = -0.0501
00220             pose.pose.orientation.x = 0
00221             pose.pose.orientation.y = 0
00222             pose.pose.orientation.z = 0
00223             pose.pose.orientation.w = 1
00224             pose.header.stamp = rospy.get_rostime()
00225             pose.header.frame_id = self._robot.get_root_link()
00226             self._planning_scene_interface.attach_box(self._robot.get_root_link(), "ground", pose, (3, 3, 0.1))
00227             return (MoveGroupInfoLevel.INFO, "Added ground")
00228 
00229         if cmd == "eef":
00230             if len(g.get_end_effector_link()) > 0:
00231                 return (MoveGroupInfoLevel.INFO, g.get_end_effector_link())
00232             else:
00233                 return (MoveGroupInfoLevel.INFO, "There is no end effector defined")
00234 
00235         if cmd == "database":
00236             if self._db_host == None:
00237                 return (MoveGroupInfoLevel.INFO, "Not connected to a database")
00238             else:
00239                 return (MoveGroupInfoLevel.INFO, "Connected to " + self._db_host + ":" + str(self._db_port))
00240         if cmd == "plan":
00241             if self._last_plan != None:
00242                 return (MoveGroupInfoLevel.INFO, str(self._last_plan))
00243             else:
00244                 return (MoveGroupInfoLevel.INFO, "No previous plan")
00245 
00246         if cmd == "constrain":
00247             g.clear_path_constraints()
00248             return (MoveGroupInfoLevel.SUCCESS, "Cleared path constraints")
00249 
00250         if cmd == "tol" or cmd == "tolerance":
00251             return (MoveGroupInfoLevel.INFO, "Joint = %0.6g, Position = %0.6g, Orientation = %0.6g" % g.get_goal_tolerance())
00252 
00253         if cmd == "time":
00254             return (MoveGroupInfoLevel.INFO, str(g.get_planning_time()))
00255 
00256         if cmd == "execute":
00257             if self._last_plan != None:
00258                 if g.execute(self._last_plan):
00259                     return (MoveGroupInfoLevel.SUCCESS, "Plan submitted for execution")
00260                 else:
00261                     return (MoveGroupInfoLevel.WARN, "Failed to submit plan for execution")
00262             else:
00263                 return (MoveGroupInfoLevel.WARN, "No motion plan computed")
00264 
00265         # see if we have assignment between variables
00266         assign_match = re.match(r"^(\w+)\s*=\s*(\w+)$", cmd)
00267         if assign_match:
00268             known = g.get_remembered_joint_values()
00269             if known.has_key(assign_match.group(2)):
00270                 g.remember_joint_values(assign_match.group(1), known[assign_match.group(2)])
00271                 return (MoveGroupInfoLevel.SUCCESS, assign_match.group(1) + " is now the same as " + assign_match.group(2))
00272             else:
00273                 return (MoveGroupInfoLevel.WARN, "Unknown command: '" + cmd + "'")
00274         
00275         # see if we have assignment of matlab-like vector syntax
00276         set_match = re.match(r"^(\w+)\s*=\s*\[([\d\.e\-\+\s]+)\]$", cmd)
00277         if set_match:
00278             try:
00279                 g.remember_joint_values(set_match.group(1), [float(x) for x in set_match.group(2).split()])
00280                 return (MoveGroupInfoLevel.SUCCESS, "Remembered joint values [" + set_match.group(2) + "] under the name " + set_match.group(1))
00281             except:
00282                 return (MoveGroupInfoLevel.WARN, "Unable to parse joint value [" + set_match.group(2) + "]")
00283 
00284         # see if we have assignment of matlab-like element update
00285         component_match = re.match(r"^(\w+)\s*\[\s*(\d+)\s*\]\s*=\s*([\d\.e\-\+]+)$", cmd)
00286         if component_match:
00287             known = g.get_remembered_joint_values()
00288             if known.has_key(component_match.group(1)):
00289                 try:
00290                     val = known[component_match.group(1)]
00291                     val[int(component_match.group(2))] = float(component_match.group(3))
00292                     g.remember_joint_values(component_match.group(1), val)
00293                     return (MoveGroupInfoLevel.SUCCESS, "Updated " + component_match.group(1) + "[" + component_match.group(2) + "]")
00294                 except:
00295                     return (MoveGroupInfoLevel.WARN, "Unable to parse index or value in '" + cmd +"'")
00296             else:
00297                 return (MoveGroupInfoLevel.WARN, "Unknown command: '" + cmd + "'")
00298 
00299         clist = cmdorig.split()
00300         clist[0] = clist[0].lower()
00301 
00302         # if this is an unknown one-word command, it is probably a variable
00303         if len(clist) == 1:
00304             known = g.get_remembered_joint_values()
00305             if known.has_key(cmd):
00306                 return (MoveGroupInfoLevel.INFO, "[" + " ".join([str(x) for x in known[cmd]]) + "]")
00307             else:
00308                 return (MoveGroupInfoLevel.WARN, "Unknown command: '" + cmd + "'")
00309 
00310         # command with one argument
00311         if len(clist) == 2:
00312             if clist[0] == "go":
00313                 self._last_plan = None
00314                 if clist[1] == "rand" or clist[1] == "random":
00315                     vals = g.get_random_joint_values()
00316                     g.set_joint_value_target(vals)
00317                     if g.go():
00318                         return (MoveGroupInfoLevel.SUCCESS, "Moved to random target [" + " ".join([str(x) for x in vals]) + "]")
00319                     else:
00320                         return (MoveGroupInfoLevel.FAIL, "Failed while moving to random target [" + " ".join([str(x) for x in vals]) + "]")
00321                 else:
00322                     try:
00323                         g.set_named_target(clist[1])
00324                         if g.go():
00325                             return (MoveGroupInfoLevel.SUCCESS, "Moved to " + clist[1])
00326                         else:
00327                             return (MoveGroupInfoLevel.FAIL, "Failed while moving to " + clist[1])
00328                     except MoveItCommanderException as e:
00329                         return (MoveGroupInfoLevel.WARN, "Going to " + clist[1] + ": " + str(e))
00330                     except:
00331                         return (MoveGroupInfoLevel.WARN, clist[1] + " is unknown")
00332             if clist[0] == "plan":
00333                 self._last_plan = None
00334                 vals = None
00335                 if clist[1] == "rand" or clist[1] == "random":
00336                     vals = g.get_random_joint_values()
00337                     g.set_joint_value_target(vals)
00338                     self._last_plan = g.plan()
00339                 else:
00340                     try:
00341                         g.set_named_target(clist[1])
00342                         self._last_plan = g.plan()
00343                     except MoveItCommanderException as e:
00344                         return (MoveGroupInfoLevel.WARN, "Planning to " + clist[1] + ": " + str(e))
00345                     except:
00346                         return (MoveGroupInfoLevel.WARN, clist[1] + " is unknown")
00347                 if self._last_plan != None:
00348                     if len(self._last_plan.joint_trajectory.points) == 0 and len(self._last_plan.multi_dof_joint_trajectory.points) == 0:
00349                         self._last_plan = None
00350                 dest_str = clist[1]
00351                 if vals != None:
00352                     dest_str = "[" + " ".join([str(x) for x in vals]) + "]"
00353                 if self._last_plan != None:
00354                     return (MoveGroupInfoLevel.SUCCESS, "Planned to " + dest_str)
00355                 else:
00356                     return (MoveGroupInfoLevel.FAIL, "Failed while planning to " + dest_str)
00357             elif clist[0] == "pick":
00358                 self._last_plan = None
00359                 if g.pick(clist[1]):
00360                     return (MoveGroupInfoLevel.SUCCESS, "Picked object " + clist[1])
00361                 else:
00362                     return (MoveGroupInfoLevel.FAIL, "Failed while trying to pick object " + clist[1])
00363             elif clist[0] == "place":
00364                 self._last_plan = None
00365                 if g.place(clist[1]):
00366                     return (MoveGroupInfoLevel.SUCCESS, "Placed object " + clist[1])
00367                 else:
00368                     return (MoveGroupInfoLevel.FAIL, "Failed while trying to place object " + clist[1])
00369             elif clist[0] == "planner":
00370                 g.set_planner_id(clist[1])
00371                 return (MoveGroupInfoLevel.SUCCESS, "Planner is now " + clist[1])
00372             elif clist[0] == "record" or clist[0] == "rec":
00373                 g.remember_joint_values(clist[1])
00374                 return (MoveGroupInfoLevel.SUCCESS, "Remembered current joint values under the name " + clist[1])
00375             elif clist[0] == "rand" or clist[0] == "random":
00376                 g.remember_joint_values(clist[1], g.get_random_joint_values())
00377                 return (MoveGroupInfoLevel.SUCCESS, "Remembered random joint values under the name " + clist[1])
00378             elif clist[0] == "del" or clist[0] == "delete":
00379                 g.forget_joint_values(clist[1])    
00380                 return (MoveGroupInfoLevel.SUCCESS, "Forgot joint values under the name " + clist[1])
00381             elif clist[0] == "show":
00382                 known = g.get_remembered_joint_values()
00383                 if known.has_key(clist[1]):
00384                     return (MoveGroupInfoLevel.INFO, "[" + " ".join([str(x) for x in known[clist[1]]]) + "]")
00385                 else:
00386                     return (MoveGroupInfoLevel.WARN, "Joint values for " + clist[1] + " are not known")
00387             elif clist[0] == "tol" or clist[0] == "tolerance":
00388                 try:
00389                     g.set_goal_tolerance(float(clist[1]))
00390                     return (MoveGroupInfoLevel.SUCCESS, "OK")
00391                 except:
00392                     return (MoveGroupInfoLevel.WARN, "Unable to parse tolerance value '" + clist[1] + "'")
00393             elif clist[0] == "time":
00394                 try:
00395                     g.set_planning_time(float(clist[1]))
00396                     return (MoveGroupInfoLevel.SUCCESS, "OK")
00397                 except:
00398                     return (MoveGroupInfoLevel.WARN, "Unable to parse planning duration value '" + clist[1] + "'")
00399             elif clist[0] == "constrain":
00400                 try:
00401                     g.set_path_constraints(clist[1])
00402                     return (MoveGroupInfoLevel.SUCCESS, "OK")
00403                 except:
00404                     if self._db_host != None:
00405                         return (MoveGroupInfoLevel.WARN, "Constraint " + clist[1] + " is not known.")
00406                     else:
00407                         return (MoveGroupInfoLevel.WARN, "Not connected to a database.")
00408             elif clist[0] == "wait":
00409                 try:
00410                     time.sleep(float(clist[1]))
00411                     return (MoveGroupInfoLevel.SUCCESS, clist[1] + " seconds passed")
00412                 except:
00413                     return (MoveGroupInfoLevel.WARN, "Unable to wait '" + clist[1] + "' seconds")
00414             elif clist[0] == "database":
00415                 try:
00416                     g.set_constraints_database(clist[1], self._db_port)
00417                     self._db_host = clist[1]
00418                     return (MoveGroupInfoLevel.SUCCESS, "Connected to " + self._db_host + ":" + str(self._db_port))
00419                 except:
00420                     return (MoveGroupInfoLevel.WARN, "Unable to connect to '" + clist[1] + ":" + str(self._db_port) + "'")
00421             else:
00422                 return (MoveGroupInfoLevel.WARN, "Unknown command: '" + cmd + "'")
00423 
00424         if len(clist) == 3:
00425             if clist[0] == "go" and self.GO_DIRS.has_key(clist[1]):
00426                 self._last_plan = None
00427                 try:
00428                     offset = float(clist[2])
00429                     (axis, factor) = self.GO_DIRS[clist[1]]
00430                     return self.command_go_offset(g, offset, factor, axis, clist[1])
00431                 except MoveItCommanderException as e:
00432                     return (MoveGroupInfoLevel.WARN, "Going " + clist[1] + ": " + str(e))
00433                 except:
00434                     return (MoveGroupInfoLevel.WARN, "Unable to parse distance '" + clist[2] + "'")
00435             elif clist[0] == "allow" and (clist[1] == "look" or clist[1] == "looking"):
00436                 if clist[2] == "1" or clist[2] == "true" or clist[2] == "T" or clist[2] == "True":
00437                     g.allow_looking(True)
00438                 else:
00439                     g.allow_looking(False)
00440                 return (MoveGroupInfoLevel.DEBUG, "OK")
00441             elif clist[0] == "allow" and (clist[1] == "replan" or clist[1] == "replanning"):
00442                 if clist[2] == "1" or clist[2] == "true" or clist[2] == "T" or clist[2] == "True":
00443                     g.allow_replanning(True)
00444                 else:
00445                     g.allow_replanning(False)
00446                 return (MoveGroupInfoLevel.DEBUG, "OK")
00447             elif clist[0] == "database":
00448                 try:
00449                     g.set_constraints_database(clist[1], int(clist[2]))
00450                     self._db_host = clist[1]
00451                     self._db_port = int(clist[2])
00452                     return (MoveGroupInfoLevel.SUCCESS, "Connected to " + self._db_host + ":" + str(self._db_port))
00453                 except:
00454                     self._db_host = None
00455                     return (MoveGroupInfoLevel.WARN, "Unable to connect to '" + clist[1] + ":" + clist[2] + "'")
00456         if len(clist) == 4:
00457             if clist[0] == "rotate":
00458                 try:
00459                     g.set_rpy_target([float(x) for x in clist[1:]])
00460                     if g.go():
00461                         return (MoveGroupInfoLevel.SUCCESS, "Rotation complete")
00462                     else:
00463                         return (MoveGroupInfoLevel.FAIL, "Failed while rotating to " + " ".join(clist[1:]))
00464                 except MoveItCommanderException as e:
00465                     return (MoveGroupInfoLevel.WARN, str(e))
00466                 except:
00467                     return (MoveGroupInfoLevel.WARN, "Unable to parse X-Y-Z rotation  values '" + " ".join(clist[1:]) + "'")
00468 
00469         return (MoveGroupInfoLevel.WARN, "Unknown command: '" + cmd + "'")
00470 
00471     def command_show(self, g):
00472         known = g.get_remembered_joint_values()
00473         res = []
00474         for k in known.keys():
00475             res.append(k + " = [" + " ".join([str(x) for x in known[k]]) + "]")
00476         return (MoveGroupInfoLevel.INFO, "\n".join(res))
00477         
00478     def command_current(self, g):
00479         res = "joints = [" + " ".join([str(x) for x in g.get_current_joint_values()]) + "]"
00480         if len(g.get_end_effector_link()) > 0:
00481             res = res + "\n" + g.get_end_effector_link() + " pose = [\n" + str(g.get_current_pose()) + " ]"
00482             res = res + "\n" + g.get_end_effector_link() + " RPY = " + str(g.get_current_rpy())
00483         return (MoveGroupInfoLevel.INFO, res)
00484 
00485     def command_go_offset(self, g, offset, factor, dimension_index, direction_name):
00486         if g.has_end_effector_link():
00487             try:
00488                 g.shift_pose_target(dimension_index, factor * offset)
00489                 if g.go():
00490                     return (MoveGroupInfoLevel.SUCCESS, "Moved " + direction_name + " by " + str(offset) + " m")
00491                 else:
00492                     return (MoveGroupInfoLevel.FAIL, "Failed while moving " + direction_name)
00493             except MoveItCommanderException as e:
00494                 return (MoveGroupInfoLevel.WARN, str(e))
00495             except:
00496                 return (MoveGroupInfoLevel.WARN, "Unable to process pose update")
00497         else:
00498             return (MoveGroupInfoLevel.WARN, "No known end effector. Cannot move " + direction_name)
00499 
00500     def resolve_command_alias(self, cmdorig):
00501         cmd = cmdorig.lower()
00502         if cmd == "which":
00503             return "id"
00504         if cmd == "groups":
00505             return "use"
00506         return cmdorig
00507 
00508     def get_help(self):
00509         res = []
00510         res.append("Known commands:")
00511         res.append("  help                show this screen")
00512         res.append("  id|which            display the name of the group that is operated on")
00513         res.append("  load [<file>]       load a set of interpreted commands from a file")
00514         res.append("  save [<file>]       save the currently known variables as a set of commands")
00515         res.append("  use <name>          switch to using the group named <name> (and load it if necessary)")
00516         res.append("  use|groups          show the group names that are already loaded")
00517         res.append("  vars                display the names of the known states")
00518         res.append("  show                display the names and values of the known states")
00519         res.append("  show <name>         display the value of a state")
00520         res.append("  record <name>       record the current joint values under the name <name>")
00521         res.append("  delete <name>       forget the joint values under the name <name>")
00522         res.append("  current             show the current state of the active group")
00523         res.append("  constrain <name>    use the constraint <name> as a path constraint")
00524         res.append("  constrain           clear path constraints")
00525         res.append("  eef                 print the name of the end effector attached to the current group")
00526         res.append("  go <name>           plan and execute a motion to the state <name>")
00527         res.append("  go <dir> <dx>|      plan and execute a motion in direction up|down|left|right|forward|backward for distance <dx>")
00528         res.append("  go rand             plan and execute a motion to a random state")
00529         res.append("  plan <name>         plan a motion to the state <name>")
00530         res.append("  execute             execute a previously computed motion plan")
00531         res.append("  rotate <x> <y> <z>  plan and execute a motion to a specified orientation (about the X,Y,Z axes)")
00532         res.append("  tolerance           show the tolerance for reaching the goal region")
00533         res.append("  tolerance <val>     set the tolerance for reaching the goal region")
00534         res.append("  wait <dt>           sleep for <dt> seconds")
00535         res.append("  x = y               assign the value of y to x")
00536         res.append("  x[idx] = val        assign a value to dimension idx of x")
00537         res.append("  x = [v1 v2...]      assign a vector of values to x")
00538         res.append("  trace <on|off>      enable/disable replanning or looking around")
00539         res.append("  ground              add a ground plane to the planning scene")
00540         res.append("  allow replanning <true|false>    enable/disable replanning")
00541         res.append("  allow looking <true|false>       enable/disable looking around")
00542         return "\n".join(res)
00543 
00544     def get_keywords(self):
00545         known_vars = []
00546         known_constr = []
00547         if self.get_active_group() != None:
00548             known_vars = self.get_active_group().get_remembered_joint_values().keys()
00549             known_constr = self.get_active_group().get_known_constraints()
00550         groups = self._robot.get_group_names()
00551         return {'go':['up', 'down', 'left', 'right', 'backward', 'forward', 'random'] + known_vars,
00552                 'help':[],
00553                 'record':known_vars,
00554                 'show':known_vars,
00555                 'wait':[],
00556                 'delete':known_vars,
00557                 'database': [],
00558                 'current':[],
00559                 'use':groups,
00560                 'load':[],
00561                 'save':[],
00562                 'pick':[],
00563                 'place':[],
00564                 'plan':known_vars,
00565                 'allow':['replanning', 'looking'],
00566                 'constrain':known_constr,
00567                 'vars':[],
00568                 'joints':[],
00569                 'tolerance':[],
00570                 'time':[],
00571                 'eef':[],
00572                 'execute':[],
00573                 'ground':[],
00574                 'id':[]}


moveit_commander
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 02:24:45