bwtest.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 check bandwidth of link
5 '''
6 from __future__ import print_function
7 import time
8 
9 from pymavlink import mavutil
10 
11 #using argparse to receive options from the command line
12 from argparse import ArgumentParser
13 parser = ArgumentParser(description=__doc__)
14 
15 parser.add_argument("--baudrate", type=int,
16  help="master port baud rate", default=115200)
17 parser.add_argument("--device", required=True, help="serial device")
18 args = parser.parse_args()
19 
20 ### MAV related code starts here ###
21 
22 # create a mavlink serial instance
23 master = mavutil.mavlink_connection(args.device, baud=args.baudrate)
24 
25 t1 = time.time()
26 
27 counts = {}
28 
29 bytes_sent = 0
30 bytes_recv = 0
31 
32 while True:
33  #send some messages to the target system with dummy data
34  master.mav.heartbeat_send(1, 1)
35  master.mav.sys_status_send(1, 2, 3, 4, 5, 6, 7)
36  master.mav.gps_raw_send(1, 2, 3, 4, 5, 6, 7, 8, 9)
37  master.mav.attitude_send(1, 2, 3, 4, 5, 6, 7)
38  master.mav.vfr_hud_send(1, 2, 3, 4, 5, 6)
39 
40  #Check for incoming data on the serial port and count
41  #how many mesages of each type have been received
42  while master.port.inWaiting() > 0:
43  #recv_msg will try parsing the serial port buffer
44  #and return a new message if available
45  m = master.recv_msg()
46 
47  if m is None: break #No new message
48 
49  if m.get_type() not in counts:
50  #if no messages of this type received, add this type to the counts dict
51  counts[m.get_type()] = 0
52 
53  counts[m.get_type()] += 1
54 
55  #Print statistics every second
56  t2 = time.time()
57  if t2 - t1 > 1.0:
58  print("%u sent, %u received, %u errors bwin=%.1f kB/s bwout=%.1f kB/s" % (
59  master.mav.total_packets_sent,
60  master.mav.total_packets_received,
61  master.mav.total_receive_errors,
62  0.001*(master.mav.total_bytes_received-bytes_recv)/(t2-t1),
63  0.001*(master.mav.total_bytes_sent-bytes_sent)/(t2-t1)))
64  bytes_sent = master.mav.total_bytes_sent
65  bytes_recv = master.mav.total_bytes_received
66  t1 = t2


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