Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 PKG_NAME = 'ackermann_hks'
00012
00013
00014 import sys
00015 import math
00016 import Queue
00017
00018 import pilot_cmd
00019
00020
00021 import roslib;
00022 roslib.load_manifest(PKG_NAME)
00023 import rospy
00024
00025
00026 from art_msgs.msg import Gear
00027 from sensor_msgs.msg import Joy
00028
00029
00030 from driver_base.msg import SensorLevels
00031 from dynamic_reconfigure.server import Server as ReconfigureServer
00032 import ackermann_hks.cfg.HKSConfig as Config
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
00045 self.estop = 13
00046
00047
00048 self.steer = 0
00049 self.drive = 4
00050 self.reverse = 6
00051 self.park = 7
00052 self.throttle = 18
00053 self.throttle_start = True
00054 self.brake = 19
00055 self.brake_start = True
00056 self.counter = 0
00057 self.throttleQueue = Queue.Queue()
00058 self.cruiseSwitch = 1
00059 self.cruise = False
00060
00061
00062 rospy.init_node('hks_teleop')
00063 self.pilot = pilot_cmd.PilotCommand()
00064 self.reconf_server = ReconfigureServer(Config, self.reconfigure)
00065 self.joy = rospy.Subscriber('joy', Joy, self.joyCallback)
00066
00067
00068 def joyCallback(self, joy):
00069 "invoked every time a joystick message arrives"
00070 rospy.logdebug('joystick input:\n' + str(joy))
00071
00072
00073 if joy.buttons[self.estop]:
00074 rospy.logwarn('emergency stop')
00075 self.pilot.halt()
00076
00077
00078 if joy.buttons[self.drive]:
00079 self.pilot.shift(Gear.Drive)
00080 rospy.loginfo('shifting to drive')
00081 elif joy.buttons[self.reverse]:
00082 self.pilot.shift(Gear.Reverse)
00083 rospy.loginfo('shifting to reverse')
00084 elif joy.buttons[self.park]:
00085 self.pilot.shift(Gear.Park)
00086 rospy.loginfo('shifting to park')
00087
00088 if joy.buttons[self.cruiseSwitch]:
00089 if self.cruise:
00090 self.cruise = False
00091 else:
00092 self.cruise = True
00093 self.pilot.pstate.target.speed = self.pilot.pstate.current.speed
00094
00095
00096 self.setAngle(joy.axes[self.steer])
00097
00098 if self.cruise:
00099 self.pilot.accelerate(0)
00100
00101 else:
00102
00103
00104
00105 br = (-joy.axes[self.brake] + 1) / 2
00106 th = (-joy.axes[self.throttle] + 1) / 2
00107 rospy.logdebug('joystick brake, throttle: '
00108 + str(br) + ', ' + str(th))
00109
00110 if self.counter < 1:
00111 self.counter = 1
00112 self.throttleQueue.put(th)
00113 else:
00114 initial_th = self.throttleQueue.get()
00115 self.throttleQueue.put(th)
00116
00117
00118
00119
00120
00121 if self.brake_start:
00122 if br == 0.5:
00123 br = 0
00124 else:
00125 self.brake_start = False
00126
00127 if self.throttle_start:
00128 if th == 0.5:
00129 th = 0
00130 else:
00131 self.throttle_start = False
00132
00133
00134 if br > 0:
00135 dv = -br * 3
00136
00137 elif th == 0 and self.pilot.pstate.current.speed > 0:
00138 dv = -.1
00139
00140 elif th > 0:
00141 if initial_th < th:
00142 dv = th
00143 elif initial_th > th:
00144 dv = -.1
00145 elif initial_th == th and self.pilot.pstate.current.acceleration >= 0:
00146 dv = th
00147 elif initial_th == th and self.pilot.pstate.current.acceleration < 0:
00148 dv = -.1
00149 else:
00150 dv = 0
00151 else:
00152 dv = 0
00153
00154
00155 self.pilot.accelerate(dv*10)
00156
00157 if self.nav.is_suspended():
00158 self.pilot.publish()
00159 else:
00160 rospy.logdebug('car running autonomously (command ignored)')
00161
00162 def reconfigure(self, config, level):
00163 "Dynamic reconfigure server callback."
00164 rospy.loginfo('Reconfigure callback, level ' + str(level))
00165 rospy.loginfo('New config ' + str(config))
00166 self.pilot.reconfigure(config['limit_forward'],
00167 config['limit_reverse'])
00168 self.config = config
00169 return config
00170
00171 def setAngle(self, turn):
00172 "set wheel angle"
00173
00174
00175
00176
00177
00178
00179
00180 if self.pilot.pstate.current.speed == 0:
00181 percentage = 1
00182
00183
00184
00185
00186 else:
00187
00188 percentage = (-math.atan2(math.fabs(self.pilot.pstate.current.speed)-3, 1) / 1.5) + 1
00189 turn = turn * percentage * self.config.max_steering
00190
00191
00192 self.pilot.steer(turn)
00193
00194 def maxFinder(self):
00195 if self.pilot.pstate.current.speed > self.config['limit_forward']:
00196 return self.pilot.state.current
00197 return self.config['limit_forward']
00198
00199 joynode = None
00200
00201
00202 def main():
00203 global joynode
00204 joynode = JoyNode()
00205 rospy.loginfo('joystick vehicle controller starting')
00206 try:
00207 rospy.spin()
00208 except rospy.ROSInterruptException: pass
00209 rospy.loginfo('joystick vehicle controller finished')
00210
00211 if __name__ == '__main__':
00212
00213 sys.exit(main())