In [7]:
import pymavlink.dialects.v10.ardupilotmega as mavlink
import struct

In [8]:
class fifo(object):
    def __init__(self):
        self.buf = []
    def write(self, data):
        self.buf += data
        return len(data)
    def read(self):
        return self.buf.pop(0)
f = fifo()

In [9]:
mav = mavlink.MAVLink(f)

In [10]:
mav


Out[10]:
<pymavlink.dialects.v10.ardupilotmega.MAVLink at 0x3879350>

In [11]:
m = mav.param_set_encode(7, 1, "WP_RADIUS", 101, mavlink.MAV_PARAM_TYPE_REAL32)

In [12]:
m.__dict__


Out[12]:
{'_crc': None,
 '_fieldnames': ['target_system',
  'target_component',
  'param_id',
  'param_value',
  'param_type'],
 '_header': <pymavlink.dialects.v10.ardupilotmega.MAVLink_header at 0x3820550>,
 '_msgbuf': None,
 '_payload': None,
 '_type': 'PARAM_SET',
 'param_id': 'WP_RADIUS',
 'param_type': 9,
 'param_value': 101,
 'target_component': 1,
 'target_system': 7}

In [13]:
b = m.pack(mav)

In [14]:
b


Out[14]:
'\xfe\x17\x00\x00\x00\x17\x00\x00\xcaB\x07\x01WP_RADIUS\x00\x00\x00\x00\x00\x00\x00\t\xb1\xf3'

In [13]:
_crcbuf = b[1:-2]
_crcbuf


Out[13]:
'\x17\x00\x00\x00\x17\x00\x00\xcaB\x07\x01WP_RADIUS\x00\x00\x00\x00\x00\x00\x00\t'

In [14]:
_crcbuf = _crcbuf + struct.pack('B', 168)
_crcbuf


Out[14]:
'\x17\x00\x00\x00\x17\x00\x00\xcaB\x07\x01WP_RADIUS\x00\x00\x00\x00\x00\x00\x00\t\xa8'

In [15]:
m2 = mav.decode(b)

In [17]:
m2.__dict__


Out[17]:
{'_crc': 62385,
 '_fieldnames': ['target_system',
  'target_component',
  'param_id',
  'param_value',
  'param_type'],
 '_header': <pymavlink.dialects.v10.pixhawk.MAVLink_header at 0x34c4b30>,
 '_msgbuf': '\xfe\x17\x00\x00\x00\x17\x00\x00\xcaB\x07\x01WP_RADIUS\x00\x00\x00\x00\x00\x00\x00\t\xb1\xf3',
 '_payload': '\x00\x00\xcaB\x07\x01WP_RADIUS\x00\x00\x00\x00\x00\x00\x00\t',
 '_type': 'PARAM_SET',
 'param_id': 'WP_RADIUS',
 'param_type': 9,
 'param_value': 101.0,
 'target_component': 1,
 'target_system': 7}

In [ ]:
struct.pack()