00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 PKG_NAME = 'art_teleop'
00011
00012
00013 import sys
00014 import math
00015 import Queue
00016
00017 import pilot_cmd
00018 import nav_estop
00019
00020
00021 import roslib;
00022 roslib.load_manifest(PKG_NAME)
00023 import rospy
00024
00025
00026 from art_msgs.msg import ArtVehicle
00027 from art_msgs.msg import Gear
00028 from joy.msg import Joy
00029
00030
00031 from driver_base.msg import SensorLevels
00032 from dynamic_reconfigure.server import Server as ReconfigureServer
00033 import art_teleop.cfg.JoyConfig as JoyConfig
00034
00035 def clamp(minimum, value, maximum):
00036 "constrain value to the range [minimum .. maximum]"
00037 return max(minimum, min(value, maximum))
00038
00039 class JoyNode():
00040 "Vehicle joystick tele-operation node."
00041
00042 def __init__(self):
00043 "JoyNode constructor"
00044
00045
00046 self.run = 3
00047 self.suspend = 12
00048 self.estop = 13
00049
00050
00051 self.steer = 0
00052 self.drive = 4
00053 self.reverse = 6
00054 self.park = 7
00055 self.throttle = 18
00056 self.throttle_start = True
00057 self.brake = 19
00058 self.brake_start = True
00059 self.counter = 0
00060 self.throttleQueue = Queue.Queue()
00061 self.cruiseSwitch = 1
00062 self.cruise = False
00063
00064
00065 rospy.init_node('josh_teleop2')
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
00076 if joy.buttons[self.estop]:
00077 rospy.logwarn('emergency stop')
00078 if self.use_navigator:
00079 self.nav.pause()
00080 else:
00081 self.pilot.halt()
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
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 if joy.buttons[self.cruiseSwitch]:
00101 if self.cruise:
00102 self.cruise = False
00103 else:
00104 self.cruise = True
00105 self.pilot.pstate.target.speed = self.pilot.pstate.current.speed
00106
00107
00108 self.setAngle(joy.axes[self.steer])
00109
00110 if self.cruise:
00111 self.pilot.accelerate(0)
00112
00113 else:
00114
00115
00116
00117 br = (-joy.axes[self.brake] + 1) / 2
00118 th = (-joy.axes[self.throttle] + 1) / 2
00119 rospy.logdebug('joystick brake, throttle: '
00120 + str(br) + ', ' + str(th))
00121
00122 if self.counter < 1:
00123 self.counter = 1
00124 self.throttleQueue.put(th)
00125 else:
00126 initial_th = self.throttleQueue.get()
00127 self.throttleQueue.put(th)
00128
00129
00130
00131
00132
00133 if self.brake_start:
00134 if br == 0.5:
00135 br = 0
00136 else:
00137 self.brake_start = False
00138
00139 if self.throttle_start:
00140 if th == 0.5:
00141 th = 0
00142 else:
00143 self.throttle_start = False
00144
00145
00146 if br > 0:
00147 dv = -br * 3
00148
00149 elif th == 0 and self.pilot.pstate.current.speed > 0:
00150 dv = -.1
00151
00152 elif th > 0:
00153 if initial_th < th:
00154 dv = th
00155 elif initial_th > th:
00156 dv = -.1
00157 elif initial_th == th and self.pilot.pstate.current.acceleration >= 0:
00158 dv = th
00159 elif initial_th == th and self.pilot.pstate.current.acceleration < 0:
00160 dv = -.1
00161 else:
00162 dv = 0
00163 else:
00164 dv = 0
00165
00166
00167 self.pilot.accelerate(dv*10)
00168
00169 if self.nav.is_suspended():
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
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
00196
00197
00198
00199
00200
00201 if self.pilot.pstate.current.speed == 0:
00202 percentage = 1
00203
00204
00205
00206
00207 else:
00208
00209 percentage = (-math.atan2(math.fabs(self.pilot.pstate.current.speed)-3, 1) / 1.5) + 1
00210 turn = turn * percentage * ArtVehicle.max_steer_radians
00211
00212
00213 self.pilot.steer(turn)
00214
00215 def maxFinder(self):
00216 if self.pilot.pstate.current.speed > self.config['limit_forward']:
00217 return self.pilot.state.current
00218 return self.config['limit_forward']
00219
00220 joynode = None
00221
00222
00223 def main():
00224 global joynode
00225 joynode = JoyNode()
00226 rospy.loginfo('joystick vehicle controller starting')
00227 try:
00228 rospy.spin()
00229 except rospy.ROSInterruptException: pass
00230 rospy.loginfo('joystick vehicle controller finished')
00231
00232 if __name__ == '__main__':
00233
00234 sys.exit(main())