Go to the documentation of this file.00001
00002
00003 import threading
00004 from operator import add
00005 import math
00006 import rospy
00007 from sensor_msgs.msg import Joy, CameraInfo, JointState
00008 import actionlib
00009 import control_msgs.msg
00010
00011
00012
00013
00014
00015
00016 from control_msgs.msg import FollowJointTrajectoryAction, FollowJointTrajectoryGoal
00017 from trajectory_msgs.msg import JointTrajectoryPoint
00018
00019 def inRange(val, min, max):
00020 if val < min:
00021 return min
00022 elif val > max:
00023 return max
00024 else:
00025 return val
00026
00027 class TrackballController:
00028 camera_info = None
00029 joint_state = None
00030 current_cursor = (0, 0)
00031 camera_info_lock = threading.Lock()
00032 joint_state_lock = threading.Lock()
00033 msg_sequence = []
00034 def camCB(self, msg):
00035 with self.camera_info_lock:
00036 if self.camera_info == None:
00037
00038 self.current_cursor = (msg.width / 2, msg.height / 2)
00039 self.camera_info = msg
00040 def getCameraInfo(self):
00041 with self.camera_info_lock:
00042 return self.camera_info
00043 def procSequence(self, sequence):
00044 if len(sequence) > 0:
00045
00046 dx = - reduce(add, [msg.axes[0] for msg in sequence])
00047 dy = reduce(add, [msg.axes[1] for msg in sequence])
00048 print (dx, dy)
00049 dpitch_deg = dx / 20.0
00050 dyaw_deg = dy / 20.0
00051 dpitch_rad = dpitch_deg / 180.0 * math.pi
00052 dyaw_rad = dyaw_deg / 180.0 * math.pi
00053 joint_state = self.getJointState()
00054 if not joint_state:
00055 rospy.logwarn("joint_state is not yet available")
00056 return
00057 if (self.pitch_joint_name in joint_state.name and
00058 self.yaw_joint_name in joint_state.name):
00059 pitch_index = joint_state.name.index(self.pitch_joint_name)
00060 yaw_index = joint_state.name.index(self.yaw_joint_name)
00061 current_pitch = joint_state.position[pitch_index]
00062 current_yaw = joint_state.position[yaw_index]
00063 print (current_pitch, current_yaw)
00064 next_pitch = current_pitch + dpitch_rad
00065 next_yaw = current_yaw + dyaw_rad
00066 print (next_pitch, next_yaw)
00067
00068 goal = FollowJointTrajectoryGoal()
00069 goal.trajectory.header.stamp = joint_state.header.stamp
00070 goal.trajectory.joint_names = [self.pitch_joint_name,
00071 self.yaw_joint_name]
00072 p = JointTrajectoryPoint()
00073 p.positions = [next_pitch, next_yaw]
00074 p.time_from_start = rospy.Duration(1.0)
00075 goal.trajectory.points = [p]
00076 self.ac_client.send_goal(goal)
00077
00078 else:
00079 rospy.logwarn("the joint for pitch and yaw cannot be found in joint_states")
00080 return
00081 def jointCB(self, msg):
00082 with self.joint_state_lock:
00083 self.joint_state = msg
00084 def getJointState(self):
00085 with self.joint_state_lock:
00086 return self.joint_state
00087 def joyCB(self, msg):
00088 if (msg.axes[0] == 0.0 and msg.axes[1] == 0.0
00089 and msg.buttons[0] == 0 and msg.buttons[1] == 0
00090 and msg.buttons[2] == 0):
00091
00092 self.procSequence(self.msg_sequence)
00093 self.msg_sequence = []
00094 elif msg.axes[0] == 0.0 and msg.axes[1] == 0.0:
00095 pass
00096 else:
00097 self.msg_sequence.append(msg)
00098 def joyCB2(self, msg):
00099 camera_info = self.getCameraInfo()
00100 if not camera_info:
00101 rospy.logfatal("camera_info is not yet available")
00102 return
00103 (raw_dx, raw_dy) = (msg.axes[0], msg.axes[1])
00104 current_x = self.current_cursor[0]
00105 current_y = self.current_cursor[1]
00106 next_x = inRange(raw_dx + current_x, 0, camera_info.width)
00107 next_y = inRange(-raw_dy + current_y, 0, camera_info.height)
00108 self.current_cursor = (next_x, next_y)
00109 self.publishCursor(msg.header.stamp, self.current_cursor)
00110 def publishCursor(self, stamp, pos):
00111 marker = ImageMarker2()
00112 marker.header.stamp = stamp
00113 marker.type = ImageMarker2.CIRCLE
00114 marker.position.x = pos[0]
00115 marker.position.y = pos[1]
00116 marker.scale = 10
00117 self.marker_pub.publish(marker)
00118 def main(self):
00119 self.joint_trajectory_action_name = rospy.get_param("~joint_trajectory_action", "/head_traj_controller/follow_joint_trajectory")
00120 self.ac_client = actionlib.SimpleActionClient(self.joint_trajectory_action_name,
00121 control_msgs.msg.FollowJointTrajectoryAction)
00122 self.ac_client.wait_for_server()
00123 self.pitch_joint_name = rospy.get_param("~pitch_joint", "head_pan_joint")
00124 self.yaw_joint_name = rospy.get_param("~yaw_joint", "head_tilt_joint")
00125
00126 s = rospy.Subscriber("/trackball_joy", Joy, self.joyCB)
00127 scam = rospy.Subscriber("camera_info", CameraInfo, self.camCB)
00128 sjs = rospy.Subscriber("/joint_states", JointState, self.jointCB)
00129 rospy.spin()
00130
00131
00132
00133 def main():
00134 controller = TrackballController()
00135 controller.main()
00136
00137
00138 if __name__ == "__main__":
00139 rospy.init_node("head_control_by_trackball")
00140 main()
00141
00142