nao_leds.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 #
00004 # ROS node to control NAO's LEDs using NaoQI
00005 # Tested with NaoQI: 1.12
00006 #
00007 # Copyright (c) 2012, 2013 Miguel Sarabia
00008 # Imperial College London
00009 #
00010 # Redistribution and use in source and binary forms, with or without
00011 # modification, are permitted provided that the following conditions are met:
00012 #
00013 #    # Redistributions of source code must retain the above copyright
00014 #       notice, this list of conditions and the following disclaimer.
00015 #    # Redistributions in binary form must reproduce the above copyright
00016 #       notice, this list of conditions and the following disclaimer in the
00017 #       documentation and/or other materials provided with the distribution.
00018 #    # Neither the name of the Imperial College London nor the names of its
00019 #       contributors may be used to endorse or promote products derived from
00020 #       this software without specific prior written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00023 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00024 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00025 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00026 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00027 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00028 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00029 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00030 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00031 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 #
00034 
00035 
00036 import roslib
00037 
00038 roslib.load_manifest('nao_driver')
00039 
00040 import rospy
00041 import actionlib
00042 import random
00043 import copy
00044 
00045 from nao_driver import NaoNode
00046 
00047 from nao_msgs.msg import(
00048     BlinkAction,
00049     BlinkResult,
00050     BlinkFeedback,
00051     FadeRGB
00052     )
00053 
00054 class NaoLeds(NaoNode):
00055     #This should be treated as a constant
00056     NODE_NAME = "nao_leds"
00057     
00058     def __init__( self ):
00059         
00060         #Initialisation
00061         NaoNode.__init__( self )
00062         rospy.init_node( self.NODE_NAME )
00063         
00064         #Proxy to interface with LEDs
00065         self.proxy = self.getProxy( "ALLeds" )
00066         
00067         #Seed python's random number generator
00068         random.seed( rospy.Time.now().to_nsec() )
00069         
00070         #Create a subscriber for the fade_rgb topic
00071         self.subscriber = rospy.Subscriber( 
00072             "fade_rgb",
00073             FadeRGB,
00074             self.fade_rgb)
00075 
00076         #Prepare and start actionlib server
00077         self.actionlib = actionlib.SimpleActionServer(
00078             "blink",
00079             BlinkAction,
00080             self.run_blink,
00081             False
00082             )
00083         self.actionlib.start()
00084         
00085     
00086     def fade_rgb(self, request) :
00087         hexColor =  int(
00088             int(request.color.r*255) << 16 | 
00089             int(request.color.g*255) << 8 |
00090             int(request.color.b*255)
00091             )
00092 
00093         self.proxy.fadeRGB(
00094             request.led_name,
00095             hexColor,
00096             request.fade_duration.to_sec()
00097             )
00098     
00099     def run_blink( self, request ):
00100         #Note that this function is executed on a different thread
00101 
00102         third_of_duration = request.blink_duration / 3.0
00103         
00104         #Prepare background message
00105         bg_msg = FadeRGB();
00106         bg_msg.led_name = "FaceLeds"
00107         bg_msg.color = request.bg_color
00108         bg_msg.fade_duration = third_of_duration
00109         
00110         #Prepare a copy for blink_msg
00111         blink_msg = copy.deepcopy( bg_msg )
00112         
00113         #Construct result and feedback
00114         feedback = BlinkFeedback()
00115         result = BlinkResult()
00116         result.still_blinking = False
00117 
00118         #Check valid parameters
00119         bad_request = False
00120         reason = ""
00121         if not request.colors:
00122             bad_request = True
00123             reason = "No colors to blink were specified"
00124         elif request.blink_duration.to_sec() <= 0.0:
00125             bad_request = True
00126             reason = "Blink duration cannot be 0"
00127         elif request.blink_rate_mean <= 0.0 or request.blink_rate_sd <= 0.0:
00128             bad_request = True
00129             reason = "Invalid parameter for blink rate"
00130         
00131         if bad_request:
00132             rospy.logwarn("Bad Blink request: {}".format(reason))
00133             self.actionlib.set_aborted(result, reason)
00134             return
00135         
00136         #Sleep time is drawn from a gaussian dist with these parameters
00137         sleep_mean = request.blink_rate_mean
00138         sleep_sd = request.blink_rate_sd
00139         max_sleep_time = sleep_mean + 3* sleep_sd #This is highly unlikely
00140         
00141         #Main blinking loop
00142         while ( not self.actionlib.is_preempt_requested() and 
00143             not rospy.is_shutdown() ) :
00144             
00145             #Chose a blinking color at random
00146             blink_msg.color = random.choice( request.colors )
00147 
00148             #Send command (takes 1/3 duration to fade)
00149             self.fade_rgb( blink_msg )
00150             #Sleep (takes 1/3 duration)
00151             rospy.sleep( third_of_duration )
00152             #Fade to background (takes another 1/3 duration)
00153             self.fade_rgb( bg_msg )
00154             
00155             #Publish feedback
00156             feedback.last_color = blink_msg.color
00157             self.actionlib.publish_feedback( feedback )
00158             
00159             #Sleep for a random amount of time
00160             sleep_time = random.gauss( sleep_mean, sleep_sd )
00161             
00162             if sleep_time < 0:
00163                 sleep_time = 0
00164             elif sleep_time > max_sleep_time : 
00165                 sleep_time = max_sleep_time
00166                 
00167             rospy.sleep( sleep_time )
00168         
00169         #If we were pre-empted by other request, make sure result shows this
00170         if self.actionlib.is_new_goal_available() :
00171             result.still_blinking = True
00172                 
00173         # Task never completes so if we reach here, blink has been pre-empted
00174         self.actionlib.set_preempted( result )
00175 
00176 if __name__ == '__main__':
00177     node = NaoLeds()
00178     rospy.loginfo( node.NODE_NAME + " running..." )
00179     rospy.spin()
00180     rospy.loginfo( node.NODE_NAME + " stopped." )
00181     exit(0)
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


nao_driver
Author(s): Armin Hornung, Stefan Osswald, Daniel Maier
autogenerated on Tue Oct 15 2013 10:06:23