6 Copyright (c) 2019, Simranjeet Singh 9 Redistribution and use in source and binary forms, with or without 10 modification, are permitted provided that the following conditions are met: 12 1. Redistributions of source code must retain the above copyright notice, this 13 list of conditions and the following disclaimer. 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. 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. 34 from geometry_msgs.msg
import Twist
36 import sys, select, termios, tty
40 --------------------------- 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), 71 tty.setraw(sys.stdin.fileno())
72 rlist, _, _ = select.select([sys.stdin], [], [], 0.1)
74 key = sys.stdin.read(1)
78 termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
85 return "currently:\tspeed %s\tturn %s " % (speed,turn)
87 if __name__==
"__main__":
88 settings = termios.tcgetattr(sys.stdin)
90 rospy.init_node(
'eDrone_teleop')
91 pub = rospy.Publisher(
'/drone_command', edrone_msgs, queue_size=5)
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]
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
137 except Exception
as e:
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
147 termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)