mavtest.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import sys, os
00004 
00005 from pymavlink import mavlinkv10 as mavlink
00006 
00007 class fifo(object):
00008     def __init__(self):
00009         self.buf = []
00010     def write(self, data):
00011         self.buf += data
00012         return len(data)
00013     def read(self):
00014         return self.buf.pop(0)
00015 
00016 # we will use a fifo as an encode/decode buffer
00017 f = fifo()
00018 
00019 # create a mavlink instance, which will do IO on file object 'f'
00020 mav = mavlink.MAVLink(f)
00021 
00022 # set the WP_RADIUS parameter on the MAV at the end of the link
00023 mav.param_set_send(7, 1, "WP_RADIUS", 101, mavlink.MAV_PARAM_TYPE_REAL32)
00024 
00025 # alternatively, produce a MAVLink_param_set object 
00026 # this can be sent via your own transport if you like
00027 m = mav.param_set_encode(7, 1, "WP_RADIUS", 101, mavlink.MAV_PARAM_TYPE_REAL32)
00028 
00029 # get the encoded message as a buffer
00030 b = m.get_msgbuf()
00031 
00032 # decode an incoming message
00033 m2 = mav.decode(b)
00034 
00035 # show what fields it has
00036 print("Got a message with id %u and fields %s" % (m2.get_msgId(), m2.get_fieldnames()))
00037 
00038 # print out the fields
00039 print(m2)


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