$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 00035 import roslib; roslib.load_manifest('nxt_controllers') 00036 import rospy 00037 import math 00038 import thread 00039 from sensor_msgs.msg import JointState 00040 from geometry_msgs.msg import Twist 00041 from nxt_msgs.msg import Range, JointCommand 00042 00043 class BaseController: 00044 def __init__(self): 00045 self.initialized = False 00046 self.vel_rot_desi = 0 00047 self.vel_trans_desi = 0 00048 self.vel_trans = 0 00049 self.vel_rot = 0 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 self.wheel_radius = rospy.get_param(self.ns +'wheel_radius', 0.022) 00056 self.wheel_basis = rospy.get_param(self.ns +'wheel_basis', 0.055) 00057 self.vel_to_eff = rospy.get_param(self.ns +'vel_to_eff', 0.5) 00058 self.k_rot = 0.075/self.vel_to_eff 00059 self.k_trans = 0.055/self.vel_to_eff 00060 00061 # joint interaction 00062 self.pub = rospy.Publisher('joint_command', JointCommand) 00063 rospy.Subscriber('joint_states', JointState, self.jnt_state_cb) 00064 00065 # base commands 00066 rospy.Subscriber('cmd_vel', Twist, self.cmd_vel_cb) 00067 00068 def cmd_vel_cb(self, msg): 00069 self.vel_rot_desi = msg.angular.z 00070 self.vel_trans_desi = msg.linear.x 00071 00072 def jnt_state_cb(self, msg): 00073 velocity = {} 00074 for name, vel in zip(msg.name, msg.velocity): 00075 velocity[name] = vel 00076 00077 # lowpass for measured velocity 00078 self.vel_trans = 0.5*self.vel_trans + 0.5*(velocity[self.r_joint] + velocity[self.l_joint])*self.wheel_radius/2.0 00079 self.vel_rot = 0.5*self.vel_rot + 0.5*(velocity[self.r_joint] - velocity[self.l_joint])*self.wheel_radius/(2.0*self.wheel_basis) 00080 00081 # velocity commands 00082 vel_trans = self.vel_trans_desi + self.k_trans*(self.vel_trans_desi - self.vel_trans) 00083 vel_rot = self.vel_rot_desi + self.k_rot*(self.vel_rot_desi - self.vel_rot) 00084 00085 # wheel commands 00086 l_cmd = JointCommand() 00087 l_cmd.name = self.l_joint 00088 l_cmd.effort = self.vel_to_eff*(vel_trans/self.wheel_radius - vel_rot*self.wheel_basis/self.wheel_radius) 00089 self.pub.publish(l_cmd) 00090 00091 r_cmd = JointCommand() 00092 r_cmd.name = self.r_joint 00093 r_cmd.effort = self.vel_to_eff*(vel_trans/self.wheel_radius + vel_rot*self.wheel_basis/self.wheel_radius) 00094 self.pub.publish(r_cmd) 00095 00096 00097 def main(): 00098 rospy.init_node('nxt_base_controller') 00099 base_controller = BaseController() 00100 rospy.spin() 00101 00102 00103 00104 if __name__ == '__main__': 00105 main()