00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 PKG_NAME = 'art_teleop'
00011
00012
00013 import sys
00014 import math
00015
00016 import pilot_cmd
00017 import nav_estop
00018
00019
00020 import roslib;
00021 roslib.load_manifest(PKG_NAME)
00022 import rospy
00023
00024
00025 from art_msgs.msg import ArtVehicle
00026 from art_msgs.msg import Gear
00027 from joy.msg import Joy
00028
00029
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
00045 self.run = 3
00046 self.suspend = 12
00047 self.estop = 13
00048
00049
00050 self.steer = 0
00051 self.drive = 4
00052 self.reverse = 6
00053 self.park = 7
00054 self.throttle = 18
00055 self.throttle_start = True
00056 self.brake = 19
00057 self.brake_start = True
00058
00059
00060 rospy.init_node('joy_teleop')
00061 self.pilot = pilot_cmd.PilotCommand()
00062 self.reconf_server = ReconfigureServer(JoyConfig, self.reconfigure)
00063 self.joy = rospy.Subscriber('joy', Joy, self.joyCallback)
00064
00065 def joyCallback(self, joy):
00066 "invoked every time a joystick message arrives"
00067 rospy.logdebug('joystick input:\n' + str(joy))
00068
00069
00070 if joy.buttons[self.estop]:
00071 rospy.logwarn('emergency stop')
00072 if self.use_navigator:
00073 self.nav.pause()
00074 else:
00075 self.pilot.halt()
00076 elif joy.buttons[self.suspend] and self.use_navigator:
00077 rospy.logwarn('suspend autonomous operation')
00078 self.nav.suspend()
00079 elif joy.buttons[self.run] and self.use_navigator:
00080 rospy.logwarn('start autonomous operation')
00081 self.nav.run()
00082
00083
00084 if joy.buttons[self.drive]:
00085 self.pilot.shift(Gear.Drive)
00086 rospy.loginfo('shifting to drive')
00087 elif joy.buttons[self.reverse]:
00088 self.pilot.shift(Gear.Reverse)
00089 rospy.loginfo('shifting to reverse')
00090 elif joy.buttons[self.park]:
00091 self.pilot.shift(Gear.Park)
00092 rospy.loginfo('shifting to park')
00093
00094
00095 self.setAngle(joy.axes[self.steer])
00096
00097
00098
00099 br = joy.axes[self.brake]
00100 th = joy.axes[self.throttle]
00101 rospy.logdebug('joystick brake, throttle: '
00102 + str(br) + ', ' + str(th))
00103
00104
00105
00106 if self.brake_start:
00107 if br == 0.0:
00108 br = 1.0
00109 else:
00110 self.brake_start = False
00111
00112 if self.throttle_start:
00113 if th == 0.0:
00114 th = 1.0
00115 else:
00116 self.throttle_start = False
00117
00118
00119 dv = 0.0
00120 if br < 1.0:
00121 dv = br - 1.0
00122 elif th < 1.0:
00123 dv = 1.0 - th
00124 self.pilot.accelerate(dv * self.config['max_accel'])
00125
00126 if self.nav.is_suspended():
00127 self.pilot.publish()
00128 else:
00129 rospy.logdebug('car running autonomously (command ignored)')
00130
00131 def reconfigure(self, config, level):
00132 "Dynamic reconfigure server callback."
00133 rospy.loginfo('Reconfigure callback, level ' + str(level))
00134 rospy.loginfo('New config ' + str(config))
00135
00136 if level & SensorLevels.RECONFIGURE_CLOSE:
00137
00138 self.use_navigator = config['use_navigator']
00139 rospy.loginfo('use navigator = ' + str(self.use_navigator))
00140
00141 self.nav = nav_estop.EstopNavigator(self.use_navigator)
00142
00143 self.pilot.reconfigure(config['limit_forward'],
00144 config['limit_reverse'])
00145
00146 self.config = config
00147 return config
00148
00149 def setAngle(self, turn):
00150 "set wheel angle"
00151
00152
00153
00154
00155
00156 turn = math.pow(turn, 3) * ArtVehicle.max_steer_radians
00157
00158
00159
00160 self.pilot.steer(turn)
00161
00162 joynode = None
00163
00164 def main():
00165 global joynode
00166 joynode = JoyNode()
00167 rospy.loginfo('joystick vehicle controller starting')
00168 try:
00169 rospy.spin()
00170 except rospy.ROSInterruptException: pass
00171 rospy.loginfo('joystick vehicle controller finished')
00172
00173 if __name__ == '__main__':
00174
00175 sys.exit(main())