00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 import roslib
00031 roslib.load_manifest('teleop_microscribe')
00032 import rospy
00033 from joy.msg import *
00034 from pr2_controllers_msgs.msg import *
00035 from trajectory_msgs.msg import *
00036 from pr2_cockpit_msgs.srv import *
00037
00038 rospy.init_node('head_pedals')
00039
00040 MIN_PAN = -2.7
00041 MAX_PAN = 2.7
00042 MIN_TILT = -0.4
00043 MAX_TILT = 1.4
00044
00045 class PedalHead:
00046
00047 def __init__(self, pedal_topic):
00048 self.pan = 0.0
00049 self.tilt = 0.0
00050 self.enabled = True
00051
00052 self.last_pedal_time = None
00053
00054 self.pub_head = rospy.Publisher('head_traj_controller/command', JointTrajectory)
00055 rospy.Service('~enable', Enable, self.enable)
00056 rospy.Subscriber(pedal_topic, Joy, self.pedal_cb)
00057
00058 def enable(self, req):
00059 self.enabled = req.enable
00060 return EnableResponse(True, "")
00061
00062 def pedal_cb(self, msg):
00063 now = rospy.get_rostime()
00064 if not self.last_pedal_time or (now - self.last_pedal_time) > rospy.Duration(5.0) :
00065 self.last_pedal_time = now
00066 return
00067 dt = now - self.last_pedal_time
00068 self.last_pedal_time = now
00069
00070 PAN = 2
00071 DOWN = 1
00072 UP = 0
00073
00074
00075 up_command = -(msg.axes[UP] - 1.0) / 2.
00076 down_command = -(msg.axes[DOWN] - 1.0) / 2.
00077
00078 pan_vel = -msg.axes[PAN]
00079 tilt_vel = (down_command - up_command)
00080 horizon = 0.2
00081
00082 if self.enabled:
00083 self.pan += pan_vel * dt.to_sec()
00084 self.tilt += tilt_vel * dt.to_sec()
00085
00086 self.pan = max(MIN_PAN, min(self.pan, MAX_PAN))
00087 self.tilt = max(MIN_TILT, min(self.tilt, MAX_TILT))
00088
00089 traj = JointTrajectory()
00090 traj.header.stamp = rospy.get_rostime() + rospy.Duration(0.01)
00091 traj.joint_names = ['head_pan_joint', 'head_tilt_joint']
00092 traj.points = [
00093 JointTrajectoryPoint(positions = [self.pan + pan_vel * horizon,
00094 self.tilt + tilt_vel * horizon],
00095 velocities = [pan_vel, tilt_vel],
00096 time_from_start = rospy.Duration(horizon))]
00097 self.pub_head.publish(traj)
00098
00099 def main():
00100 h = PedalHead('l_rudder_pedals')
00101 rospy.spin()
00102
00103
00104 if __name__ == '__main__':
00105 main()