#!/usr/bin/env python ''' set stream rate on an APM ''' from __future__ import print_function from builtins import range import sys from argparse import ArgumentParser parser = ArgumentParser(description=__doc__) parser.add_argument("--baudrate", type=int, help="master port baud rate", default=115200) parser.add_argument("--device", required=True, help="serial device") parser.add_argument("--rate", default=4, type=int, help="requested stream rate") parser.add_argument("--source-system", dest='SOURCE_SYSTEM', type=int, default=255, help='MAVLink source system for this GCS') parser.add_argument("--showmessages", action='store_true', help="show incoming messages", default=False) args = parser.parse_args() from pymavlink import mavutil def wait_heartbeat(m): '''wait for a heartbeat so we know the target system IDs''' print("Waiting for APM heartbeat") m.wait_heartbeat() print("Heartbeat from APM (system %u component %u)" % (m.target_system, m.target_system)) def show_messages(m): '''show incoming mavlink messages''' while True: msg = m.recv_match(blocking=True) if not msg: return if msg.get_type() == "BAD_DATA": if mavutil.all_printable(msg.data): sys.stdout.write(msg.data) sys.stdout.flush() else: print(msg) # create a mavlink serial instance master = mavutil.mavlink_connection(args.device, baud=args.baudrate) # wait for the heartbeat msg to find the system ID wait_heartbeat(master) print("Sending all stream request for rate %u" % args.rate) for i in range(0, 3): master.mav.request_data_stream_send(master.target_system, master.target_component, mavutil.mavlink.MAV_DATA_STREAM_ALL, args.rate, 1) if args.showmessages: show_messages(master)