sr_ronex_flash_LED_with_PWM.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 PWM
00024 
00025 #--------------------------------------------------------------------------------
00026 
00027 # Flash a LED light with PWM.
00028 def flashLED(topic):
00029     pwm_period = 320
00030     # Start with a 100% duty cycle.
00031     pwm_on_time_0 = pwm_period
00032     # The second output is not used.
00033     pwm_on_time_1 = 0
00034 
00035     pub = rospy.Publisher( topic, PWM )
00036     while not rospy.is_shutdown():
00037         # Flash the light...
00038         pwm_on_time_0 -= 10
00039         if pwm_on_time_0 < 0:
00040             pwm_on_time_0 = pwm_period
00041 
00042         # Set the PWM data.
00043         pwm = PWM()
00044         pwm.pwm_period    = pwm_period
00045         pwm.pwm_on_time_0 = pwm_on_time_0
00046         pwm.pwm_on_time_1 = pwm_on_time_1
00047 
00048         pub.publish( pwm )
00049         rospy.sleep( 0.01 )
00050 
00051 #--------------------------------------------------------------------------------
00052 
00053 """
00054 This class demonstrates how to find the General I/O module with the given ronex_id.
00055 """
00056 class SrRonexFindGeneralIOModule(object):
00057 
00058     def __init__(self, ronex_id):
00059         self.ronex_id = ronex_id
00060 
00061     """
00062     Get the path of the General I/O module with the given ronex_id.
00063     Note that None is returned if the module is not found.
00064     """
00065     def get_path(self):
00066         """
00067         Find the ronexes present on the system.
00068         """
00069         # Wait until there's one ronex.
00070         while True:
00071             try:
00072                 rospy.get_param("/ronex/devices/0/ronex_id")
00073                 break
00074             except:
00075                 rospy.loginfo("Waiting for the ronex to be loaded properly.")
00076                 sleep(0.1)
00077 
00078         """
00079         Retrieve all the ronex parameter ids from the parameter server.
00080         If there are three General I/O modules, then ronex_param_ids is [0,1,2].
00081         Note that the id starts from zero. And the size of the returned variable
00082         is equal to the number of General I/O modules.
00083         """
00084         ronex_param_ids = rospy.get_param("/ronex/devices")
00085         for key in ronex_param_ids:
00086             if self.ronex_id == ronex_param_ids[key]["ronex_id"]:
00087                 path = ronex_param_ids[key]["path"]
00088                 return path
00089 
00090 #--------------------------------------------------------------------------------
00091 
00092 """
00093 Assume that your RoNeX consists of a Bridge (IN) module, and one or multiple General I/O module(s).
00094 This example demonstrates how to flash a LED light with pulse-width modulation (PWM).
00095 """
00096 if __name__ == "__main__":
00097     rospy.init_node('sr_ronex_flash_LED_with_PWM')
00098 
00099     print "Please configure D0 pin of your ronex module as output (you can use plugin Dynamic Reconfigure in rqt): \n"
00100 
00101     # Note that you may have to set the value of ronex_id,
00102     # depending on which General I/O board the LED is connected to.
00103     ronex_id = raw_input( "Please enter the ronex id: " )
00104     findModule = SrRonexFindGeneralIOModule( str(ronex_id) )
00105     path = findModule.get_path()
00106 
00107     if path != None:
00108         # Always use the first digital I/O channel to flash the LED light.
00109         # For example "/ronex/general_io/1" + "/command/pwm/0".
00110         topic = path + "/command/pwm/0"
00111         rospy.loginfo("topic = %s.", topic)
00112         try:
00113             flashLED(topic)
00114         except rospy.ROSInterruptException:
00115             pass
00116     else:
00117         rospy.loginfo("Failed to find the General I/O module with the given ronex_id %s.", ronex_id)
00118 
00119 #--------------------------------------------------------------------------------


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