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
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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
00056 NODE_NAME = "nao_leds"
00057
00058 def __init__( self ):
00059
00060
00061 NaoNode.__init__( self )
00062 rospy.init_node( self.NODE_NAME )
00063
00064
00065 self.proxy = self.getProxy( "ALLeds" )
00066
00067
00068 random.seed( rospy.Time.now().to_nsec() )
00069
00070
00071 self.subscriber = rospy.Subscriber(
00072 "fade_rgb",
00073 FadeRGB,
00074 self.fade_rgb)
00075
00076
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
00101
00102 third_of_duration = request.blink_duration / 3.0
00103
00104
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
00111 blink_msg = copy.deepcopy( bg_msg )
00112
00113
00114 feedback = BlinkFeedback()
00115 result = BlinkResult()
00116 result.still_blinking = False
00117
00118
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
00137 sleep_mean = request.blink_rate_mean
00138 sleep_sd = request.blink_rate_sd
00139 max_sleep_time = sleep_mean + 3* sleep_sd
00140
00141
00142 while ( not self.actionlib.is_preempt_requested() and
00143 not rospy.is_shutdown() ) :
00144
00145
00146 blink_msg.color = random.choice( request.colors )
00147
00148
00149 self.fade_rgb( blink_msg )
00150
00151 rospy.sleep( third_of_duration )
00152
00153 self.fade_rgb( bg_msg )
00154
00155
00156 feedback.last_color = blink_msg.color
00157 self.actionlib.publish_feedback( feedback )
00158
00159
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
00170 if self.actionlib.is_new_goal_available() :
00171 result.still_blinking = True
00172
00173
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)