timed_out_and_back.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 """ timed_out_and_back.py - Version 0.1 2012-03-24
4 
5  A basic demo of the using odometry data to move the robot along
6  and out-and-back trajectory.
7 
8  Created for the Pi Robot Project: http://www.pirobot.org
9  Copyright (c) 2012 Patrick Goebel. All rights reserved.
10 
11  This program is free software; you can redistribute it and/or modify
12  it under the terms of the GNU General Public License as published by
13  the Free Software Foundation; either version 2 of the License, or
14  (at your option) any later version.5
15 
16  This program is distributed in the hope that it will be useful,
17  but WITHOUT ANY WARRANTY; without even the implied warranty of
18  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
19  GNU General Public License for more details at:
20 
21  http://www.gnu.org/licenses/gpl.html
22 
23 """
24 
25 #import roslib; roslib.load_manifest('rbx1_nav')
26 import rospy
27 from geometry_msgs.msg import Twist
28 from math import pi
29 
30 class OutAndBack():
31  def __init__(self):
32  # Give the node a name
33  rospy.init_node('out_and_back', anonymous=False)
34 
35  # Set rospy to exectute a shutdown function when exiting
36  rospy.on_shutdown(self.shutdown)
37 
38  # Publisher to control the robot's speed
39  self.cmd_vel = rospy.Publisher('/cmd_vel', Twist)
40 
41  # How fast will we update the robot's movement?
42  rate = 50
43 
44  # Set the equivalent ROS rate variable
45  r = rospy.Rate(rate)
46 
47  # Set the forward linear speed to 0.2 meters per second
48  linear_speed = 0.2
49 
50  # Set the travel distance to 1.0 meters
51  goal_distance = 1.0
52 
53  # How long should it take us to get there?
54  linear_duration = goal_distance / linear_speed
55 
56  # Set the rotation speed to 1.0 radians per second
57  angular_speed = 1.0
58 
59  # Set the rotation angle to Pi radians (180 degrees)
60  goal_angle = pi
61 
62  # How long should it take to rotate?
63  angular_duration = goal_angle / angular_speed
64 
65  # Loop through the two legs of the trip
66  for i in range(2):
67  # Initialize the movement command
68  move_cmd = Twist()
69 
70  # Set the forward speed
71  move_cmd.linear.x = linear_speed
72 
73  # Move forward for a time to go the desired distance
74  ticks = int(linear_duration * rate)
75 
76  for t in range(ticks):
77  self.cmd_vel.publish(move_cmd)
78  r.sleep()
79 
80  # Stop the robot before the rotation
81  move_cmd = Twist()
82  self.cmd_vel.publish(move_cmd)
83  rospy.sleep(1)
84 
85  # Now rotate left roughly 180 degrees
86 
87  # Set the angular speed
88  move_cmd.angular.z = angular_speed
89 
90  # Rotate for a time to go 180 degrees
91  ticks = int(goal_angle * rate)
92 
93  for t in range(ticks):
94  self.cmd_vel.publish(move_cmd)
95  r.sleep()
96 
97  # Stop the robot before the next leg
98  move_cmd = Twist()
99  self.cmd_vel.publish(move_cmd)
100  rospy.sleep(1)
101 
102  # Stop the robot
103  self.cmd_vel.publish(Twist())
104 
105  def shutdown(self):
106  # Always stop the robot when shutting down the node.
107  rospy.loginfo("Stopping the robot...")
108  self.cmd_vel.publish(Twist())
109  rospy.sleep(1)
110 
111 if __name__ == '__main__':
112  try:
113  OutAndBack()
114  except:
115  rospy.loginfo("Out-and-Back node terminated.")


oculusprime
Author(s): Colin Adamson
autogenerated on Wed Mar 10 2021 03:14:59