joint_0_publisher.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import rospy
3 from sensor_msgs.msg import JointState
4 
5 
7  def __init__(self):
8  rospy.init_node('joint_0_publisher', anonymous=True)
9  self.sub = rospy.Subscriber("joint_states", JointState, self.callback)
10  self.pub = rospy.Publisher("joint_0s/joint_states", JointState, queue_size=1)
11  self.joint_state_msg = JointState()
12 
13  rospy.spin()
14 
15  def callback(self, data):
16  self.joint_state_msg.header.stamp = rospy.Time.now()
17 
18  self.joint_state_msg.name = []
19  self.joint_state_msg.position = []
20  self.joint_state_msg.velocity = []
21  self.joint_state_msg.effort = []
22 
23  fj0 = [0.0, 0.0, 0.0]
24  for name, position, velocity, effort in zip(data.name,
25  data.position,
26  data.velocity,
27  data.effort):
28  if "FJ1" in name and len(name) == 4:
29  fj0 = [position, velocity, effort]
30 
31  if "FJ2" in name and len(name) == 4:
32  fj0 = [fj0[0] + position, fj0[1] + velocity, fj0[2] + effort]
33  self.joint_state_msg.name.append(name[0]+"FJ0")
34  self.joint_state_msg.position.append(fj0[0])
35  self.joint_state_msg.velocity.append(fj0[1])
36  self.joint_state_msg.effort.append(fj0[2])
37 
38  self.pub.publish(self.joint_state_msg)
39 
40 if __name__ == '__main__':
41  j0_pub = Joint0Publisher()


sr_utilities
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:49