drone_teleop.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 BSD 2-Clause License
5 
6 Copyright (c) 2019, Simranjeet Singh
7 All rights reserved.
8 
9 Redistribution and use in source and binary forms, with or without
10 modification, are permitted provided that the following conditions are met:
11 
12 1. Redistributions of source code must retain the above copyright notice, this
13  list of conditions and the following disclaimer.
14 
15 2. Redistributions in binary form must reproduce the above copyright notice,
16  this list of conditions and the following disclaimer in the documentation
17  and/or other materials provided with the distribution.
18 
19 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
23 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
24 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
25 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
27 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29 '''
30 
31 import rospy
32 from edrone_client.msg import *
33 
34 from geometry_msgs.msg import Twist
35 
36 import sys, select, termios, tty
37 
38 msg = """
39 Control Your eDrone!
40 ---------------------------
41 Moving around:
42  u i o
43  j k l
44  m
45 
46 
47 a : Arm drone
48 d : Dis-arm drone
49 w : Increase Altitude
50 s : Increase Altitude
51 u,o: Change Yaw
52 
53 CTRL-C to quit
54 """
55 
56 KeyBinding = {
57  #key:(roll,pitch,yaw,throt,aux1,aux2,aux3,aux4)
58  'i':(1500,1900,1500,1500,1500,1500,1500,1500),
59  'a':(1500,1500,1500,1000,1500,1500,1500,1500),
60  'j':(1900,1500,1500,1500,1500,1500,1500,1500),
61  'l':(1100,1500,1500,1500,1500,1500,1500,1500),
62  'd':(1500,1500,1500,1300,1500,1500,1500,1200),
63  'm':(1500,1100,1500,1500,1500,1500,1500,1500),
64  'w':(1500,1500,1500,1900,1500,1500,1500,1500),
65  's':(1500,1500,1500,1100,1500,1500,1500,1500),
66  'o':(1500,1500,1600,1900,1500,1500,1500,1500),
67  'u':(1500,1500,1400,1100,1500,1500,1500,1500),
68  }
69 
70 def getKey():
71  tty.setraw(sys.stdin.fileno())
72  rlist, _, _ = select.select([sys.stdin], [], [], 0.1)
73  if rlist:
74  key = sys.stdin.read(1)
75  else:
76  key = ''
77 
78  termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
79  return key
80 
81 speed = .2
82 turn = 1
83 
84 def vels(speed,turn):
85  return "currently:\tspeed %s\tturn %s " % (speed,turn)
86 
87 if __name__=="__main__":
88  settings = termios.tcgetattr(sys.stdin)
89 
90  rospy.init_node('eDrone_teleop')
91  pub = rospy.Publisher('/drone_command', edrone_msgs, queue_size=5)
92 
93  roll = 1500
94  pitch = 1500
95  yaw = 1500
96  throttle = 1500
97  aux1=1500
98  aux2=1500
99  aux3=1500
100  aux4=1500
101  count =0
102 
103  try:
104  print(msg)
105  while(1):
106  key = getKey()
107  if key in KeyBinding.keys():
108  roll = KeyBinding[key][0]
109  pitch = KeyBinding[key][1]
110  yaw = KeyBinding[key][2]
111  throttle = KeyBinding[key][3]
112  aux1=KeyBinding[key][4]
113  aux2=KeyBinding[key][5]
114  aux3=KeyBinding[key][6]
115  aux4=KeyBinding[key][7]
116  count = 0
117  if (key == '\x03'):
118  break
119  else:
120  count = count + 1
121  if count > 4:
122  roll = 1500
123  pitch = 1500
124  yaw = 1500
125  throttle = 1500
126  aux1=1500
127  aux2=1500
128  aux3=1500
129  aux4=1500
130 
131  cmd = edrone_msgs()
132  cmd.rcRoll = roll; cmd.rcPitch = pitch; cmd.rcYaw = yaw
133  cmd.rcThrottle = throttle; cmd.rcAUX1 = aux1; cmd.rcAUX2 = aux2
134  cmd.rcAUX3 = aux3; cmd.rcAUX4 = aux4
135  pub.publish(cmd)
136 
137  except Exception as e:
138  print(e)
139 
140  finally:
141  cmd = edrone_msgs()
142  cmd.rcRoll = roll; cmd.rcPitch = pitch; cmd.rcYaw = yaw
143  cmd.rcThrottle = throttle; cmd.rcAUX1 = aux1; cmd.rcAUX2 = aux2
144  cmd.rcAUX3 = aux3; cmd.rcAUX4 = aux4
145  pub.publish(cmd)
146 
147  termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
148 
def vels(speed, turn)
Definition: drone_teleop.py:84


edrone_server
Author(s): Simranjeet Singh
autogenerated on Sun Dec 1 2019 03:30:53