Go to the documentation of this file.00001
00002
00003 """ Example code of how to move a robot around the shape of a square. """
00004
00005
00006 import roslib; roslib.load_manifest('mini_max_tutorials')
00007 import rospy
00008
00009
00010
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
00019 rospy.on_shutdown(self.cleanup)
00020
00021
00022 self.pub = rospy.Publisher('cmd_vel', Twist)
00023
00024 rospy.sleep(1)
00025
00026
00027 r = rospy.Rate(5.0)
00028
00029
00030 while not rospy.is_shutdown():
00031
00032 twist = Twist()
00033 twist.linear.x = 0.15
00034 for i in range(10):
00035 self.pub.publish(twist)
00036 r.sleep()
00037
00038 twist = Twist()
00039 twist.angular.z = 1.57/2
00040 for i in range(10):
00041 self.pub.publish(twist)
00042 r.sleep()
00043
00044 def cleanup(self):
00045
00046 twist = Twist()
00047 self.pub.publish(twist)
00048
00049 if __name__=="__main__":
00050 rospy.init_node('square')
00051 square()
00052