38 from sensor_msgs.msg
import JointState
40 prev_joint_states =
None 44 global prev_joint_states, pub
45 if not prev_joint_states:
49 prev_joint_states = msg
51 prev_joint_states.name = list(prev_joint_states.name)
52 prev_joint_states.position = list(prev_joint_states.position)
53 if len(prev_joint_states.velocity) > 0:
54 prev_joint_states.velocity = list(prev_joint_states.velocity)
56 prev_joint_states.velocity = [0] * len(prev_joint_states.name)
57 if len(prev_joint_states.effort) > 0:
58 prev_joint_states.effort = list(prev_joint_states.effort)
60 prev_joint_states.effort = [0] * len(prev_joint_states.name)
62 if len(msg.velocity) > 0:
63 velocity = msg.velocity
65 velocity = [0] * len(msg.name)
66 if len(msg.effort) > 0:
69 effort = [0] * len(msg.name)
71 for name, pos, vel, ef
in zip(msg.name, msg.position, velocity, effort):
72 if name
in prev_joint_states.name:
75 index = prev_joint_states.name.index(name)
76 prev_joint_states.position[index] = pos
77 prev_joint_states.velocity[index] = vel
78 prev_joint_states.effort[index] = ef
82 prev_joint_states.name.append(name)
83 prev_joint_states.position.append(pos)
84 prev_joint_states.effort.append(ef)
85 prev_joint_states.velocity.append(vel)
86 if prev_joint_states.header.stamp < msg.header.stamp:
87 prev_joint_states.header.stamp = msg.header.stamp
88 pub.publish(prev_joint_states)
90 if __name__ ==
"__main__":
91 rospy.init_node(
"joint_states_appender")
92 pub = rospy.Publisher(
"joint_states_appended", JointState, queue_size=1)
93 sub = rospy.Subscriber(
"joint_states", JointState, callback, queue_size=1)