$search
00001 #!/usr/bin/env python 00002 import math 00003 import roslib; roslib.load_manifest('teer_example_turtle') 00004 import rospy 00005 import numpy as np 00006 from turtlesim.msg import Velocity 00007 from turtlesim.msg import Pose 00008 from turtlesim.srv import TeleportAbsolute 00009 from turtlesim.srv import SetPen 00010 from turtlesim.srv import Spawn 00011 from std_srvs.srv import Empty as EmptyServiceCall 00012 from turtle_math import * 00013 from teer_ros import * 00014 00015 class TurtleScheduler(Scheduler): 00016 """ A teer scheduler working with ROS """ 00017 00018 turtle1_pose = ConditionVariable(None) 00019 turtle2_pose = ConditionVariable(None) 00020 00021 def __init__(self): 00022 """ Init the ROS scheduler """ 00023 super(TurtleScheduler,self).__init__() 00024 00025 def turtle1_go(target): 00026 """ Make turtle1 go to target, giving new speed command every second """ 00027 while True: 00028 # set new speed commands 00029 turtle1_velocity.publish(control_command(sched.turtle1_pose, target, 1.0)) 00030 # wait for 1 s 00031 yield WaitDuration(0.5) 00032 00033 def turtle2_go(target): 00034 """ Make turtle2 go to target, giving new speed command every second """ 00035 while True: 00036 # set new speed commands 00037 turtle2_velocity.publish(control_command(sched.turtle2_pose, target, 0.7)) 00038 # wait for 1 s 00039 yield WaitDuration(0.5) 00040 00041 def turtle1_wandering(): 00042 """ Make turtle1 do a square in the environment """ 00043 yield WaitCondition(lambda: sched.turtle1_pose is not None) 00044 00045 targets = [(2,2), (9,2), (9,9), (2,9)] 00046 target_id = 0 00047 while True: 00048 sched.printd('Going to ' + str(targets[target_id])) 00049 target = targets[target_id] 00050 go_tid = sched.new_task(turtle1_go(target)) 00051 yield WaitCondition(lambda: dist(sched.turtle1_pose, target) < 0.1) 00052 sched.kill_task(go_tid) 00053 target_id = (target_id + 1) % len(targets) 00054 00055 def turtle2_wandering(): 00056 """ Make turtle2 do a square in the environment, reverse direction as turtle1 """ 00057 yield WaitCondition(lambda: sched.turtle2_pose is not None) 00058 00059 targets = [(2,9), (9,9), (9,2), (2,2)] 00060 target_id = 0 00061 while True: 00062 sched.printd('Going to ' + str(targets[target_id])) 00063 target = targets[target_id] 00064 go_tid = sched.new_task(turtle2_go(target)) 00065 yield WaitCondition(lambda: dist(sched.turtle2_pose, target) < 0.1) 00066 sched.kill_task(go_tid) 00067 target_id = (target_id + 1) % len(targets) 00068 00069 def cupidon(): 00070 """ When turtles are close, make them dance """ 00071 my_tid = sched.get_current_tid() 00072 while True: 00073 yield WaitCondition(lambda: dist(sched.turtle1_pose, sched.turtle2_pose) < 1) 00074 sched.printd('Found friend, let\'s dance') 00075 paused_tasks = sched.pause_all_tasks_except([my_tid]) 00076 turtle1_set_pen(255,0,0,0,0) 00077 turtle2_set_pen(0,255,0,0,0) 00078 for i in range(7): 00079 turtle1_velocity.publish(Velocity(1, 1)) 00080 turtle2_velocity.publish(Velocity(1, -1)) 00081 yield WaitDuration(0.9) 00082 turtle1_set_pen(0,0,0,0,1) 00083 turtle2_set_pen(0,0,0,0,1) 00084 sched.printd('Tired of dancing, going back to wandering') 00085 sched.resume_tasks(paused_tasks) 00086 yield WaitDuration(10) 00087 00088 def turtle1_pose_updated(new_pose): 00089 """ We received a new pose of turtle1 from turtlesim, update condition variable in scheduler """ 00090 sched.turtle1_pose = new_pose 00091 00092 def turtle2_pose_updated(new_pose): 00093 """ We received a new pose of turtle2 from turtlesim, update condition variable in scheduler """ 00094 sched.turtle2_pose = new_pose 00095 00096 if __name__ == '__main__': 00097 # create scheduler 00098 sched = TurtleScheduler() 00099 sched.new_task(turtle1_wandering()) 00100 sched.new_task(turtle2_wandering()) 00101 sched.new_task(cupidon()) 00102 00103 # connect to turtlesim 00104 rospy.init_node('teer_example_turtle') 00105 # services 00106 rospy.wait_for_service('reset') 00107 reset_simulator = rospy.ServiceProxy('reset', EmptyServiceCall) 00108 reset_simulator() 00109 rospy.wait_for_service('clear') 00110 clear_background = rospy.ServiceProxy('clear', EmptyServiceCall) 00111 spawn_turtle = rospy.ServiceProxy('spawn', Spawn) 00112 spawn_turtle(0,0,0, "turtle2") 00113 rospy.wait_for_service('turtle1/set_pen') 00114 turtle1_set_pen = rospy.ServiceProxy('turtle1/set_pen', SetPen) 00115 rospy.wait_for_service('turtle1/teleport_absolute') 00116 turtle1_teleport = rospy.ServiceProxy('turtle1/teleport_absolute', TeleportAbsolute) 00117 rospy.wait_for_service('turtle2/set_pen') 00118 turtle2_set_pen = rospy.ServiceProxy('turtle2/set_pen', SetPen) 00119 rospy.wait_for_service('turtle2/teleport_absolute') 00120 turtle2_teleport = rospy.ServiceProxy('turtle2/teleport_absolute', TeleportAbsolute) 00121 # subscriber/publisher 00122 rospy.Subscriber('turtle1/pose', Pose, turtle1_pose_updated) 00123 turtle1_velocity = rospy.Publisher('turtle1/command_velocity', Velocity) 00124 rospy.Subscriber('turtle2/pose', Pose, turtle2_pose_updated) 00125 turtle2_velocity = rospy.Publisher('turtle2/command_velocity', Velocity) 00126 00127 # setup environment 00128 turtle1_set_pen(0,0,0,0,1) 00129 turtle2_set_pen(0,0,0,0,1) 00130 turtle1_teleport(2,2,0) 00131 turtle2_teleport(2,9,0) 00132 clear_background() 00133 00134 # run scheduler 00135 sched.run()