trackpoint_status.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import rospy
00004 import roslib
00005 
00006 class TrackpointStatus():
00007     def __init__(self, msg):
00008         if msg.buttons[0] == 1:
00009             self.left = True
00010         else:
00011             self.left = False
00012         if msg.buttons[1] == 1:
00013             self.middle = True
00014         else:
00015             self.middle = False
00016         if msg.buttons[2] == 1:
00017             self.right = True
00018         else:
00019             self.right = False
00020         self.x = msg.axes[0]
00021         self.y = msg.axes[1]
00022 
00023 
00024 import pprint
00025 
00026 def joyCB(msg):
00027     status = TrackpointStatus(msg)
00028     pprint.PrettyPrinter().pprint(status.__dict__)
00029 
00030 
00031 def main():
00032     import roslib
00033     import rospy
00034     from sensor_msgs.msg import Joy
00035 
00036     rospy.sleep(1)
00037     rospy.init_node('trackpoint_controller')
00038     s = rospy.Subscriber('/trackpoint/joy', Joy, joyCB)
00039   
00040     rospy.spin()
00041   
00042 if __name__ == '__main__':
00043     main()
00044 
00045 


jsk_teleop_joy
Author(s): Ryohei Ueda
autogenerated on Mon Oct 6 2014 01:11:11