Functions | Variables
drone_teleop Namespace Reference

Functions

def getKey ()
 
def vels (speed, turn)
 

Variables

int aux1 = 1500
 
int aux2 = 1500
 
int aux3 = 1500
 
int aux4 = 1500
 
 cmd = edrone_msgs()
 
int count = 0
 
 key = getKey()
 
dictionary KeyBinding
 
string msg
 
int pitch = 1500
 
 pub = rospy.Publisher('/drone_command', edrone_msgs, queue_size=5)
 
 rcAUX1
 
 rcAUX2
 
 rcAUX3
 
 rcAUX4
 
 rcPitch
 
 rcRoll
 
 rcThrottle
 
 rcYaw
 
int roll = 1500
 
 settings = termios.tcgetattr(sys.stdin)
 
int speed = .2
 
int throttle = 1500
 
int turn = 1
 
int yaw = 1500
 

Detailed Description

BSD 2-Clause License

Copyright (c) 2019, Simranjeet Singh
All rights reserved.

Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:

1. Redistributions of source code must retain the above copyright notice, this
   list of conditions and the following disclaimer.

2. Redistributions in binary form must reproduce the above copyright notice,
   this list of conditions and the following disclaimer in the documentation
   and/or other materials provided with the distribution.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Function Documentation

def drone_teleop.getKey ( )

Definition at line 70 of file drone_teleop.py.

def drone_teleop.vels (   speed,
  turn 
)

Definition at line 84 of file drone_teleop.py.

Variable Documentation

int drone_teleop.aux1 = 1500

Definition at line 97 of file drone_teleop.py.

int drone_teleop.aux2 = 1500

Definition at line 98 of file drone_teleop.py.

int drone_teleop.aux3 = 1500

Definition at line 99 of file drone_teleop.py.

int drone_teleop.aux4 = 1500

Definition at line 100 of file drone_teleop.py.

drone_teleop.cmd = edrone_msgs()

Definition at line 131 of file drone_teleop.py.

int drone_teleop.count = 0

Definition at line 101 of file drone_teleop.py.

drone_teleop.key = getKey()

Definition at line 106 of file drone_teleop.py.

dictionary drone_teleop.KeyBinding
Initial value:
1 = {
2  #key:(roll,pitch,yaw,throt,aux1,aux2,aux3,aux4)
3  'i':(1500,1900,1500,1500,1500,1500,1500,1500),
4  'a':(1500,1500,1500,1000,1500,1500,1500,1500),
5  'j':(1900,1500,1500,1500,1500,1500,1500,1500),
6  'l':(1100,1500,1500,1500,1500,1500,1500,1500),
7  'd':(1500,1500,1500,1300,1500,1500,1500,1200),
8  'm':(1500,1100,1500,1500,1500,1500,1500,1500),
9  'w':(1500,1500,1500,1900,1500,1500,1500,1500),
10  's':(1500,1500,1500,1100,1500,1500,1500,1500),
11  'o':(1500,1500,1600,1900,1500,1500,1500,1500),
12  'u':(1500,1500,1400,1100,1500,1500,1500,1500),
13  }

Definition at line 56 of file drone_teleop.py.

string drone_teleop.msg
Initial value:
1 = """
2 Control Your eDrone!
3 ---------------------------
4 Moving around:
5  u i o
6  j k l
7  m
8 
9 
10 a : Arm drone
11 d : Dis-arm drone
12 w : Increase Altitude
13 s : Increase Altitude
14 u,o: Change Yaw
15 
16 CTRL-C to quit
17 """

Definition at line 38 of file drone_teleop.py.

int drone_teleop.pitch = 1500

Definition at line 94 of file drone_teleop.py.

drone_teleop.pub = rospy.Publisher('/drone_command', edrone_msgs, queue_size=5)

Definition at line 91 of file drone_teleop.py.

drone_teleop.rcAUX1

Definition at line 133 of file drone_teleop.py.

drone_teleop.rcAUX2

Definition at line 133 of file drone_teleop.py.

drone_teleop.rcAUX3

Definition at line 134 of file drone_teleop.py.

drone_teleop.rcAUX4

Definition at line 134 of file drone_teleop.py.

drone_teleop.rcPitch

Definition at line 132 of file drone_teleop.py.

drone_teleop.rcRoll

Definition at line 132 of file drone_teleop.py.

drone_teleop.rcThrottle

Definition at line 133 of file drone_teleop.py.

drone_teleop.rcYaw

Definition at line 132 of file drone_teleop.py.

int drone_teleop.roll = 1500

Definition at line 93 of file drone_teleop.py.

drone_teleop.settings = termios.tcgetattr(sys.stdin)

Definition at line 88 of file drone_teleop.py.

int drone_teleop.speed = .2

Definition at line 81 of file drone_teleop.py.

int drone_teleop.throttle = 1500

Definition at line 96 of file drone_teleop.py.

int drone_teleop.turn = 1

Definition at line 82 of file drone_teleop.py.

int drone_teleop.yaw = 1500

Definition at line 95 of file drone_teleop.py.



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