Go to the documentation of this file.00001
00002
00003 """ timed_out_and_back.py - Version 0.1 2012-03-24
00004
00005 A basic demo of the using odometry data to move the robot along
00006 and out-and-back trajectory.
00007
00008 Created for the Pi Robot Project: http://www.pirobot.org
00009 Copyright (c) 2012 Patrick Goebel. All rights reserved.
00010
00011 This program is free software; you can redistribute it and/or modify
00012 it under the terms of the GNU General Public License as published by
00013 the Free Software Foundation; either version 2 of the License, or
00014 (at your option) any later version.5
00015
00016 This program is distributed in the hope that it will be useful,
00017 but WITHOUT ANY WARRANTY; without even the implied warranty of
00018 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
00019 GNU General Public License for more details at:
00020
00021 http://www.gnu.org/licenses/gpl.html
00022
00023 """
00024
00025
00026 import rospy
00027 from geometry_msgs.msg import Twist
00028 from math import pi
00029
00030 class OutAndBack():
00031 def __init__(self):
00032
00033 rospy.init_node('out_and_back', anonymous=False)
00034
00035
00036 rospy.on_shutdown(self.shutdown)
00037
00038
00039 self.cmd_vel = rospy.Publisher('/cmd_vel', Twist)
00040
00041
00042 rate = 50
00043
00044
00045 r = rospy.Rate(rate)
00046
00047
00048 linear_speed = 0.2
00049
00050
00051 goal_distance = 1.0
00052
00053
00054 linear_duration = goal_distance / linear_speed
00055
00056
00057 angular_speed = 1.0
00058
00059
00060 goal_angle = pi
00061
00062
00063 angular_duration = goal_angle / angular_speed
00064
00065
00066 for i in range(2):
00067
00068 move_cmd = Twist()
00069
00070
00071 move_cmd.linear.x = linear_speed
00072
00073
00074 ticks = int(linear_duration * rate)
00075
00076 for t in range(ticks):
00077 self.cmd_vel.publish(move_cmd)
00078 r.sleep()
00079
00080
00081 move_cmd = Twist()
00082 self.cmd_vel.publish(move_cmd)
00083 rospy.sleep(1)
00084
00085
00086
00087
00088 move_cmd.angular.z = angular_speed
00089
00090
00091 ticks = int(goal_angle * rate)
00092
00093 for t in range(ticks):
00094 self.cmd_vel.publish(move_cmd)
00095 r.sleep()
00096
00097
00098 move_cmd = Twist()
00099 self.cmd_vel.publish(move_cmd)
00100 rospy.sleep(1)
00101
00102
00103 self.cmd_vel.publish(Twist())
00104
00105 def shutdown(self):
00106
00107 rospy.loginfo("Stopping the robot...")
00108 self.cmd_vel.publish(Twist())
00109 rospy.sleep(1)
00110
00111 if __name__ == '__main__':
00112 try:
00113 OutAndBack()
00114 except:
00115 rospy.loginfo("Out-and-Back node terminated.")