Go to the documentation of this file.00001
00002
00003 import os
00004
00005 import rospy
00006 import roslib
00007 from joy_controller import JoyController
00008 import std_msgs
00009
00010 roslib.load_manifest("jsk_pr2_startup")
00011
00012 class ImageSnapshotJoy(JoyController):
00013 def __init__(self):
00014 self._head_pub = rospy.Publisher('/head_snap/snapshot', std_msgs.msg.Empty)
00015 self._lhand_pub = rospy.Publisher('/lhand_snap/snapshot', std_msgs.msg.Empty)
00016 self._rhand_pub = rospy.Publisher('/rhand_snap/snapshot', std_msgs.msg.Empty)
00017 self._head_pub_button = rospy.get_param('~head_pub_button', 0)
00018 self._lhand_pub_button = rospy.get_param('~lhand_pub_button', 1)
00019 self._rhand_pub_button = rospy.get_param('~rhand_pub_button', 2)
00020 JoyController.__init__(self)
00021
00022 def joy_execute(self):
00023 if self.check_pushed(self._head_pub_button):
00024 self._head_pub.publish(std_msgs.msg.Empty())
00025 if self.check_pushed(self._lhand_pub_button):
00026 self._lhand_pub.publish(std_msgs.msg.Empty())
00027 if self.check_pushed(self._rhand_pub_button):
00028 self._rhand_pub.publish(std_msgs.msg.Empty())
00029
00030 if __name__ =='__main__':
00031 rospy.init_node('image_snapshot_joy', anonymous=True)
00032 image_snapshot_joy = ImageSnapshotJoy()
00033