$search
00001 #!/usr/bin/python 00002 # 00003 # send tele-operation commands to pilot from an HKS racing controller 00004 # 00005 # Copyright (C) 2011 Austin Robot Technology 00006 # License: Modified BSD Software License Agreement 00007 # 00008 # $Id: joy_teleop.py 1321 2011-04-19 20:23:37Z jack.oquin $ 00009 00010 PKG_NAME = 'art_teleop' 00011 00012 # standard Python packages 00013 import sys 00014 import math 00015 00016 import pilot_cmd # ART pilot interface 00017 import nav_estop # ART navigator E-stop package 00018 00019 # ROS node setup 00020 import roslib; 00021 roslib.load_manifest(PKG_NAME) 00022 import rospy 00023 00024 # ROS messages 00025 from art_msgs.msg import ArtVehicle 00026 from art_msgs.msg import Gear 00027 from joy.msg import Joy 00028 00029 # dynamic parameter reconfiguration 00030 from driver_base.msg import SensorLevels 00031 from dynamic_reconfigure.server import Server as ReconfigureServer 00032 import art_teleop.cfg.JoyConfig as JoyConfig 00033 00034 def clamp(minimum, value, maximum): 00035 "constrain value to the range [minimum .. maximum]" 00036 return max(minimum, min(value, maximum)) 00037 00038 class JoyNode(): 00039 "Vehicle joystick tele-operation node." 00040 00041 def __init__(self): 00042 "JoyNode constructor" 00043 00044 # estop controls 00045 self.run = 3 # start autonomous run 00046 self.suspend = 12 # suspend autonomous running 00047 self.estop = 13 # emergency stop 00048 00049 # tele-operation controls 00050 self.steer = 0 # steering axis (wheel) 00051 self.drive = 4 # shift to Drive (^) 00052 self.reverse = 6 # shift to Reverse (v) 00053 self.park = 7 # shift to Park 00054 self.throttle = 18 # throttle axis (X) 00055 self.throttle_start = True 00056 self.brake = 19 # brake axis (square) 00057 self.brake_start = True 00058 self.lowincrease_max = 11 # Increase max .5 (R1) 00059 self.highincrease_max = 9 # Increase max 2 (R2) 00060 self.lowdecrease_max = 10 # Decrease max .5 (L1) 00061 self.highdecrease_max = 8 # Decrease max 2 (L2) 00062 00063 00064 # initialize ROS topics 00065 rospy.init_node('josh_teleop') 00066 self.pilot = pilot_cmd.PilotCommand() 00067 self.reconf_server = ReconfigureServer(JoyConfig, self.reconfigure) 00068 self.joy = rospy.Subscriber('joy', Joy, self.joyCallback) 00069 00070 00071 def joyCallback(self, joy): 00072 "invoked every time a joystick message arrives" 00073 rospy.logdebug('joystick input:\n' + str(joy)) 00074 00075 # handle E-stop buttons 00076 if joy.buttons[self.estop]: 00077 rospy.logwarn('emergency stop') 00078 if self.use_navigator: 00079 self.nav.pause() # tell navigator to pause 00080 else: 00081 self.pilot.halt() # halt car using pilot 00082 elif joy.buttons[self.suspend] and self.use_navigator: 00083 rospy.logwarn('suspend autonomous operation') 00084 self.nav.suspend() 00085 elif joy.buttons[self.run] and self.use_navigator: 00086 rospy.logwarn('start autonomous operation') 00087 self.nav.run() 00088 00089 # handle shifter buttons 00090 if joy.buttons[self.drive]: 00091 self.pilot.shift(Gear.Drive) 00092 rospy.loginfo('shifting to drive') 00093 elif joy.buttons[self.reverse]: 00094 self.pilot.shift(Gear.Reverse) 00095 rospy.loginfo('shifting to reverse') 00096 elif joy.buttons[self.park]: 00097 self.pilot.shift(Gear.Park) 00098 rospy.loginfo('shifting to park') 00099 00100 # handle max increases/decreases 00101 if joy.buttons[self.lowincrease_max]: 00102 self.config['limit_forward'] += .5 00103 if joy.buttons[self.highincrease_max]: 00104 self.config['limit_forward'] += 2 00105 if joy.buttons[self.lowdecrease_max]: 00106 self.config['limit_forward'] -= .5 00107 if joy.buttons[self.highdecrease_max]: 00108 self.config['limit_forward'] -= 2 00109 00110 # set steering angle 00111 self.setAngle(joy.axes[self.steer]) 00112 00113 # adjust speed -- the brake and throttle controls both 00114 # return 1.0 when released, -1.0 when completely on 00115 # Convert the -1 to 1 to 0 to 1 in increments of .01 00116 br = (-joy.axes[self.brake] + 1) / 2 00117 th = (-joy.axes[self.throttle] + 1) / 2 00118 rospy.logdebug('joystick brake, throttle: ' 00119 + str(br) + ', ' + str(th)) 00120 00121 # initially the ROS /joy topic sends zeroes for each axis 00122 # until a button press occurs 00123 dv = 0 00124 if self.brake_start: 00125 if br == 0.5: 00126 br = 0 00127 else: 00128 self.brake_start = False 00129 00130 if self.throttle_start: 00131 if th == 0.5: 00132 th = 0 00133 else: 00134 self.throttle_start = False 00135 00136 if br > 0: 00137 dv = -br * 3 00138 00139 elif th == 0 and self.pilot.pstate.current.speed > 0: 00140 dv = -.1 00141 # This error makes the script work, although I'm not sure why. 00142 #self.pilot.pstate.plan.goal_acceleration = -.2 00143 00144 elif th > 0: 00145 if self.pilot.pstate.current.speed < self.config['limit_forward']*th: 00146 dv = self.config['limit_forward']*th - self.pilot.pstate.current.speed 00147 if dv > 1: 00148 dv = 1 + math.pow(dv/self.config['limit_forward'], 2) # varies from 1 to 2 00149 else: 00150 dv = math.pow(dv, 2) # varies from 0 to 1 00151 elif self.pilot.pstate.current.speed > self.config['limit_forward']*th: 00152 dv = -.1 00153 else: 00154 dv = 0 00155 else: 00156 dv = 0 00157 00158 # set acceleration and speed from brake and throttle controls 00159 self.pilot.car_ctl.acceleration = dv * 10 00160 if self.pilot.car_ctl.gear.value == Gear.Drive: 00161 self.pilot.car_ctl.speed = self.config['limit_forward']*th 00162 elif self.pilot.car_ctl.gear.value == Gear.Reverse: 00163 self.pilot.car_ctl.speed = -self.config['limit_reverse']*th 00164 else: # do nothing in Park 00165 self.pilot.car_ctl.speed = 0.0 00166 self.pilot.car_ctl.acceleration = 0.0 00167 00168 00169 if self.nav.is_suspended(): # OK to issue command? 00170 self.pilot.publish() 00171 else: 00172 rospy.logdebug('car running autonomously (command ignored)') 00173 00174 def reconfigure(self, config, level): 00175 "Dynamic reconfigure server callback." 00176 rospy.loginfo('Reconfigure callback, level ' + str(level)) 00177 rospy.loginfo('New config ' + str(config)) 00178 00179 if level & SensorLevels.RECONFIGURE_CLOSE: 00180 # create new EstopNavigator and PilotCommand instances 00181 self.use_navigator = config['use_navigator'] 00182 rospy.loginfo('use navigator = ' + str(self.use_navigator)) 00183 00184 self.nav = nav_estop.EstopNavigator(self.use_navigator) 00185 00186 self.pilot.reconfigure(config['limit_forward'], 00187 config['limit_reverse']) 00188 00189 self.config = config 00190 return config 00191 00192 def setAngle(self, turn): 00193 "set wheel angle" 00194 00195 # Try various functions with domain [-1..1] to improve 00196 # sensitivity while retaining sign. At higher speeds, it may 00197 # make sense to limit the range, avoiding too-sharp turns and 00198 # providing better control sensitivity. 00199 #turn = math.pow(turn, 3) * ArtVehicle.max_steer_radians 00200 #turn = math.tan(turn) * ArtVehicle.max_steer_radians 00201 00202 # currently doesn't work in reverse 00203 if self.pilot.pstate.current.speed == 0: 00204 percentage = 1 00205 else: 00206 percentage = -0.2738*(math.log(math.fabs(self.pilot.pstate.current.speed))) + 0.6937 00207 turn = turn * percentage * ArtVehicle.max_steer_radians 00208 00209 # ensure maximum wheel angle never exceeded 00210 self.pilot.steer(turn) 00211 00212 def maxFinder(self): 00213 if self.pilot.pstate.current.speed > self.config['limit_forward']: 00214 return self.pilot.state.current 00215 return self.config['limit_forward'] 00216 00217 joynode = None 00218 00219 00220 def main(): 00221 global joynode 00222 joynode = JoyNode() 00223 rospy.loginfo('joystick vehicle controller starting') 00224 try: 00225 rospy.spin() 00226 except rospy.ROSInterruptException: pass 00227 rospy.loginfo('joystick vehicle controller finished') 00228 00229 if __name__ == '__main__': 00230 # run main function and exit 00231 sys.exit(main())