robot.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2013, 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 from moveit_commander import MoveGroupCommander, MoveItCommanderException
00036 from moveit_ros_planning_interface import _moveit_robot_interface
00037 import conversions
00038 
00039 class RobotCommander(object):
00040 
00041     class Joint(object):
00042         def __init__(self, robot, name):
00043             self._robot = robot
00044             self._name = name
00045         def name(self):
00046             return self._name
00047         def variable_count(self):
00048             return len(self.__get_joint_limits())
00049         def bounds(self):
00050             l = self.__get_joint_limits()
00051             if len(l) == 1:
00052                 return l[0]
00053             else:
00054                 return l
00055         def min_bound(self):
00056             limits = self.__get_joint_limits()
00057             if len(limits) == 1:
00058                 return limits[0][0]
00059             else:
00060                 return [l[0] for l in limits]
00061         def max_bound(self):
00062             limits = self.__get_joint_limits()
00063             if len(limits) == 1:
00064                 return limits[0][1]
00065             else:
00066                 return [l[1] for l in limits]
00067         def value(self):
00068             vals = self._robot._r.get_current_joint_values(self._name)
00069             if len(vals) == 1:
00070                 return vals[0]
00071             else:
00072                 return vals
00073         def move(self, position, wait = True):
00074             group = self._robot.get_default_owner_group()
00075             if group is None:
00076                 raise MoveItCommanderException("There is no known group containing joint %s. Cannot move." % self._name)
00077             gc = self._robot.get_group(group)
00078             if gc is not None:
00079                 gc.set_joint_value_target(gc.get_current_joint_values())
00080                 gc.set_joint_value_target(self._name, position)
00081                 return gc.go(wait)
00082             return False
00083         def __get_joint_limits(self):
00084             return self._robot._r.get_joint_limits(self._name)
00085 
00086     class Link(object):
00087         def __init__(self, robot, name):
00088             self._robot = robot
00089             self._name = name
00090         def name(self):
00091             return self._name
00092         def pose(self):
00093             return conversions.list_to_pose_stamped(self._robot._r.get_link_pose(self._name), self._robot.get_planning_frame())
00094 
00095     def __init__(self):
00096         self._r = _moveit_robot_interface.RobotInterface("robot_description")
00097         self._groups = {}
00098         self._joint_owner_group = {}
00099 
00100     def get_planning_frame(self):
00101         """Get the frame of reference in which planning is done (and environment is maintained)"""
00102         return self._r.get_planning_frame()
00103 
00104     def get_root_link(self):
00105         """Get the name of the root link of the robot model """
00106         return self._r.get_robot_root_link()
00107 
00108     def get_joint_names(self, group = None):
00109         """Get the names of all the movable joints that make up a group (mimic joints and fixed joints are excluded). If no group name is specified, all joints in the robot model are returned, including fixed and mimic joints """
00110         if group is not None:
00111             if self.has_group(group):
00112                 return self._r.get_group_joint_names(group)
00113             else:
00114                 raise MoveItCommanderException("There is no group named %s" % group)
00115         else:
00116             return self._r.get_joint_names()
00117 
00118     def get_link_names(self, group = None):
00119         """Get the links that make up a group. If no group name is specified, all the links in the robot model are returned. """
00120         if group is not None:
00121             if self.has_group(group):
00122                 return self._r.get_group_link_names(group)
00123             else:
00124                 raise MoveItCommanderException("There is no group named %s" % group)
00125         else:
00126             return self._r.get_link_names()
00127 
00128     def get_group_names(self):
00129         """Get the names of the groups defined for the robot"""
00130         return self._r.get_group_names()
00131 
00132     def get_current_variable_values(self):
00133         """Get a dictionary mapping variable names to values. Note that a joint may consist of one or more variables """
00134         return self._r.get_current_variable_values()
00135 
00136     def get_joint(self, name):
00137         if name in self.get_joint_names():
00138             return self.Joint(self, name)
00139         else:
00140             raise MoveItCommanderException("There is no joint named %s" % name)
00141 
00142     def get_link(self, name):
00143         if name in self.get_link_names():
00144             return self.Link(self, name)
00145         else:
00146             raise MoveItCommanderException("There is no link named %s" % name)
00147 
00148     def get_group(self, name):
00149         if not self._groups.has_key(name): 
00150             if not self.has_group(name):
00151                 raise MoveItCommanderException("There is no group named %s" % name)
00152             self._groups[name] = MoveGroupCommander(name)
00153         return self._groups[name]
00154 
00155     def has_group(self, name):
00156         return self._r.has_group(name)
00157 
00158     def get_default_owner_group(self, joint_name):
00159         """Get the name of the smallest group (fewest joints) that includes the joint name specified as argument"""
00160         if not self._joint_owner_groups.has_key(joint_name):
00161             group = None
00162             for g in self.get_group_names():
00163                 if joint_name in self.get_joint_names(g):
00164                     if group is None:
00165                         group = g
00166                     else:
00167                         if len(self.get_link_names(g)) < len(self.get_link_names(group)):
00168                             group = g
00169             self._joint_owner_groups[joint_name] = group
00170         return self._joint_owner_groups[joint_name]
00171 
00172     def __getattr__(self, name):
00173         """ We catch the names of groups, joints and links to allow easy access to their properties """
00174         if name in self.get_group_names():
00175             return self.get_group(name)
00176         elif name in self.get_joint_names():
00177             return self.Joint(name)
00178         elif name in self.get_link_names():
00179             return self.Link(name)
00180         else:
00181             return object.__getattribute__(self, name)


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