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
00035 import roslib; roslib.load_manifest('nxt_ros')
00036 import rospy
00037 import math
00038 from sensor_msgs.msg import JointState
00039
00040
00041 class JS:
00042 def __init__(self, name, header, position, velocity, effort):
00043 self.name = name
00044 self.header = header
00045 self.position = position
00046 self.velocity = velocity
00047 self.effort = effort
00048
00049
00050 class JSAggregator:
00051 def __init__(self):
00052
00053 self.sub = rospy.Subscriber('joint_state', JointState, self.callback)
00054
00055 self.pub = rospy.Publisher('joint_states', JointState)
00056 self.observed_states = {}
00057 self.updates_since_publish = 0
00058
00059 def callback(self, data):
00060 num_joints = len(data.name)
00061 if len(data.position) < num_joints:
00062 rospy.logerr("Position array shorter than names %s < %d"%(len(data.position), num_joints))
00063 return
00064 elif len(data.velocity) < num_joints:
00065 rospy.logerr("Velocity array shorter than names %s < %d"%(len(data.velocity), num_joints))
00066 return
00067 elif len(data.effort) < num_joints:
00068 rospy.logerr("Effort array shorter than names %s < %d"%(len(data.effort), num_joints))
00069 return
00070
00071 for i in xrange(0, num_joints):
00072 self.observed_states[data.name[i]] = JS(data.name[i],
00073 data.header,
00074 data.position[i],
00075 data.velocity[i],
00076 data.effort[i])
00077
00078 todelete = [k for k, v in self.observed_states.iteritems() if data.header.stamp - v.header.stamp > rospy.Duration().from_sec(10.0) ]
00079 for td in todelete:
00080 del self.observed_states[td]
00081
00082
00083
00084 if self.updates_since_publish < len(self.observed_states.keys()):
00085 self.updates_since_publish += 1
00086 return
00087
00088 self.updates_since_publish = 0
00089 msg_out = JointState()
00090 msg_out.header = data.header
00091 for k, v in self.observed_states.iteritems():
00092
00093 msg_out.name.append(v.name)
00094 msg_out.position.append(v.position)
00095 msg_out.velocity.append(v.velocity)
00096 msg_out.effort.append(v.effort)
00097
00098 self.pub.publish(msg_out)
00099
00100 def main():
00101 rospy.init_node("joint_state_aggregator")
00102
00103 agg = JSAggregator()
00104
00105 rospy.spin()
00106
00107
00108
00109 if __name__ == '__main__':
00110 main()