$search
00001 #!/usr/bin/env python 00002 # 00003 # Copyright (c) 2011, Bosch LLC 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 Bosch LLC 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 # Authors: Christian Bersch Bosch LLC 00031 00032 import roslib 00033 roslib.load_manifest("simple_robot_control") 00034 import rospy 00035 import math 00036 import numpy 00037 00038 import threading 00039 00040 import geometry_msgs.msg 00041 import tf.listener 00042 import tf.transformations 00043 00044 00045 00046 class Base: 00047 def __init__(self): 00048 00049 self.base_vel_cmd_pub = rospy.Publisher("/base_controller/command", geometry_msgs.msg.Twist) 00050 self.listener = tf.TransformListener() 00051 self.lock = threading.Lock() 00052 # self.thread = None 00053 00054 00055 def driveForward(self,distance,speed = 0.1, wait = True): 00056 """ 00057 if distance is positive it drives forward else backwards 00058 """ 00059 speed = abs(speed) 00060 velocity = geometry_msgs.msg.Twist() 00061 if distance < 0.0: 00062 speed = -1.0 * speed 00063 distance = -1.0 * distance 00064 velocity.linear.x = speed 00065 self.driveTwist(distance, velocity, wait) 00066 00067 def driveLeft(self,distance,speed = 0.1, wait = True): 00068 """ 00069 if distance is positive it drives left else right 00070 """ 00071 speed = abs(speed) 00072 velocity = geometry_msgs.msg.Twist() 00073 if distance < 0.0: 00074 speed = -1.0 * speed 00075 distance = -1.0 * distance 00076 velocity = geometry_msgs.msg.Twist() 00077 velocity.linear.y = speed 00078 self.driveTwist(distance, velocity, wait) 00079 00080 00081 def _driveTwist(self, distance, velocity): 00082 velocity.angular.x = velocity.angular.y = velocity.angular.z = velocity.linear.z = 0 00083 #get current pose 00084 now = rospy.Time.now() 00085 self.listener.waitForTransform('base_footprint', 'odom_combined', now, rospy.Duration(5.0)) 00086 self.lock.acquire() 00087 (trans_start,rot_start) = (trans_end,rot_end) = self.listener.lookupTransform( 'base_footprint', 'odom_combined', rospy.Time(0)) 00088 #keep moving until distance travelled 00089 while numpy.linalg.norm(numpy.array(trans_start) - trans_end) < distance and not rospy.is_shutdown(): 00090 self.base_vel_cmd_pub.publish(velocity) 00091 rospy.sleep(0.05) 00092 (trans_end,rot_end) = self.listener.lookupTransform( 'base_footprint', 'odom_combined', rospy.Time(0)) 00093 self.lock.release() 00094 00095 def driveTwist(self, distance, velocity, wait): 00096 """ 00097 executes translational drive command as specified in velocity twist 00098 """ 00099 if not isinstance(velocity, geometry_msgs.msg.Twist): 00100 raise TypeError('velocity must be of type geometry_msgs.msg.Twist') 00101 00102 if wait: 00103 self._driveTwist(distance, velocity) 00104 else: 00105 thread = threading.Thread(target=self._driveTwist, args = (distance, velocity)) 00106 thread.start() 00107 00108 00109 00110 def _turnLeft(self,radians, speed = 0.2): 00111 speed = abs(speed) 00112 if radians < 0.0: 00113 speed = -1.0 * speed 00114 radians = -1.0 * radians 00115 radians = radians % math.pi 00116 velocity = geometry_msgs.msg.Twist() 00117 velocity.angular.z = speed 00118 #get current pose 00119 now = rospy.Time.now() 00120 self.listener.waitForTransform('base_footprint', 'odom_combined', now, rospy.Duration(5.0)) 00121 self.lock.acquire() 00122 (trans_start,rot_start) = (trans_end,rot_end) = self.listener.lookupTransform( 'base_footprint', 'odom_combined', rospy.Time(0)) 00123 #keep moving until rotation reached - since robot only rotates around z axis one can compare the w component of the quaternions to half the angle 00124 angle_turned = 0.0 00125 rot_start_inv = tf.transformations.quaternion_inverse(rot_start) 00126 while angle_turned < radians: 00127 00128 self.base_vel_cmd_pub.publish(velocity) 00129 rospy.sleep(0.05) 00130 (trans_end,rot_end) = self.listener.lookupTransform( 'base_footprint', 'odom_combined', rospy.Time(0)) 00131 euler_angles = tf.transformations.euler_from_quaternion(tf.transformations.quaternion_multiply(rot_start_inv, rot_end)) 00132 angle_turned = abs( euler_angles[2]) 00133 # print "angle_turned", angle_turned 00134 self.lock.release() 00135 00136 00137 def turnLeft(self,radians, speed = 0.2, wait = True): 00138 """ 00139 rotates the base by radians with speed. positive radians value will cause counterclockwise turning, negative radians will cause clockwise turning 00140 """ 00141 if wait: 00142 self._turnLeft(radians, speed) 00143 else: 00144 thread = threading.Thread(target=self._turnLeft, args = (radians, speed)) 00145 thread.start() 00146 00147 00148 def isDone(self): 00149 return not self.lock.locked() 00150 00151 00152 00153 00154 00155 00156