mavtest.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 """
4 Generate a message using different MAVLink versions, put in a buffer and then read from it.
5 """
6 
7 from __future__ import print_function
8 from builtins import object
9 
10 from pymavlink.dialects.v10 import ardupilotmega as mavlink1
11 from pymavlink.dialects.v20 import ardupilotmega as mavlink2
12 
13 class fifo(object):
14  def __init__(self):
15  self.buf = []
16  def write(self, data):
17  self.buf += data
18  return len(data)
19  def read(self):
20  return self.buf.pop(0)
21 
22 def test_protocol(mavlink, signing=False):
23  # we will use a fifo as an encode/decode buffer
24  f = fifo()
25 
26  print("Creating MAVLink message...")
27  # create a mavlink instance, which will do IO on file object 'f'
28  mav = mavlink.MAVLink(f)
29 
30  if signing:
31  mav.signing.secret_key = chr(42)*32
32  mav.signing.link_id = 0
33  mav.signing.timestamp = 0
34  mav.signing.sign_outgoing = True
35 
36  # set the WP_RADIUS parameter on the MAV at the end of the link
37  mav.param_set_send(7, 1, "WP_RADIUS", 101, mavlink.MAV_PARAM_TYPE_REAL32)
38 
39  # alternatively, produce a MAVLink_param_set object
40  # this can be sent via your own transport if you like
41  m = mav.param_set_encode(7, 1, "WP_RADIUS", 101, mavlink.MAV_PARAM_TYPE_REAL32)
42 
43  m.pack(mav)
44 
45  # get the encoded message as a buffer
46  b = m.get_msgbuf()
47 
48  bi=[]
49  for c in b:
50  bi.append(int(c))
51  print("Buffer containing the encoded message:")
52  print(bi)
53 
54  print("Decoding message...")
55  # decode an incoming message
56  m2 = mav.decode(b)
57 
58  # show what fields it has
59  print("Got a message with id %u and fields %s" % (m2.get_msgId(), m2.get_fieldnames()))
60 
61  # print out the fields
62  print(m2)
63 
64 
65 print("Testing mavlink1\n")
66 test_protocol(mavlink1)
67 
68 print("\nTesting mavlink2\n")
69 test_protocol(mavlink2)
70 
71 print("\nTesting mavlink2 with signing\n")
72 test_protocol(mavlink2, True)


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02