apmsetrate.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 set stream rate on an APM
5 '''
6 from __future__ import print_function
7 from builtins import range
8 
9 import sys
10 
11 from argparse import ArgumentParser
12 parser = ArgumentParser(description=__doc__)
13 
14 parser.add_argument("--baudrate", type=int,
15  help="master port baud rate", default=115200)
16 parser.add_argument("--device", required=True, help="serial device")
17 parser.add_argument("--rate", default=4, type=int, help="requested stream rate")
18 parser.add_argument("--source-system", dest='SOURCE_SYSTEM', type=int,
19  default=255, help='MAVLink source system for this GCS')
20 parser.add_argument("--showmessages", action='store_true',
21  help="show incoming messages", default=False)
22 args = parser.parse_args()
23 
24 from pymavlink import mavutil
25 
27  '''wait for a heartbeat so we know the target system IDs'''
28  print("Waiting for APM heartbeat")
29  m.wait_heartbeat()
30  print("Heartbeat from APM (system %u component %u)" % (m.target_system, m.target_system))
31 
33  '''show incoming mavlink messages'''
34  while True:
35  msg = m.recv_match(blocking=True)
36  if not msg:
37  return
38  if msg.get_type() == "BAD_DATA":
39  if mavutil.all_printable(msg.data):
40  sys.stdout.write(msg.data)
41  sys.stdout.flush()
42  else:
43  print(msg)
44 
45 # create a mavlink serial instance
46 master = mavutil.mavlink_connection(args.device, baud=args.baudrate)
47 
48 # wait for the heartbeat msg to find the system ID
49 wait_heartbeat(master)
50 
51 print("Sending all stream request for rate %u" % args.rate)
52 for i in range(0, 3):
53  master.mav.request_data_stream_send(master.target_system, master.target_component,
54  mavutil.mavlink.MAV_DATA_STREAM_ALL, args.rate, 1)
55 if args.showmessages:
56  show_messages(master)


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Jul 7 2019 03:22:06