$search
00001 #!/usr/bin/python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2008, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of the Willow Garage nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 00033 # 00034 00035 # Author: Wim Meeussen 00036 00037 import roslib; roslib.load_manifest('pr2_base_recovery') 00038 import rospy 00039 import random 00040 import PyKDL 00041 from math import fabs 00042 from threading import Lock 00043 from geometry_msgs.msg import Twist 00044 from pr2_mechanism_controllers.msg import Odometer, BaseControllerState2 00045 from threading import Thread 00046 00047 DIST_THRESHOLD = 0.0001 00048 EFF_THRESHOLD = 3.0 00049 BASE_THRESHOLD = 0.05 00050 TIMEOUT = 10.0 00051 RECEIVE_TIMEOUT = 2.0 00052 RECOVERY_DURATION = 0.25 00053 00054 class BaseRecovery(Thread): 00055 def __init__(self): 00056 Thread.__init__(self) 00057 self.lock = Lock() 00058 self.odom_sub = rospy.Subscriber('base_odometry/odometer', Odometer, self.odom_cb) 00059 self.control_sub = rospy.Subscriber('base_controller/state', BaseControllerState2, self.control_cb) 00060 self.base_sub = rospy.Subscriber('base_controller/command', Twist, self.base_cb) 00061 self.eff_start_time = rospy.Time.now() 00062 self.dist_start_time = rospy.Time.now() 00063 self.base_start_time = rospy.Time.now() 00064 self.base_receive_time = rospy.Time(0.0) 00065 self.dist = 0 00066 00067 def run(self): 00068 recovering = last_recovering = False 00069 recovery_start_time = rospy.Time(0.0) 00070 timeout = rospy.Duration(TIMEOUT) 00071 receive_timeout = rospy.Duration(RECEIVE_TIMEOUT) 00072 recovery_duration = rospy.Duration(RECOVERY_DURATION) 00073 recovery_twist = Twist() 00074 vel_pub = rospy.Publisher('base_controller/command', Twist) 00075 00076 while not rospy.is_shutdown(): 00077 now = rospy.Time.now() 00078 with self.lock: 00079 00080 # check if need to start a recovery 00081 if now < self.base_receive_time + receive_timeout and now > self.base_start_time + timeout and now > self.eff_start_time + timeout and now > self.dist_start_time + timeout: 00082 vec = PyKDL.Vector(random.randint(-50, 50), random.randint(-50, 50), random.randint(-100, 100)) 00083 vec.Normalize() 00084 recovery_twist.linear.x = vec[0] 00085 recovery_twist.linear.y = vec[1] 00086 recovery_twist.angular.z = vec[2] 00087 recovery_start_time = now 00088 self.eff_start_time = now 00089 self.dist_start_time = now 00090 rospy.logerr("Base is stuck... recovering with velocity (%f %f %f)"%(vec[0], vec[1], vec[2])) 00091 00092 # do the recovery 00093 if now < recovery_start_time + recovery_duration: 00094 vel_pub.publish(recovery_twist) 00095 recovering = True 00096 else: 00097 recovering = False 00098 00099 # after recovery send zero twist 00100 if not recovering and last_recovering: 00101 vel_pub.publish(Twist()) 00102 last_recovering = recovering 00103 00104 if recovering: 00105 rospy.sleep(0.001) 00106 else: 00107 rospy.sleep(0.1) 00108 00109 00110 def odom_cb(self, msg): 00111 with self.lock: 00112 dist = msg.distance + (msg.angle * 0.25) 00113 if dist > self.dist + DIST_THRESHOLD: 00114 #print 'resetting odom monitor' 00115 self.dist_start_time = rospy.Time.now() 00116 self.dist = dist 00117 00118 def base_cb(self, msg): 00119 with self.lock: 00120 self.base_receive_time = rospy.Time.now() 00121 base_cmd = fabs(msg.linear.x) + fabs(msg.linear.y) + fabs(msg.angular.z) 00122 if base_cmd < BASE_THRESHOLD: 00123 #print 'resetting base monitor' 00124 self.base_start_time = rospy.Time.now() 00125 00126 def control_cb(self, msg): 00127 with self.lock: 00128 eff = max( (fabs(e) for e in msg.joint_effort_measured) ) 00129 if eff < EFF_THRESHOLD: 00130 #print 'resetting effort monitor' 00131 self.eff_start_time = rospy.Time.now() 00132 00133 00134 00135 def main(): 00136 rospy.init_node('continuous_ops_executive') 00137 random.seed() 00138 br = BaseRecovery() 00139 br.start() 00140 rospy.spin() 00141 00142 00143 if __name__ == '__main__': 00144 main()