Go to the documentation of this file.00001
00002 import rospy
00003 from sensor_msgs.msg import JointState
00004
00005
00006 class Joint0Publisher:
00007 def __init__(self):
00008 rospy.init_node('joint_0_publisher', anonymous=True)
00009 self.sub = rospy.Subscriber("joint_states", JointState, self.callback)
00010 self.pub = rospy.Publisher("joint_0s/joint_states", JointState, queue_size=1)
00011 self.joint_state_msg = JointState()
00012
00013 rospy.spin()
00014
00015 def callback(self, data):
00016 self.joint_state_msg.header.stamp = rospy.Time.now()
00017
00018 self.joint_state_msg.name = []
00019 self.joint_state_msg.position = []
00020 self.joint_state_msg.velocity = []
00021 self.joint_state_msg.effort = []
00022
00023 fj0 = [0.0, 0.0, 0.0]
00024 for name,position,velocity,effort in zip(data.name,
00025 data.position,
00026 data.velocity,
00027 data.effort):
00028 if "FJ1" in name and len(name) == 4:
00029 fj0 = [position, velocity, effort]
00030
00031 if "FJ2" in name and len(name) == 4:
00032 fj0 = [fj0[0] + position, fj0[1] + velocity, fj0[2] + effort]
00033 self.joint_state_msg.name.append(name[0]+"FJ0")
00034 self.joint_state_msg.position.append(fj0[0])
00035 self.joint_state_msg.velocity.append(fj0[1])
00036 self.joint_state_msg.effort.append(fj0[2])
00037
00038 self.pub.publish(self.joint_state_msg)
00039
00040 if __name__ == '__main__':
00041 j0_pub = Joint0Publisher()