joint_states_merger.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright 2011 Shadow Robot Company Ltd.
4 #
5 # This program is free software: you can redistribute it and/or modify it
6 # under the terms of the GNU General Public License as published by the Free
7 # Software Foundation version 2 of the License.
8 #
9 # This program is distributed in the hope that it will be useful, but WITHOUT
10 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
11 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
12 # more details.
13 #
14 # You should have received a copy of the GNU General Public License along
15 # with this program. If not, see <http://www.gnu.org/licenses/>.
16 
17 import rospy
18 from sensor_msgs.msg import JointState
19 import thread
20 
21 
23  def __init__(self):
24  rospy.init_node('joint_state_merger', anonymous=True)
25  self.subs_1 = rospy.Subscriber("/srh/position/joint_states", JointState, self.callback1)
26  self.subs_2 = rospy.Subscriber("/sr_arm/position/joint_states", JointState, self.callback2)
27 
28  self.pub = rospy.Publisher("/joint_states", JointState)
29 
30  self.msg_1_received = False
31  self.msg_2_received = False
32 
33  self.joint_state_msg = JointState()
34 
35  self.mutex = thread.allocate_lock()
36 
37  rospy.spin()
38 
39  def callback1(self, data):
40  self.mutex.acquire()
41  if self.msg_1_received:
42  self.mutex.release()
43  return
44 
45  self.msg_1_received = True
46 
47  self.joint_state_msg.header.stamp = rospy.Time.now()
48 
49  tmp = self.joint_state_msg.name
50  tmp += data.name
51  self.joint_state_msg.name = tmp
52 
53  tmp = self.joint_state_msg.position
54  tmp += data.position
55  self.joint_state_msg.position = tmp
56 
57  tmp = self.joint_state_msg.velocity
58  tmp += data.velocity
59  self.joint_state_msg.velocity = tmp
60 
61  tmp = self.joint_state_msg.effort
62  tmp += data.effort
63  self.joint_state_msg.effort = tmp
64 
65  if self.msg_2_received:
66  self.pub.publish(self.joint_state_msg)
67  self.msg_1_received = False
68  self.msg_2_received = False
69  self.joint_state_msg = JointState()
70 
71  self.mutex.release()
72 
73  def callback2(self, data):
74  self.mutex.acquire()
75  if self.msg_2_received:
76  self.mutex.release()
77  return
78 
79  self.msg_2_received = True
80 
81  self.joint_state_msg.header.stamp = rospy.Time.now()
82 
83  tmp = self.joint_state_msg.name
84  tmp += data.name
85  self.joint_state_msg.name = tmp
86 
87  tmp = self.joint_state_msg.position
88  tmp += data.position
89  self.joint_state_msg.position = tmp
90 
91  tmp = self.joint_state_msg.velocity
92  tmp += data.velocity
93  self.joint_state_msg.velocity = tmp
94 
95  tmp = self.joint_state_msg.effort
96  tmp += data.effort
97  self.joint_state_msg.effort = tmp
98 
99  if self.msg_1_received:
100  self.pub.publish(self.joint_state_msg)
101  self.msg_1_received = False
102  self.msg_2_received = False
103  self.joint_state_msg = JointState()
104 
105  self.mutex.release()
106 
107 
108 if __name__ == '__main__':
109  merger = MergeMessages()


sr_utilities
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:19