mavcrc.py
Go to the documentation of this file.
00001 '''MAVLink X25 CRC code'''
00002 
00003 
00004 class x25crc(object):
00005     '''x25 CRC - based on checksum.h from mavlink library'''
00006     def __init__(self, buf=None):
00007         self.crc = 0xffff
00008         if buf is not None:
00009             if isinstance(buf, str):
00010                 self.accumulate_str(buf)
00011             else:
00012                 self.accumulate(buf)
00013 
00014     def accumulate(self, buf):
00015         '''add in some more bytes'''
00016         accum = self.crc
00017         for b in buf:
00018             tmp = b ^ (accum & 0xff)
00019             tmp = (tmp ^ (tmp<<4)) & 0xFF
00020             accum = (accum>>8) ^ (tmp<<8) ^ (tmp<<3) ^ (tmp>>4)
00021         self.crc = accum
00022 
00023     def accumulate_str(self, buf):
00024         '''add in some more bytes'''
00025         accum = self.crc
00026         import array
00027         bytes = array.array('B')
00028         bytes.fromstring(buf)
00029         self.accumulate(bytes)


mavlink
Author(s): Lorenz Meier
autogenerated on Wed Sep 9 2015 18:06:17