Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
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
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
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
00085
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
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