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 art_msgs.msg import SteeringState
00029 from joy.msg import Joy
00030
00031
00032 from driver_base.msg import SensorLevels
00033 from dynamic_reconfigure.server import Server as ReconfigureServer
00034 import art_teleop.cfg.JoyConfig as JoyConfig
00035
00036 def clamp(minimum, value, maximum):
00037 "constrain value to the range [minimum .. maximum]"
00038 return max(minimum, min(value, maximum))
00039
00040 class JoyNode():
00041 "Vehicle joystick tele-operation node."
00042
00043 def __init__(self):
00044 "JoyNode constructor"
00045
00046
00047 self.run = 3
00048 self.suspend = 12
00049 self.estop = 13
00050
00051
00052 self.steer = 0
00053 self.drive = 4
00054 self.reverse = 6
00055 self.park = 7
00056 self.throttle = 18
00057 self.throttle_start = True
00058 self.brake = 19
00059 self.brake_start = True
00060 self.steeringQueue = Queue.Queue()
00061 self.counter = 0
00062
00063
00064 rospy.init_node('jaime_teleop')
00065 self.pilot = pilot_cmd.PilotCommand()
00066 self.steering = SteeringState()
00067 self.reconf_server = ReconfigureServer(JoyConfig, self.reconfigure)
00068 self.joy = rospy.Subscriber('joy', Joy, self.joyCallback)
00069
00070 def joyCallback(self, joy):
00071 "invoked every time a joystick message arrives"
00072 rospy.logdebug('joystick input:\n' + str(joy))
00073
00074
00075 if joy.buttons[self.estop]:
00076 rospy.logwarn('emergency stop')
00077 if self.use_navigator:
00078 self.nav.pause()
00079 else:
00080 self.pilot.halt()
00081 elif joy.buttons[self.suspend] and self.use_navigator:
00082 rospy.logwarn('suspend autonomous operation')
00083 self.nav.suspend()
00084 elif joy.buttons[self.run] and self.use_navigator:
00085 rospy.logwarn('start autonomous operation')
00086 self.nav.run()
00087
00088
00089 if joy.buttons[self.drive]:
00090 self.pilot.shift(Gear.Drive)
00091 rospy.loginfo('shifting to drive')
00092 elif joy.buttons[self.reverse]:
00093 self.pilot.shift(Gear.Reverse)
00094 rospy.loginfo('shifting to reverse')
00095 elif joy.buttons[self.park]:
00096 self.pilot.shift(Gear.Park)
00097 rospy.loginfo('shifting to park')
00098
00099
00100 self.setAngle(joy.axes[self.steer])
00101
00102
00103
00104 br = joy.axes[self.brake]
00105 th = joy.axes[self.throttle]
00106 rospy.logdebug('joystick brake, throttle: '
00107 + str(br) + ', ' + str(th))
00108
00109
00110
00111 if self.brake_start:
00112 if br == 0.0:
00113 br = 1.0
00114 else:
00115 self.brake_start = False
00116
00117 if self.throttle_start:
00118 if th == 0.0:
00119 th = 1.0
00120 else:
00121 self.throttle_start = False
00122
00123
00124 dv = 0.0
00125 if br < 1.0:
00126 dv = br - 1.0
00127 elif th < 1.0:
00128 dv = 1.0 - th
00129 self.pilot.accelerate(dv * self.config['max_accel'])
00130
00131 if self.nav.is_suspended():
00132 self.pilot.publish()
00133 else:
00134 rospy.logdebug('car running autonomously (command ignored)')
00135
00136 def reconfigure(self, config, level):
00137 "Dynamic reconfigure server callback."
00138 rospy.loginfo('Reconfigure callback, level ' + str(level))
00139 rospy.loginfo('New config ' + str(config))
00140
00141 if level & SensorLevels.RECONFIGURE_CLOSE:
00142
00143 self.use_navigator = config['use_navigator']
00144 rospy.loginfo('use navigator = ' + str(self.use_navigator))
00145
00146 self.nav = nav_estop.EstopNavigator(self.use_navigator)
00147
00148 self.pilot.reconfigure(config['limit_forward'],
00149 config['limit_reverse'])
00150
00151 self.config = config
00152 return config
00153
00154 def setAngle(self, turn):
00155 "set wheel angle"
00156
00157
00158
00159
00160
00161
00162
00163
00164 if(self.counter < 5):
00165 self.counter +=1
00166 self.steeringQueue.put(self.steering.angle/180)
00167 else:
00168
00169 oldVal = self.steeringQueue.get()
00170
00171 currentRate = (self.steering.angle/180 - oldVal)/.25
00172 limit = 2.0361 * math.pow(.72898, self.pilot.pstate.current.speed)
00173 rospy.logwarn(str(currentRate) + ' ' + str(limit))
00174
00175
00176
00177 if(math.fabs(currentRate > limit)):
00178 rospy.logwarn('Success')
00179 turn = limit*.25 + oldVal
00180
00181
00182 self.steeringQueue.put(turn)
00183
00184
00185
00186 self.pilot.steer(turn)
00187
00188 joynode = None
00189
00190 def main():
00191 global joynode
00192 joynode = JoyNode()
00193 rospy.loginfo('joystick vehicle controller starting')
00194 try:
00195 rospy.spin()
00196 except rospy.ROSInterruptException: pass
00197 rospy.loginfo('joystick vehicle controller finished')
00198
00199 if __name__ == '__main__':
00200
00201 sys.exit(main())