joint_states_merger.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import rospy
3 from sensor_msgs.msg import JointState
4 import thread
5 
6 
8  def __init__(self):
9  rospy.init_node('joint_state_merger', anonymous=True)
10  self.subs_1 = rospy.Subscriber("/srh/position/joint_states", JointState, self.callback1)
11  self.subs_2 = rospy.Subscriber("/sr_arm/position/joint_states", JointState, self.callback2)
12 
13  self.pub = rospy.Publisher("/joint_states", JointState)
14 
15  self.msg_1_received = False
16  self.msg_2_received = False
17 
18  self.joint_state_msg = JointState()
19 
20  self.mutex = thread.allocate_lock()
21 
22  rospy.spin()
23 
24  def callback1(self, data):
25  self.mutex.acquire()
26  if self.msg_1_received:
27  self.mutex.release()
28  return
29 
30  self.msg_1_received = True
31 
32  self.joint_state_msg.header.stamp = rospy.Time.now()
33 
34  tmp = self.joint_state_msg.name
35  tmp += data.name
36  self.joint_state_msg.name = tmp
37 
38  tmp = self.joint_state_msg.position
39  tmp += data.position
40  self.joint_state_msg.position = tmp
41 
42  tmp = self.joint_state_msg.velocity
43  tmp += data.velocity
44  self.joint_state_msg.velocity = tmp
45 
46  tmp = self.joint_state_msg.effort
47  tmp += data.effort
48  self.joint_state_msg.effort = tmp
49 
50  if self.msg_2_received:
51  self.pub.publish(self.joint_state_msg)
52  self.msg_1_received = False
53  self.msg_2_received = False
54  self.joint_state_msg = JointState()
55 
56  self.mutex.release()
57 
58  def callback2(self, data):
59  self.mutex.acquire()
60  if self.msg_2_received:
61  self.mutex.release()
62  return
63 
64  self.msg_2_received = True
65 
66  self.joint_state_msg.header.stamp = rospy.Time.now()
67 
68  tmp = self.joint_state_msg.name
69  tmp += data.name
70  self.joint_state_msg.name = tmp
71 
72  tmp = self.joint_state_msg.position
73  tmp += data.position
74  self.joint_state_msg.position = tmp
75 
76  tmp = self.joint_state_msg.velocity
77  tmp += data.velocity
78  self.joint_state_msg.velocity = tmp
79 
80  tmp = self.joint_state_msg.effort
81  tmp += data.effort
82  self.joint_state_msg.effort = tmp
83 
84  if self.msg_1_received:
85  self.pub.publish(self.joint_state_msg)
86  self.msg_1_received = False
87  self.msg_2_received = False
88  self.joint_state_msg = JointState()
89 
90  self.mutex.release()
91 
92 
93 if __name__ == '__main__':
94  merger = MergeMessages()


sr_utilities
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:49