$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2010, 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 Willow Garage, Inc. 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 import roslib; roslib.load_manifest('nxt_controllers') 00035 import rospy 00036 import math 00037 import thread 00038 import tf 00039 from PyKDL import * 00040 from sensor_msgs.msg import JointState 00041 from nav_msgs.msg import Odometry 00042 from nxt_msgs.msg import Range, JointCommand 00043 from tf_conversions import posemath 00044 00045 PUBLISH_TF = False 00046 00047 class BaseOdometry: 00048 def __init__(self): 00049 self.initialized = False 00050 00051 self.ns =rospy.get_namespace() + 'base_parameters/' 00052 # get joint name 00053 self.l_joint = rospy.get_param(self.ns +'l_wheel_joint') 00054 self.r_joint = rospy.get_param(self.ns +'r_wheel_joint') 00055 00056 self.wheel_radius = rospy.get_param(self.ns +'wheel_radius', 0.022) 00057 self.wheel_basis = rospy.get_param(self.ns +'wheel_basis', 0.055) 00058 00059 # joint interaction 00060 rospy.Subscriber('joint_states', JointState, self.jnt_state_cb) 00061 00062 # tf broadcaster 00063 if PUBLISH_TF: 00064 self.br = tf.TransformBroadcaster() 00065 00066 # publish results on topic 00067 self.pub = rospy.Publisher('odom', Odometry) 00068 00069 self.initialized = False 00070 00071 def jnt_state_cb(self, msg): 00072 # crates map 00073 position = {} 00074 for name, pos in zip(msg.name, msg.position): 00075 position[name] = pos 00076 00077 # initialize 00078 if not self.initialized: 00079 self.r_pos = position[self.r_joint] 00080 self.l_pos = position[self.l_joint] 00081 self.pose = Frame() 00082 self.initialized = True 00083 else: 00084 delta_r_pos = position[self.r_joint] - self.r_pos 00085 delta_l_pos = position[self.l_joint] - self.l_pos 00086 delta_trans = (delta_r_pos + delta_l_pos)*self.wheel_radius/2.0 00087 delta_rot = (delta_r_pos - delta_l_pos)*self.wheel_radius/(2.0*self.wheel_basis) 00088 twist = Twist(Vector(delta_trans, 0, 0), Vector(0, 0, delta_rot)) 00089 self.r_pos = position[self.r_joint] 00090 self.l_pos = position[self.l_joint] 00091 self.pose = addDelta(self.pose, self.pose.M * twist) 00092 if PUBLISH_TF: 00093 self.br.sendTransform(self.pose.p, self.pose.M.GetQuaternion(), rospy.Time.now(), 'base_link', 'odom') 00094 00095 00096 self.rot_covar = 1.0 00097 if delta_rot == 0: 00098 self.rot_covar = 0.00000000001 00099 00100 odom = Odometry() 00101 odom.header.stamp = rospy.Time.now() 00102 odom.pose.pose = posemath.toMsg(self.pose) 00103 odom.pose.covariance = [0.00001, 0, 0, 0, 0, 0, 00104 0, 0.00001, 0, 0, 0, 0, 00105 0, 0, 10.0000, 0, 0, 0, 00106 0, 0, 0, 1.00000, 0, 0, 00107 0, 0, 0, 0, 1.00000, 0, 00108 0, 0, 0, 0, 0, self.rot_covar] 00109 self.pub.publish(odom) 00110 00111 def main(): 00112 rospy.init_node('nxt_base_odometry') 00113 base_odometry = BaseOdometry() 00114 rospy.spin() 00115 00116 00117 00118 if __name__ == '__main__': 00119 main()