00001
00002
00003
00004 try:
00005 import roslib; roslib.load_manifest('rospeex_if')
00006 except:
00007 pass
00008
00009 import rospy
00010
00011 from geometry_msgs.msg import Twist
00012
00013 from rospeex_if import ROSpeexInterface
00014 import re
00015
00016 rospeex = None
00017 turtle_pub = None
00018
00019 OPERATION_TIME = 500
00020 TURN_TIME = 11
00021 TURN_ACTION_COUNTER_MAX = 7
00022 TARGET_SPEED = 0.12
00023 TARGET_TURN = 1.0
00024
00025 _target_speed = 0.0
00026 _control_speed = 0.0
00027 _target_turn = 0.0
00028 _control_turn = 0.0
00029 _operation_count = 0
00030 _turn_action = 0
00031 _started = False
00032 _force_stop = False
00033 _force_stop = False
00034 _during_right = False
00035 _during_left = False
00036
00037 _pattern_rule = ""
00038
00039 def set_ope_param( target_speed, target_turn ):
00040 global _target_speed, _target_turn, _operation_count
00041 _target_speed = target_speed
00042 _target_turn = target_turn
00043 _operation_count = 0
00044
00045 def speak(msg):
00046 rospeex.say( msg, language='en', engine='nict', voice_font='EF007')
00047
00048 def timer_callback(event):
00049 global _target_speed, _control_speed, _target_turn, _control_turn, _operation_count, _during_right, _during_left, _started, _force_stop, _turn_action, OPERATION_TIME, TARGET_SPEED, TURN_TIME, TURN_ACTION_COUNTER_MAX
00050 _operation_count += 1
00051 if _force_stop == True:
00052 _started = False
00053 _force_stop = False
00054 _during_right = False
00055 _during_left = False
00056 _turn_action = 0
00057 elif _during_right == True:
00058 if _operation_count > TURN_TIME:
00059 _turn_action += 1
00060 if _turn_action == TURN_ACTION_COUNTER_MAX:
00061 set_ope_param(0, TARGET_TURN)
00062 else:
00063 set_ope_param(TARGET_SPEED, 0)
00064 elif _during_left == True:
00065 if _operation_count > TURN_TIME:
00066 _turn_action += 1
00067 if _turn_action == TURN_ACTION_COUNTER_MAX:
00068 set_ope_param(0, -TARGET_TURN)
00069 else:
00070 set_ope_param(TARGET_SPEED, 0)
00071 elif _operation_count > OPERATION_TIME and _started == True:
00072 speak( "It's time over.")
00073 print "It's time over."
00074 set_ope_param( 0, 0 )
00075 _started = False
00076
00077 turtle_move( _target_speed, _target_turn )
00078 if _turn_action > TURN_ACTION_COUNTER_MAX:
00079 _turn_action = 0
00080 _during_right = False
00081 _during_left = False
00082
00083 def sr_response(message):
00084 rospy.loginfo(message)
00085 global TARGET_SPEED, TARGET_TURN, _during_right, _during_left, _started, _force_stop, _pattern_rule
00086 print 'you said : \"%s\"' %message
00087
00088 m = _pattern_rule.match(message.lower())
00089
00090 if m is not None:
00091 operation = m.group(2)
00092 print "recognized \"%s\"" %operation
00093
00094 if ( operation == "back" ) and _started == False:
00095 speak("I'm moving backward.")
00096 _started = True
00097 set_ope_param(-TARGET_SPEED, 0)
00098
00099 elif operation == "ready" and _started == False:
00100 print "Ready."
00101 _started = True
00102 set_ope_param(TARGET_SPEED*0.08, 0)
00103
00104 elif operation == "start" or operation == "straight":
00105 speak("I'm starting.")
00106 print "I'm starting."
00107 _started = True
00108 set_ope_param(TARGET_SPEED, 0)
00109
00110 elif operation == "right":
00111 if _during_right == True:
00112 speak("I'm already turning.")
00113 print "I'm already turning."
00114 elif _started == True:
00115 _during_right = True
00116 speak("I'm turning right.")
00117 print "I'm turning right."
00118 set_ope_param(0, -TARGET_TURN)
00119
00120 elif operation == "left":
00121 if _during_left == True:
00122 speak("I'm already turning.")
00123 print "I'm already turning."
00124 elif _started == True:
00125 _during_left = True
00126 speak("I'm turning left.")
00127 print "I'm turning left."
00128 set_ope_param(0, TARGET_TURN)
00129
00130 elif operation == "stop" or operation == 'wait':
00131 speak("I stopped.")
00132 print "I stopped."
00133 _force_stop = True
00134 set_ope_param(0, 0)
00135
00136 elif message != "":
00137 print "What?"
00138 rospeex.play_sound( "alert.wav" )
00139
00140 def turtle_move( target_speed, target_turn ):
00141 global _control_speed, _control_turn
00142
00143 if target_speed > _control_speed:
00144 _control_speed = min( target_speed, _control_speed + 0.02 )
00145 elif target_speed < _control_speed:
00146 _control_speed = max( target_speed, _control_speed - 0.02 )
00147 else:
00148 _control_speed = target_speed
00149
00150 if target_turn > _control_turn:
00151 _control_turn = min( target_turn, _control_turn + 0.1 )
00152 elif target_turn < _control_turn:
00153 _control_turn = max( target_turn, _control_turn - 0.1 )
00154 else:
00155 _control_turn = target_turn
00156
00157 control_speed = _control_speed
00158 control_turn = _control_turn
00159
00160 twist = Twist()
00161 twist.linear.x = control_speed; twist.linear.y = 0; twist.linear.z = 0
00162 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = control_turn
00163 turtle_pub.publish(twist)
00164
00165 if __name__=="__main__":
00166
00167 _pattern_rule = re.compile( '.*(robot)*.*(back|ready|start|straight|right|left|stop|wait)')
00168
00169 _operation_count = 0
00170 _turn_action = 0
00171 _started = False
00172 _force_stop = False
00173 _force_stop = False
00174 _during_right = False
00175 _during_left = False
00176 rospy.init_node('rospeex_turtle')
00177 rospeex = ROSpeexInterface()
00178 rospeex.init()
00179 rospeex.register_sr_response( sr_response )
00180 rospeex.set_spi_config(language='en',engine='nict')
00181
00182 turtle_pub = rospy.Publisher('cmd_vel_mux/input/teleop', Twist)
00183 rospy.Timer(rospy.Duration(0,100000000), timer_callback)
00184
00185 try:
00186 rospy.spin();
00187 except:
00188 print e
00189 finally:
00190 twist = Twist()
00191 twist.linear.x = 0; twist.linear.y = 0; twist.linear.z = 0
00192 twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 0
00193 turtle_pub.publish(twist)
00194