tactile_receiver.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 
00003 # Copyright 2014 Shadow Robot Company Ltd.
00004 #
00005 # This program is free software: you can redistribute it and/or modify it
00006 # under the terms of the GNU General Public License as published by the Free
00007 # Software Foundation, either version 2 of the License, or (at your option)
00008 # any later version.
00009 #
00010 # This program is distributed in the hope that it will be useful, but WITHOUT
00011 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
00012 # FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
00013 # more details.
00014 #
00015 # You should have received a copy of the GNU General Public License along
00016 # with this program.  If not, see <http://www.gnu.org/licenses/>.
00017 
00018 import rospy
00019 
00020 from sr_robot_msgs.msg import BiotacAll, ShadowPST, UBI0All
00021 
00022 
00023 class TactileReceiver(object):
00024     """
00025     Module that receives the tactile values.
00026     """
00027 
00028     def __init__(self, prefix=""):
00029         """
00030         Receives the tactile information from a Shadow Hand
00031         @param prefix - prefix for the tactile topic
00032         """
00033         # appends trailing slash if necessary
00034         if not prefix.endswith("/"):
00035             prefix += "/"
00036 
00037         self._prefix = prefix
00038 
00039         self.tactile_type = self.find_tactile_type()
00040         self.tactile_state = None
00041 
00042         if self.tactile_type == "PST":
00043             self.tactile_listener = rospy.Subscriber(prefix+"tactile", ShadowPST, self.tactile_callback, queue_size=1)
00044         elif self.tactile_type == "biotac":
00045             self.tactile_listener = rospy.Subscriber(prefix+"tactile", BiotacAll, self.tactile_callback, queue_size=1)
00046         elif self.tactile_type == "UBI0":
00047             self.tactile_listener = rospy.Subscriber(prefix+"tactile", UBI0All, self.tactile_callback, queue_size=1)
00048 
00049     def find_tactile_type(self):
00050         try:
00051             rospy.wait_for_message(self._prefix+"tactile", ShadowPST, timeout=0.2)
00052             return "PST"
00053         except (rospy.ROSException, rospy.ROSInterruptException):
00054             pass
00055 
00056         try:
00057             rospy.wait_for_message(self._prefix+"tactile", BiotacAll, timeout=0.2)
00058             return "biotac"
00059         except (rospy.ROSException, rospy.ROSInterruptException):
00060             pass
00061 
00062         try:
00063             rospy.wait_for_message(self._prefix+"tactile", UBI0All, timeout=0.2)
00064             return "UBI0"
00065         except (rospy.ROSException, rospy.ROSInterruptException):
00066             rospy.logwarn("No tactile topic found. This is normal for a simulated hand")
00067 
00068         return None
00069 
00070     def tactile_callback(self, tactile_msg):
00071         self.tactile_state = tactile_msg
00072 
00073     def get_tactile_type(self):
00074         return self.tactile_type
00075 
00076     def get_tactile_state(self):
00077         return self.tactile_state


sr_hand
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:24:55