port.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 # Software License Agreement (BSD)
5 #
6 # file @port.py
7 # authors Mike Purvis <mpurvis@clearpathrobotics.com>
8 # NovAtel <novatel.com/support>
9 # copyright Copyright (c) 2012, Clearpath Robotics, Inc., All rights reserved.
10 # Copyright (c) 2014, NovAtel Inc., All rights reserved.
11 #
12 # Redistribution and use in source and binary forms, with or without modification, are permitted provided that
13 # the following conditions are met:
14 # * Redistributions of source code must retain the above copyright notice, this list of conditions and the
15 # following disclaimer.
16 # * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
17 # following disclaimer in the documentation and/or other materials provided with the distribution.
18 # * Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
19 # products derived from this software without specific prior written permission.
20 #
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
22 # RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
23 # PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
24 # DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
25 # OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
26 # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 
29 import rospy
30 import novatel_msgs.msg as msg
31 
32 # Node source
33 from translator import Translator
34 
35 # Python
36 import threading
37 import socket
38 import serial
39 import struct
40 from cStringIO import StringIO
41 
42 
43 class Port(threading.Thread):
44 
45  """ Common base class for DataPort and ControlPort. Provides functionality to
46  recv/send novatel-formatted packets from the socket. Could in future
47  support LoggingPort and DisplayPort."""
48  checksum_struct = struct.Struct("<hh")
49 
50  def __init__(self, sock, **opts):
51  super(Port, self).__init__()
52  self.sock = sock
53  self.opts = opts
54  self.daemon = False
55  self.finish = threading.Event()
56  self.bSerial = False
57 
58  def recv(self, d=False):
59  """ Receive a packet from the port's socket.
60  Returns (header, pkt_str)
61  Returns None, None when no data. """
62 
63  header = msg.CommonHeader()
64  footer = msg.CommonFooter()
65 
66  try:
67  bytes_before_sync = []
68  while True:
69  sync = self.sock.recv(1)
70  if sync == "\xAA":
71  bytes_before_sync = ''.join(bytes_before_sync)
72  if len(bytes_before_sync) > 0 and not bytes_before_sync.startswith("\r\n<OK"):
73  rospy.logwarn(("Discarded %d bytes between end of previous message " +
74  "and next sync byte.") % len(bytes_before_sync))
75  rospy.logwarn("Discarded: %s" % repr(bytes_before_sync))
76  break
77  bytes_before_sync.append(sync)
78 
79  sync = self.sock.recv(1)
80  if sync != "\x44":
81  raise ValueError("Bad sync2 byte, expected 0x44, received 0x%x" % ord(sync[0]))
82  sync = self.sock.recv(1)
83  if sync != "\x12":
84  raise ValueError("Bad sync3 byte, expected 0x12, received 0x%x" % ord(sync[0]))
85 
86  # Four byte offset to account for 3 sync bytes and one header length byte already consumed.
87  header_length = ord(self.sock.recv(1)[0]) - 4
88  if header_length != header.translator().size:
89  raise ValueError("Bad header length. Expected %d, got %d" %
90  (header.translator().size, header_length))
91 
92  except (socket.timeout, serial.SerialTimeoutException) as e:
93  rospy.logwarn("Connection timeout... %s" % str(e))
94  return None, None
95 
96  header_str = self.sock.recv(header_length)
97  header_data = StringIO(header_str)
98  header.translator().deserialize(header_data)
99 
100  packet_str = self.sock.recv(header.length)
101  footer_data = StringIO(self.sock.recv(footer.translator().size))
102 
103  return header, packet_str
104 
105  def send(self, header, message):
106  """ Sends a header/msg/footer out the socket. Takes care of computing
107  length field for header and checksum field for footer. """
108 
109  msg_buff = StringIO()
110  message.translator().preserialize()
111  message.translator().serialize(msg_buff)
112  pad_count = -msg_buff.tell() % 4
113  msg_buff.write("\x00" * pad_count)
114 
115  footer = msg.CommonFooter(end=msg.CommonFooter.END)
116  header.length = msg_buff.tell() + footer.translator().size
117 
118  # Write header and message to main buffer.
119  buff = StringIO()
120  header.translator().serialize(buff)
121  buff.write(msg_buff.getvalue())
122 
123  # Write footer.
124  footer_start = buff.tell()
125  footer.translator().serialize(buff)
126 
127  # Compute checksum.
128  buff.seek(0)
129  footer.checksum = 65536 - self._checksum(buff)
130 
131  # Rewrite footer with correct checksum.
132  buff.seek(footer_start)
133  footer.translator().serialize(buff)
134 
135  self.sock.send(buff.getvalue())
136 
137  @classmethod
138  def _checksum(cls, buff):
139  """ Compute novatel checksum. Expects a StringIO with a
140  size that is a multiple of four bytes. """
141  checksum = 0
142 
143  while True:
144  data = buff.read(cls.checksum_struct.size)
145 
146  if len(data) == 0:
147  break
148  if len(data) < 4:
149  pad_count = len(data) % 4
150  data = data + "\x00" * pad_count
151  raise ValueError("Checksum data length is not a multiple of 4. %d" % len(data))
152  print(data)
153  c1, c2 = cls.checksum_struct.unpack(data)
154  checksum += c1 + c2
155  print(checksum, checksum % 65536) # novatel 32 bit crc
156  return checksum % 65536
def _checksum(cls, buff)
Definition: port.py:138
def __init__(self, sock, opts)
Definition: port.py:50
def recv(self, d=False)
Definition: port.py:58
def send(self, header, message)
Definition: port.py:105


novatel_span_driver
Author(s): NovAtel Support
autogenerated on Mon Sep 2 2019 03:58:19