00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
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
00049 self.name = rospy.get_param('name', 'motor_1')
00050
00051
00052 self.pub = rospy.Publisher('joint_command', JointCommand)
00053 rospy.Subscriber('joint_states', JointState, self.jnt_state_cb)
00054
00055
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()