3 """ timed_out_and_back.py - Version 0.1 2012-03-24 5 A basic demo of the using odometry data to move the robot along 6 and out-and-back trajectory. 8 Created for the Pi Robot Project: http://www.pirobot.org 9 Copyright (c) 2012 Patrick Goebel. All rights reserved. 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 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: 21 http://www.gnu.org/licenses/gpl.html 27 from geometry_msgs.msg
import Twist
33 rospy.init_node(
'out_and_back', anonymous=
False)
39 self.
cmd_vel = rospy.Publisher(
'/cmd_vel', Twist)
54 linear_duration = goal_distance / linear_speed
63 angular_duration = goal_angle / angular_speed
71 move_cmd.linear.x = linear_speed
74 ticks = int(linear_duration * rate)
76 for t
in range(ticks):
77 self.cmd_vel.publish(move_cmd)
82 self.cmd_vel.publish(move_cmd)
88 move_cmd.angular.z = angular_speed
91 ticks = int(goal_angle * rate)
93 for t
in range(ticks):
94 self.cmd_vel.publish(move_cmd)
99 self.cmd_vel.publish(move_cmd)
103 self.cmd_vel.publish(Twist())
107 rospy.loginfo(
"Stopping the robot...")
108 self.cmd_vel.publish(Twist())
111 if __name__ ==
'__main__':
115 rospy.loginfo(
"Out-and-Back node terminated.")