$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 from sensor_msgs.msg import JointState 00039 from nxt_msgs.msg import Range, JointCommand 00040 00041 00042 00043 class JointPositionController: 00044 def __init__(self): 00045 self.initialized = False 00046 self.vel = 0 00047 00048 # get joint name 00049 self.name = rospy.get_param('name', 'motor_1') 00050 00051 # joint interaction 00052 self.pub = rospy.Publisher('joint_command', JointCommand) 00053 rospy.Subscriber('joint_states', JointState, self.jnt_state_cb) 00054 00055 # desired joint position 00056 rospy.Subscriber('joint_position', JointCommand, self.jnt_pos_cb) 00057 00058 00059 00060 def jnt_pos_cb(self, msg): 00061 if msg.name == self.name: 00062 self.pos_desi = msg.effort 00063 00064 00065 def jnt_state_cb(self, msg): 00066 for name, pos, vel in zip(msg.name, msg.position, msg.velocity): 00067 if name == self.name: 00068 self.vel = 0.5 * self.vel + 0.5 * vel 00069 if not self.initialized: 00070 self.pos_desi = pos 00071 self.initialized = True 00072 cmd = JointCommand() 00073 cmd.name = self.name 00074 cmd.effort = 190.0 * (self.pos_desi - pos) - 4.0 * self.vel 00075 print 'Joint at %f, going to %f, commanding joint %f'%(pos,self.pos_desi, cmd.effort) 00076 self.pub.publish(cmd) 00077 00078 00079 00080 def main(): 00081 rospy.init_node('jnt_pos_controller') 00082 jnt_pos_controller = JointPositionController() 00083 rospy.spin() 00084 00085 00086 00087 if __name__ == '__main__': 00088 main()