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 rospy
00037 import actionlib
00038 import random
00039 import copy
00040
00041 from nao_driver import NaoNode
00042
00043 from nao_msgs.msg import(
00044 BlinkAction,
00045 BlinkResult,
00046 BlinkFeedback,
00047 FadeRGB
00048 )
00049
00050 class NaoLeds(NaoNode):
00051
00052 NODE_NAME = "nao_leds"
00053
00054 def __init__( self ):
00055
00056
00057 NaoNode.__init__( self, self.NODE_NAME )
00058
00059
00060 self.proxy = self.get_proxy( "ALLeds" )
00061
00062
00063 random.seed( rospy.Time.now().to_nsec() )
00064
00065
00066 self.subscriber = rospy.Subscriber(
00067 "fade_rgb",
00068 FadeRGB,
00069 self.fade_rgb)
00070
00071
00072 self.actionlib = actionlib.SimpleActionServer(
00073 "blink",
00074 BlinkAction,
00075 self.run_blink,
00076 False
00077 )
00078 self.actionlib.start()
00079
00080
00081 def fade_rgb(self, request) :
00082 hexColor = int(
00083 int(request.color.r*255) << 16 |
00084 int(request.color.g*255) << 8 |
00085 int(request.color.b*255)
00086 )
00087
00088 self.proxy.fadeRGB(
00089 request.led_name,
00090 hexColor,
00091 request.fade_duration.to_sec()
00092 )
00093
00094 def run_blink( self, request ):
00095
00096
00097 third_of_duration = request.blink_duration / 3.0
00098
00099
00100 bg_msg = FadeRGB();
00101 bg_msg.led_name = "FaceLeds"
00102 bg_msg.color = request.bg_color
00103 bg_msg.fade_duration = third_of_duration
00104
00105
00106 blink_msg = copy.deepcopy( bg_msg )
00107
00108
00109 feedback = BlinkFeedback()
00110 result = BlinkResult()
00111 result.still_blinking = False
00112
00113
00114 bad_request = False
00115 reason = ""
00116 if not request.colors:
00117 bad_request = True
00118 reason = "No colors to blink were specified"
00119 elif request.blink_duration.to_sec() <= 0.0:
00120 bad_request = True
00121 reason = "Blink duration cannot be 0"
00122 elif request.blink_rate_mean <= 0.0 or request.blink_rate_sd <= 0.0:
00123 bad_request = True
00124 reason = "Invalid parameter for blink rate"
00125
00126 if bad_request:
00127 rospy.logwarn("Bad Blink request: {}".format(reason))
00128 self.actionlib.set_aborted(result, reason)
00129 return
00130
00131
00132 sleep_mean = request.blink_rate_mean
00133 sleep_sd = request.blink_rate_sd
00134 max_sleep_time = sleep_mean + 3* sleep_sd
00135
00136
00137 while ( not self.actionlib.is_preempt_requested() and
00138 not rospy.is_shutdown() ) :
00139
00140
00141 blink_msg.color = random.choice( request.colors )
00142
00143
00144 self.fade_rgb( blink_msg )
00145
00146 rospy.sleep( third_of_duration )
00147
00148 self.fade_rgb( bg_msg )
00149
00150
00151 feedback.last_color = blink_msg.color
00152 self.actionlib.publish_feedback( feedback )
00153
00154
00155 sleep_time = random.gauss( sleep_mean, sleep_sd )
00156
00157 if sleep_time < 0:
00158 sleep_time = 0
00159 elif sleep_time > max_sleep_time :
00160 sleep_time = max_sleep_time
00161
00162 rospy.sleep( sleep_time )
00163
00164
00165 if self.actionlib.is_new_goal_available() :
00166 result.still_blinking = True
00167
00168
00169 self.actionlib.set_preempted( result )
00170
00171 if __name__ == '__main__':
00172 node = NaoLeds()
00173 rospy.loginfo( node.NODE_NAME + " running..." )
00174 rospy.spin()
00175 rospy.loginfo( node.NODE_NAME + " stopped." )
00176 exit(0)
nao_driver
Author(s): Armin Hornung, Armin Hornung, Stefan Osswald, Daniel Maier, Miguel Sarabia, Séverin Lemaignan
autogenerated on Mon Oct 6 2014 02:39:17