$search
00001 #!/usr/bin/env python 00002 # Software License Agreement (BSD License) 00003 # 00004 # Copyright (c) 2010, Willow Garage, Inc. 00005 # All rights reserved. 00006 # 00007 # Redistribution and use in source and binary forms, with or without 00008 # modification, are permitted provided that the following conditions 00009 # are met: 00010 # 00011 # * Redistributions of source code must retain the above copyright 00012 # notice, this list of conditions and the following disclaimer. 00013 # * Redistributions in binary form must reproduce the above 00014 # copyright notice, this list of conditions and the following 00015 # disclaimer in the documentation and/or other materials provided 00016 # with the distribution. 00017 # * Neither the name of Willow Garage, Inc. nor the names of its 00018 # contributors may be used to endorse or promote products derived 00019 # from this software without specific prior written permission. 00020 # 00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 # POSSIBILITY OF SUCH DAMAGE. 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 # create motor 00053 self.sub = rospy.Subscriber('joint_state', JointState, self.callback) 00054 # create publisher 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) ] #hack parametersize 00079 for td in todelete: 00080 del self.observed_states[td] 00081 00082 00083 # Only publish if there has been as many updates as there are joints, otherwise odom, gets zero deltas and the robot jerks around. 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 #print k, v 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()