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


moveit_commander
Author(s): Ioan Sucan
autogenerated on Wed Aug 26 2015 12:38:52