outgoing_message.py
Go to the documentation of this file.
1 from rosbridge_library.internal.message_conversion import extract_values as extract_json_values
2 from rosbridge_library.internal.cbor_conversion import extract_cbor_values
3 from rospy import get_rostime
4 try:
5  from cbor import dumps as encode_cbor
6 except ImportError:
7  from rosbridge_library.util.cbor import dumps as encode_cbor
8 
9 
11  """A message wrapper for caching encoding operations."""
12  def __init__(self, message):
13  self._message = message
14  self._json_values = None
15  self._cbor_values = None
16  self._cbor_msg = None
17  self._cbor_raw_msg = None
18 
19  @property
20  def message(self):
21  return self._message
22 
23  def get_json_values(self):
24  if self._json_values is None:
25  self._json_values = extract_json_values(self._message)
26  return self._json_values
27 
28  def get_cbor_values(self):
29  if self._cbor_values is None:
31  return self._cbor_values
32 
33  def get_cbor(self, outgoing_msg):
34  if self._cbor_msg is None:
35  outgoing_msg[u"msg"] = self.get_cbor_values()
36  self._cbor_msg = encode_cbor(outgoing_msg)
37 
38  return self._cbor_msg
39 
40  def get_cbor_raw(self, outgoing_msg):
41  if self._cbor_raw_msg is None:
42  now = get_rostime()
43  outgoing_msg[u"msg"] = {
44  u"secs": now.secs,
45  u"nsecs": now.nsecs,
46  u"bytes": self._message._buff
47  }
48  self._cbor_raw_msg = encode_cbor(outgoing_msg)
49 
50  return self._cbor_raw_msg


rosbridge_library
Author(s): Jonathan Mace
autogenerated on Fri Oct 21 2022 02:45:18