square.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 """ Example code of how to move a robot around the shape of a square. """
00004 
00005 # We always import roslib, and load the manifest to handle dependencies
00006 import roslib; roslib.load_manifest('mini_max_tutorials')
00007 import rospy
00008 
00009 # recall: robots generally take base movement commands on a topic 
00010 #  called "cmd_vel" using a message type "geometry_msgs/Twist"
00011 from geometry_msgs.msg import Twist
00012 
00013 class square:
00014     """ This example is in the form of a class. """
00015 
00016     def __init__(self):
00017         """ This is the constructor of our class. """
00018         # register this function to be called on shutdown
00019         rospy.on_shutdown(self.cleanup)
00020 
00021         # publish to cmd_vel
00022         self.pub = rospy.Publisher('cmd_vel', Twist)
00023         # give our node/publisher a bit of time to connect
00024         rospy.sleep(1)
00025 
00026         # use a rate to make sure the bot keeps moving
00027         r = rospy.Rate(5.0)
00028 
00029         # go forever!
00030         while not rospy.is_shutdown():
00031             # create a Twist message, fill it in to drive forward
00032             twist = Twist()
00033             twist.linear.x = 0.15
00034             for i in range(10):         # 10*5hz = 2sec
00035                 self.pub.publish(twist)
00036                 r.sleep()
00037             # create a twist message, fill it in to turn
00038             twist = Twist()
00039             twist.angular.z = 1.57/2    # 45 deg/s * 2sec = 90 degrees
00040             for i in range(10):         # 10*5hz = 2sec
00041                 self.pub.publish(twist)
00042                 r.sleep()
00043 
00044     def cleanup(self):
00045         # stop the robot!
00046         twist = Twist()
00047         self.pub.publish(twist)
00048 
00049 if __name__=="__main__":
00050     rospy.init_node('square')
00051     square()
00052 


mini_max_tutorials
Author(s): Michael Ferguson
autogenerated on Mon Oct 6 2014 02:23:05