keyboard_teleop.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (c) 2011, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 #    * Redistributions of source code must retain the above copyright
00010 #      notice, this list of conditions and the following disclaimer.
00011 #    * Redistributions in binary form must reproduce the above copyright
00012 #      notice, this list of conditions and the following disclaimer in the
00013 #      documentation and/or other materials provided with the distribution.
00014 #    * Neither the name of the Willow Garage, Inc. nor the names of its
00015 #      contributors may be used to endorse or promote products derived from
00016 #       this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028 # POSSIBILITY OF SUCH DAMAGE.
00029 
00030 import roslib
00031 roslib.load_manifest('turtlebot_teleop')
00032 import rospy
00033 
00034 from geometry_msgs.msg import Twist
00035 
00036 import sys, select, termios, tty
00037 
00038 msg = """
00039 Control Your Turtlebot!
00040 ---------------------------
00041 Moving around:
00042    u    i    o
00043    j    k    l
00044    m    ,    .
00045 q/z : increase/decrease max speeds by 10%
00046 w/x : increase/decrease only linear speed by 10%
00047 e/c : increase/decrease only angular speed by 10%
00048 space key, k : force stop
00049 anything else : stop smoothly
00050 CTRL-C to quit
00051 """
00052 
00053 moveBindings = {
00054         'i':(1,0),
00055         'o':(1,-1),
00056         'j':(0,1),
00057         'l':(0,-1),
00058         'u':(1,1),
00059         ',':(-1,0),
00060         '.':(-1,1),
00061         'm':(-1,-1),
00062            }
00063 
00064 speedBindings={
00065         'q':(1.1,1.1),
00066         'z':(.9,.9),
00067         'w':(1.1,1),
00068         'x':(.9,1),
00069         'e':(1,1.1),
00070         'c':(1,.9),
00071           }
00072 
00073 def getKey():
00074     tty.setraw(sys.stdin.fileno())
00075     rlist, _, _ = select.select([sys.stdin], [], [], 0.1)
00076     if rlist:
00077         key = sys.stdin.read(1)
00078     else:
00079         key = ''
00080 
00081     termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)
00082     return key
00083 
00084 speed = .2
00085 turn = 1
00086 
00087 def vels(speed,turn):
00088     return "currently:\tspeed %s\tturn %s " % (speed,turn)
00089 
00090 if __name__=="__main__":
00091     settings = termios.tcgetattr(sys.stdin)
00092     
00093     rospy.init_node('turtlebot_teleop')
00094     pub = rospy.Publisher('~cmd_vel', Twist)
00095 
00096     x = 0
00097     th = 0
00098     status = 0
00099     count = 0
00100     acc = 0.1
00101     target_speed = 0
00102     target_turn = 0
00103     control_speed = 0
00104     control_turn = 0
00105     try:
00106         print msg
00107         print vels(speed,turn)
00108         while(1):
00109             key = getKey()
00110             if key in moveBindings.keys():
00111                 x = moveBindings[key][0]
00112                 th = moveBindings[key][1]
00113                 count = 0
00114             elif key in speedBindings.keys():
00115                 speed = speed * speedBindings[key][0]
00116                 turn = turn * speedBindings[key][1]
00117                 count = 0
00118 
00119                 print vels(speed,turn)
00120                 if (status == 14):
00121                     print msg
00122                 status = (status + 1) % 15
00123             elif key == ' ' or key == 'k' :
00124                 x = 0
00125                 th = 0
00126                 control_speed = 0
00127                 control_turn = 0
00128             else:
00129                 count = count + 1
00130                 if count > 4:
00131                     x = 0
00132                     th = 0
00133                 if (key == '\x03'):
00134                     break
00135 
00136             target_speed = speed * x
00137             target_turn = turn * th
00138 
00139             if target_speed > control_speed:
00140                 control_speed = min( target_speed, control_speed + 0.02 )
00141             elif target_speed < control_speed:
00142                 control_speed = max( target_speed, control_speed - 0.02 )
00143             else:
00144                 control_speed = target_speed
00145 
00146             if target_turn > control_turn:
00147                 control_turn = min( target_turn, control_turn + 0.1 )
00148             elif target_turn < control_turn:
00149                 control_turn = max( target_turn, control_turn - 0.1 )
00150             else:
00151                 control_turn = target_turn
00152 
00153             twist = Twist()
00154             twist.linear.x = control_speed; twist.linear.y = 0; twist.linear.z = 0
00155             twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = control_turn
00156             pub.publish(twist)
00157 
00158             #print("loop: {0}".format(count))
00159             #print("target: vx: {0}, wz: {1}".format(target_speed, target_turn))
00160             #print("publihsed: vx: {0}, wz: {1}".format(twist.linear.x, twist.angular.z))
00161 
00162     except:
00163         print e
00164 
00165     finally:
00166         twist = Twist()
00167         twist.linear.x = 0; twist.linear.y = 0; twist.linear.z = 0
00168         twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 0
00169         pub.publish(twist)
00170 
00171     termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)


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