joint_states_appender.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #####################################################################
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2015, JSK Lab
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/o2r other materials provided
17 # with the distribution.
18 # * Neither the name of the JSK Lab nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 #####################################################################
35 
36 
37 import rospy
38 from sensor_msgs.msg import JointState
39 
40 prev_joint_states = None
41 pub = None
42 
43 def callback(msg):
44  global prev_joint_states, pub
45  if not prev_joint_states:
46  # initial time
47  # just pass the input message to output
48  pub.publish(msg)
49  prev_joint_states = msg
50  # force to use list instead of tuple.
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)
55  else:
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)
59  else:
60  prev_joint_states.effort = [0] * len(prev_joint_states.name)
61  else:
62  if len(msg.velocity) > 0:
63  velocity = msg.velocity
64  else:
65  velocity = [0] * len(msg.name)
66  if len(msg.effort) > 0:
67  effort = msg.effort
68  else:
69  effort = [0] * len(msg.name)
70 
71  for name, pos, vel, ef in zip(msg.name, msg.position, velocity, effort):
72  if name in prev_joint_states.name:
73  # if name is already listed in prev_joint_states,
74  # update value
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
79  else:
80  # if name is not yet listed in prev_joint_states,
81  # append name and position to prev_joint_states
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)
89 
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)
94  rospy.spin()


jsk_calibration
Author(s):
autogenerated on Fri May 14 2021 02:51:46