-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
_lcm_extra.py
36 lines (30 loc) · 1.29 KB
/
_lcm_extra.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
# See `ExecuteExtraPythonCode` in `pydrake_pybind.h` for usage details and
# rationale.
# This is a python reimplementation of drake::lcm::Subscriber. We reimplement
# (rather than bind) the C++ class because we want message() to be a python LCM
# message, not a C++ object.
class Subscriber:
"""Subscribes to and stores a copy of the most recent message on a given
channel, for some message type. This class does NOT provide any mutex
behavior for multi-threaded locking; it should only be used in cases where
the governing DrakeLcmInterface.HandleSubscriptions is called from the same
thread that owns all copies of this object.
"""
def __init__(self, lcm, channel, lcm_type):
"""Creates a subscriber and subscribes to `channel` on `lcm`.
Args:
lcm: LCM service instance (a pydrake.lcm.DrakeLcmInterface).
channel: LCM channel name.
lcm_type: Python class generated by lcmgen.
"""
self.lcm_type = lcm_type
self.clear()
lcm.Subscribe(channel=channel, handler=self._handler)
def clear(self):
self.count = 0
self.raw = []
self.message = self.lcm_type()
def _handler(self, raw):
self.count += 1
self.raw = raw
self.message = self.lcm_type.decode(raw)