ardrone_control.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 import rospy
00003 import sys
00004 from std_msgs.msg import String
00005 from std_msgs.msg import Empty
00006 from geometry_msgs.msg import Twist
00007 
00008 
00009 
00010 def takeoff():    
00011     takeoff_pub.publish(Empty())
00012 
00013 
00014 def land():    
00015     land_pub.publish(Empty())
00016     
00017 def circle(): 
00018     twist = Twist()  
00019     twist.linear.x=4.0
00020     twist.angular.z=4.0 
00021     velocity_pub.publish(twist)
00022     
00023 def stop(): 
00024     twist = Twist()  
00025     twist.linear.x=0.0
00026     twist.linear.y=0.0
00027     twist.angular.z=0.0 
00028     velocity_pub.publish(twist)
00029 
00030 
00031 def menu():
00032     print ("t: takeoff")
00033     print ("l: land")
00034     print ("c: circle")
00035     print ("s: stop")
00036 
00037 if __name__ == '__main__':
00038     rospy.init_node('ardrone_control_node', anonymous=True)
00039     takeoff_pub = rospy.Publisher("/ardrone/takeoff", Empty, queue_size=10 )
00040     land_pub = rospy.Publisher("ardrone/land", Empty, queue_size=10 )
00041     velocity_pub = rospy.Publisher("cmd_vel", Twist, queue_size=10 )
00042     #rate = rospy.Rate(10) # 10hz
00043     try:
00044         while not rospy.is_shutdown():
00045             menu()
00046             #key= input("press a key for action")
00047             key=sys.stdin.read(1)
00048             if (key == str('t')):
00049                 takeoff()
00050             elif (key == str('l')):
00051                 land()
00052             elif (key == str('c')):
00053                 circle()
00054             elif (key == str('s')):
00055                 stop()
00056     except rospy.ROSInterruptException:
00057         pass


gapter
Author(s):
autogenerated on Thu Jun 6 2019 22:05:13