sr_ronex_read_analog_data.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # ####################################################################
00004 # Copyright (c) 2013, Shadow Robot Company, All rights reserved.
00005 # 
00006 # This library is free software; you can redistribute it and/or
00007 # modify it under the terms of the GNU Lesser General Public
00008 # License as published by the Free Software Foundation; either
00009 # version 3.0 of the License, or (at your option) any later version.
00010 #
00011 # This library is distributed in the hope that it will be useful,
00012 # but WITHOUT ANY WARRANTY; without even the implied warranty of
00013 # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
00014 # Lesser General Public License for more details.
00015 #
00016 # You should have received a copy of the GNU Lesser General Public
00017 # License along with this library.
00018 # ####################################################################
00019 
00020 import roslib; roslib.load_manifest('sr_ronex_examples')
00021 import rospy
00022 from time import sleep
00023 from sr_ronex_msgs.msg import GeneralIOState
00024 
00025 #--------------------------------------------------------------------------------
00026 
00027 """
00028 The callback function given to the subscribe() call.
00029 """
00030 def generalIOState_callback(data):
00031     # Note that the type of data.analogue is tuple.
00032     analogue = data.analogue 
00033     rospy.loginfo( "analogue = %s", analogue )
00034 
00035 #--------------------------------------------------------------------------------
00036 
00037 """
00038 This class demonstrates how to find the General I/O module with the given ronex_id.
00039 """
00040 class SrRonexFindGeneralIOModule(object):
00041 
00042     def __init__(self, ronex_id):
00043         self.ronex_id = ronex_id
00044         
00045     """
00046     Get the path of the General I/O module with the given ronex_id.
00047     Note that None is returned if the module is not found.
00048     """
00049     def get_path(self):
00050         """
00051         Find the ronexes present on the system.
00052         """
00053         # Wait until there's one ronex.
00054         while True:
00055             try:
00056                 rospy.get_param("/ronex/devices/0/ronex_id")
00057                 break
00058             except:
00059                 rospy.loginfo("Waiting for the ronex to be loaded properly.")
00060                 sleep(0.1)
00061 
00062         """
00063         Retrieve all the ronex parameter ids from the parameter server.
00064         If there are three General I/O modules, then ronex_param_ids is [0,1,2].
00065         Note that the id starts from zero. And the size of the returned variable
00066         is equal to the number of General I/O modules.
00067         """
00068         ronex_param_ids = rospy.get_param("/ronex/devices")
00069         for key in ronex_param_ids:
00070             if self.ronex_id == ronex_param_ids[key]["ronex_id"]:
00071                 path = ronex_param_ids[key]["path"]
00072                 return path
00073 
00074 #--------------------------------------------------------------------------------
00075 
00076 """
00077 Assume that your RoNeX consists of a Bridge (IN) module, and one 
00078 or multiple General I/O module(s). This example demonstrates how 
00079 to read analogue data with RoNeX.
00080 """
00081 if __name__ == "__main__":
00082     rospy.init_node("sr_ronex_read_analog_data")
00083 
00084     # Note that you may have to set the value of ronex_id,
00085     # depending on which General I/O board the input device is connected to.
00086     ronex_id = raw_input( "Please enter the ronex id: " )
00087     findModule = SrRonexFindGeneralIOModule( str(ronex_id) )
00088     path = findModule.get_path()
00089 
00090     if path != None:
00091         # For example "/ronex/general_io/1" + "/state".
00092         topic = path + "/state"
00093         rospy.Subscriber( topic, GeneralIOState, generalIOState_callback )
00094         rospy.spin()
00095     else:
00096         rospy.loginfo("Failed to find the General I/O module with the given ronex_id %s.", ronex_id)
00097 
00098 #--------------------------------------------------------------------------------


sr_ronex_examples
Author(s): Ugo Cupcic, Toni Oliver, Mark Pitchless, Yi Li
autogenerated on Fri Aug 28 2015 13:12:34