scripts
sr_tactile_sensors
virtual_ShadowPST_publisher.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
# This node combines 5 virtual touch sensors into a ShadowPST message compatible with etherCAT hand
18
19
import
rospy
20
from
std_msgs.msg
import
Float64
21
from
sr_robot_msgs.msg
import
ShadowPST
22
import
thread
23
24
25
class
MergeMessages
(object):
26
def
__init__
(self):
27
rospy.init_node(
'ShadowPST_publisher'
, anonymous=
True
)
28
self.
ff_sub
= rospy.Subscriber(
'/sr_tactile/touch/ff'
, Float64, self.
ff_cb
)
29
self.
mf_sub
= rospy.Subscriber(
'/sr_tactile/touch/mf'
, Float64, self.
mf_cb
)
30
self.
rf_sub
= rospy.Subscriber(
'/sr_tactile/touch/rf'
, Float64, self.
rf_cb
)
31
self.
lf_sub
= rospy.Subscriber(
'/sr_tactile/touch/lf'
, Float64, self.
lf_cb
)
32
self.
th_sub
= rospy.Subscriber(
'/sr_tactile/touch/th'
, Float64, self.
th_cb
)
33
self.
rate
= rospy.Rate(25.0)
34
self.
pub
= rospy.Publisher(
"/tactile"
, ShadowPST)
35
self.
pst
= [0.0, 0.0, 0.0, 0.0, 0.0]
36
self.
mutex
= thread.allocate_lock()
37
38
def
ff_cb
(self, msg):
39
self.
mutex
.acquire()
40
self.
pst
[0] = msg.data
41
self.
mutex
.release()
42
43
def
mf_cb
(self, msg):
44
self.
mutex
.acquire()
45
self.
pst
[1] = msg.data
46
self.
mutex
.release()
47
48
def
rf_cb
(self, msg):
49
self.
mutex
.acquire()
50
self.
pst
[2] = msg.data
51
self.
mutex
.release()
52
53
def
lf_cb
(self, msg):
54
self.
mutex
.acquire()
55
self.
pst
[3] = msg.data
56
self.
mutex
.release()
57
58
def
th_cb
(self, msg):
59
self.
mutex
.acquire()
60
self.
pst
[4] = msg.data
61
self.
mutex
.release()
62
63
def
shadowpst_publisher
(self):
64
pst_state_msg = ShadowPST()
65
pst_state_msg.temperature = [0, 0, 0, 0, 0, 0]
66
pressure = []
67
self.
mutex
.acquire()
68
for
i
in
range(0, 5):
69
pressure.append(self.
pst
[i]*100)
70
pst_state_msg.pressure = pressure
71
# print pst_state_msg.pressure
72
self.
mutex
.release()
73
74
pst_state_msg.header.stamp = rospy.Time.now()
75
self.
pub
.publish(pst_state_msg)
76
77
if
__name__ ==
'__main__'
:
78
merger =
MergeMessages
()
79
while
not
rospy.is_shutdown():
80
merger.shadowpst_publisher()
81
merger.rate.sleep()
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.mf_sub
mf_sub
Definition:
virtual_ShadowPST_publisher.py:29
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.th_sub
th_sub
Definition:
virtual_ShadowPST_publisher.py:32
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.lf_cb
def lf_cb(self, msg)
Definition:
virtual_ShadowPST_publisher.py:53
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.th_cb
def th_cb(self, msg)
Definition:
virtual_ShadowPST_publisher.py:58
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.rf_sub
rf_sub
Definition:
virtual_ShadowPST_publisher.py:30
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.pst
pst
Definition:
virtual_ShadowPST_publisher.py:35
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.__init__
def __init__(self)
Definition:
virtual_ShadowPST_publisher.py:26
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.rate
rate
Definition:
virtual_ShadowPST_publisher.py:33
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.ff_sub
ff_sub
Definition:
virtual_ShadowPST_publisher.py:28
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages
Definition:
virtual_ShadowPST_publisher.py:25
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.lf_sub
lf_sub
Definition:
virtual_ShadowPST_publisher.py:31
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.shadowpst_publisher
def shadowpst_publisher(self)
Definition:
virtual_ShadowPST_publisher.py:63
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.pub
pub
Definition:
virtual_ShadowPST_publisher.py:34
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.ff_cb
def ff_cb(self, msg)
Definition:
virtual_ShadowPST_publisher.py:38
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.rf_cb
def rf_cb(self, msg)
Definition:
virtual_ShadowPST_publisher.py:48
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.mutex
mutex
Definition:
virtual_ShadowPST_publisher.py:36
sr_tactile_sensors.virtual_ShadowPST_publisher.MergeMessages.mf_cb
def mf_cb(self, msg)
Definition:
virtual_ShadowPST_publisher.py:43
sr_tactile_sensors
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:14