00001 import rospy
00002
00003 import actionlib
00004 from jsk_teleop_joy.joy_plugin import JSKJoyPlugin
00005 from drc_task_common.srv import StringRequest, StringRequestResponse
00006
00007 try:
00008 imp.find_module("std_msgs")
00009 except:
00010 import roslib; roslib.load_manifest('jsk_teleop_joy')
00011
00012
00013 from std_msgs.msg import String, Float64, Bool, Float32
00014 from std_srvs.srv import Empty, EmptyResponse
00015 from geometry_msgs.msg import PoseStamped
00016 import xml.etree.ElementTree as ET
00017 import os, sys, time, numpy
00018
00019 class VehicleJoyController(JSKJoyPlugin):
00020 def __init__(self, name, args):
00021 JSKJoyPlugin.__init__(self, name, args)
00022 self.command_states = {
00023 "handle": HandleCommandState("handle", Float64, Float32, "drive/controller/goal_handle_angle"),
00024 "accel": VehicleCommandState("accel", Float64, Float32, "drive/controller/step"),
00025 "brake": VehicleCommandState("brake", Float64, None, None),
00026 "neck_y": VehicleCommandState("neck_y", Float64, Float32, "drive/controller/neck_y_angle"),
00027 "neck_p": VehicleCommandState("neck_p", Float64, Float32, "drive/controller/neck_p_angle")
00028 }
00029 self.synchronizeAllCommand()
00030 self.execute_flag = False
00031 print >> sys.stderr, "Joystick initialization is finished"
00032 self.initialize_service = rospy.Service('drive/operation/initialize', Empty, self.initializeServiceCallback)
00033 self.synchronize_service = rospy.Service('drive/operation/synchronize', StringRequest, self.synchronizeServiceCallback)
00034 self.subscriber = rospy.Subscriber('drive/execute_flag', Bool, self.executeFlagCallback)
00035
00036 def joyCB(self, status, history):
00037 latest = history.latest()
00038 handle_resolution = 0.025
00039 neck_y_resolution = 0.1
00040 neck_y_angle_max = 35.0
00041 neck_y_angle_min = -35.0
00042 neck_p_resolution = 0.1
00043 neck_p_angle_max = 35.0
00044 neck_p_angle_min = -35.0
00045 max_accel_resolution = 0.05
00046 max_brake_resolution = 1.0
00047
00048 if not self.execute_flag or not latest:
00049 return
00050
00051
00052 if status.left_analog_x:
00053 self.command_states["handle"].command = self.command_states["handle"].command + handle_resolution * status.left_analog_x
00054
00055 if status.left:
00056 self.command_states["neck_y"].command = self.commandJointAngle(self.command_states["neck_y"].command, neck_y_resolution, neck_y_angle_max, neck_y_angle_min)
00057 elif status.right:
00058 self.command_states["neck_y"].command = self.commandJointAngle(self.command_states["neck_y"].command, -neck_y_resolution, neck_y_angle_max, neck_y_angle_min)
00059
00060 if status.up:
00061 self.command_states["neck_p"].command = self.commandJointAngle(self.command_states["neck_p"].command, -neck_p_resolution, neck_p_angle_max, neck_p_angle_min)
00062 elif status.down:
00063 self.command_states["neck_p"].command = self.commandJointAngle(self.command_states["neck_p"].command, neck_p_resolution, neck_p_angle_max, neck_p_angle_min)
00064
00065 if status.right_analog_y:
00066 self.command_states["accel"].command = max(status.right_analog_y, 0.0)
00067 if status.right_analog_y < -0.5:
00068 self.command_states["brake"].command = 1.0
00069 else:
00070 self.command_states["brake"].command = 0.0
00071 else:
00072 self.command_states["accel"].command = 0.0
00073 self.command_states["brake"].command = 0.0
00074
00075 for command in self.command_states.values():
00076 command.publishCommand()
00077
00078 def commandJointAngle(self, current_value, resolution, max_value, min_value):
00079 next_value = current_value + resolution
00080 if next_value > max_value:
00081 next_value = max_value
00082 elif next_value < min_value:
00083 next_value = min_value
00084 return next_value
00085
00086 def initializeAllCommand(self):
00087 for command in self.command_states.values():
00088 command.initialize()
00089
00090 def synchronizeCommand(self, key):
00091 print >> sys.stderr, "Sync " + key
00092 self.command_states[key].synchronize()
00093
00094 def synchronizeAllCommand(self):
00095 for key in self.command_states.keys():
00096 self.synchronizeCommand(key)
00097
00098 def executeFlagCallback(self, msg):
00099 self.execute_flag = msg.data
00100 print >> sys.stderr, "set execute_flag as " + str(self.execute_flag)
00101
00102 def initializeServiceCallback(self, req):
00103 print >> sys.stderr, "initialize vehicle joy"
00104 self.initializeAllCommand()
00105 return EmptyResponse()
00106
00107 def synchronizeServiceCallback(self, req):
00108 key = req.data.lower()
00109 if key in self.command_states:
00110 self.synchronizeCommand(key)
00111 elif key == "neck":
00112 self.synchronizeCommand("neck_p")
00113 self.synchronizeCommand("neck_y")
00114 elif key == "all":
00115 self.synchronizeAllCommand()
00116 else:
00117 print >> sys.stderr, "Invalid key"
00118 return StringRequestResponse()
00119
00120 class VehicleCommandState():
00121 def __init__(self, command_name, pub_type, sub_type, robot_topic):
00122 self.command_name = command_name
00123 self.pub_type = pub_type
00124 self.sub_type = sub_type
00125 self.wait_for_message_flag = True
00126 self.robot_topic = robot_topic
00127 self.publisher = rospy.Publisher("drive/operation/" + self.command_name + "_cmd_fast", self.pub_type)
00128 if robot_topic and self.sub_type:
00129 self.subscriber = rospy.Subscriber(robot_topic, self.sub_type, self.callback)
00130 else:
00131 self.subscriber = None
00132 self.initialize()
00133 def callback(self, msg):
00134 self.robot_value = msg.data
00135 def initialize(self):
00136 self.command = 0.0
00137 self.robot_value = 0.0
00138 def synchronize(self, timeout = 1.0):
00139 if self.robot_topic != None and self.sub_type != None:
00140 try:
00141 if self.wait_for_message_flag:
00142 rospy.wait_for_message(self.robot_topic, self.sub_type, timeout)
00143 self.wait_for_message_flag = False
00144 print >> sys.stderr, "Sync with " + self.robot_topic
00145 print "%s -> %s" % (str(self.command), str(self.robot_value))
00146 self.command = self.robot_value
00147 except rospy.ROSException, e:
00148 print >> sys.stderr, "Cannot subscribe " + self.robot_topic
00149 def publishCommand(self):
00150 pub_msg = self.pub_type(data = self.command)
00151 self.publisher.publish(pub_msg)
00152
00153 class HandleCommandState(VehicleCommandState):
00154 def callback(self, msg):
00155 self.robot_value = msg.data * numpy.pi / 180.0
00156
00157
00158