• attachment:button_test.py of MichaelFerguson

Attachment 'button_test.py'

Download

   1 #!/usr/bin/env python
   2 
   3 """ Example code of how to access button state. """
   4 
   5 import roslib; roslib.load_manifest('turtlebot_node')
   6 import rospy
   7 
   8 from turtlebot_node.msg import TurtlebotSensorState
   9 from geometry_msgs.msg import Twist
  10 
  11 class ButtonTest:
  12     BUTTON_ID = 2 ** 3  # Using digital input 3
  13 
  14     def buttonCb(self, msg):
  15         # is the button pressed?
  16         if not msg.user_digital_inputs & self.BUTTON_ID:
  17             # debounce it!
  18             if rospy.Time.now() > self.last + rospy.Duration(1.0):
  19                 self.ok_to_move = not self.ok_to_move
  20                 self.last = rospy.Time.now()
  21 
  22     def __init__(self):
  23         # we have to initialize the node, with a name in the ROS graph
  24         rospy.init_node('button_test')
  25 
  26         # subscribe to sensor state
  27         self.ok_to_move = False
  28         self.last = rospy.Time.now()
  29         rospy.Subscriber('/turtlebot_node/sensor_state', TurtlebotSensorState, self.buttonCb)
  30 
  31         # publisher for movement
  32         self.pub = rospy.Publisher('/turtlebot_node/cmd_vel', Twist)
  33 
  34         # move the base if we should
  35         rate = rospy.Rate(10.0)
  36         while not rospy.is_shutdown():
  37             if self.ok_to_move:
  38                 msg = Twist()
  39                 msg.linear.x = 0.1
  40                 self.pub.publish(msg)
  41             else:
  42                 self.pub.publish(Twist())
  43             rate.sleep()
  44 
  45 
  46 if __name__ == "__main__":
  47     bt = ButtonTest()

Attached Files

To refer to attachments on a page, use attachment:filename, as shown below in the list of files. Do NOT use the URL of the [get] link, since this is subject to change and can break easily.
  • [get | view] (2011-09-14 05:28:44, 1.4 KB) [[attachment:button_test.py]]
 All files | Selected Files: delete move to page copy to page

You are not allowed to attach a file to this page.