3 from sensor_msgs.msg
import JointState
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)
13 self.
pub = rospy.Publisher(
"/joint_states", JointState)
20 self.
mutex = thread.allocate_lock()
32 self.joint_state_msg.header.stamp = rospy.Time.now()
34 tmp = self.joint_state_msg.name
36 self.joint_state_msg.name = tmp
38 tmp = self.joint_state_msg.position
40 self.joint_state_msg.position = tmp
42 tmp = self.joint_state_msg.velocity
44 self.joint_state_msg.velocity = tmp
46 tmp = self.joint_state_msg.effort
48 self.joint_state_msg.effort = tmp
66 self.joint_state_msg.header.stamp = rospy.Time.now()
68 tmp = self.joint_state_msg.name
70 self.joint_state_msg.name = tmp
72 tmp = self.joint_state_msg.position
74 self.joint_state_msg.position = tmp
76 tmp = self.joint_state_msg.velocity
78 self.joint_state_msg.velocity = tmp
80 tmp = self.joint_state_msg.effort
82 self.joint_state_msg.effort = tmp
93 if __name__ ==
'__main__':
def callback2(self, data)
def callback1(self, data)