periodic_drive.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright (c) 2008, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 #     * Redistributions of source code must retain the above copyright
00010 #       notice, this list of conditions and the following disclaimer.
00011 #     * Redistributions in binary form must reproduce the above copyright
00012 #       notice, this list of conditions and the following disclaimer in the
00013 #       documentation and/or other materials provided with the distribution.
00014 #     * Neither the name of the Willow Garage, Inc. nor the names of its
00015 #       contributors may be used to endorse or promote products derived from
00016 #       this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028 # POSSIBILITY OF SUCH DAMAGE.
00029 
00030 # Author: Stuart Glaser
00031 import time
00032 import math
00033 import random
00034 random.seed()
00035 import roslib
00036 roslib.load_manifest('life_test')
00037 import rospy
00038 from std_msgs.msg import Float64
00039 
00040 from sensor_msgs.msg import JointState
00041 
00042 
00043 STRAIGHT = 0.82 + math.pi / 2
00044 ROTATION_JOINT = 'fl_caster_rotation_joint'
00045 SPEED = 10.0
00046 PERIOD = 15.0
00047 PI = 3.14159
00048 
00049 class LastMessage(object):
00050     def __init__(self, topic, msg_type):
00051         self.msg = None
00052         rospy.Subscriber(topic, msg_type, self.callback)
00053 
00054     def last(self):
00055         return self.msg
00056 
00057     def callback(self, msg):
00058         self.msg = msg
00059 
00060 def main():
00061     angle = STRAIGHT
00062     speed = -SPEED
00063     last_time = 0
00064     rospy.init_node('caster_cmder')
00065     last_state = LastMessage('joint_states', JointState)
00066     pub_steer = rospy.Publisher("caster_fl/steer", Float64)
00067     pub_drive = rospy.Publisher("caster_fl/drive", Float64)
00068     pub_steer.publish(Float64(0.0))
00069     pub_drive.publish(Float64(0.0))
00070     my_rate = rospy.Rate(100)
00071 
00072     rospy.loginfo("Waiting for a joint_state message...")
00073     while not last_state.msg and not rospy.is_shutdown(): my_rate.sleep()
00074     while not rospy.is_shutdown():
00075         my_rate.sleep()
00076         jnt_states = last_state.last()
00077         rotation_idx = -1
00078         for i, name in enumerate(jnt_states.name):
00079             if name == ROTATION_JOINT:
00080                 rotation_idx = i
00081                 break
00082         if rotation_idx < 0:
00083             rospy.logwarn("The %s joint was not found in the mechanism state" % ROTATION_JOINT)
00084             continue
00085 
00086         # Steers the caster to be straight
00087         angle_diff = angle - jnt_states.position[rotation_idx]
00088         pub_steer.publish(Float64(6.0 * angle_diff))
00089 
00090         # Drive
00091         if abs(angle_diff) < 0.05:
00092             pub_drive.publish(Float64(speed))
00093         else:
00094             pub_drive.publish(Float64(0.0))
00095 
00096         if rospy.get_time() - last_time > (PERIOD / 2):
00097             speed *= -1
00098             if(random.random() > 0.25): # Rotate caster
00099                 rospy.loginfo('Rotating caster')
00100                 pub_drive.publish(Float64(speed))
00101                 time.sleep(0.75) # Allow for rotation
00102                 speed *= -1
00103                 if angle > PI:
00104                     angle -= PI
00105                 else:
00106                     angle += PI
00107             last_time = rospy.get_time()
00108 
00109 
00110 if __name__ == '__main__':
00111     main()


life_test
Author(s): Kevin Watts
autogenerated on Sat Dec 28 2013 17:56:37