The interval of getting data

Hi, I find that when I get ‘SCALED_IMU2’ data using pymavlink, it costs time close to 0.5s no matter how I set the frequency of ‘request_message_interval’.However, when I get ‘ATTITUDE’ data, it takes the same time as I set. And I remenber all the requesting data was fine before, could anyone tell me what’s wrong with it? Thanks a lot.

Hi, I meet weired problems during using ‘request_message_interval’ with mavutil.That is the interval of getting ‘ATTITUDE’ data doesn’t change with the frequency I set which results in consuming time close to 0.5s, but it did work well before. I remember I haven’t changed the applied firmware, so what’s wrong with it? Thank you very much.

Hi @leaf,

I expect this is an issue with mavproxy configuration in Companion. I would need to look more into it to find the cause and a potential fix, but are you able to use BlueOS instead? Companion is no longer being developed, so we recommend switching to BlueOS unless your application requires one of the small number of features that is not yet implemented.

I’ve just tested, and didn’t have any issues requesting a given interval for the SCALED_IMU2 message when using BlueOS :slight_smile:

Hi, I have been trying to use BlueOS,but it is sad that the interval of getting data still takes too long as showed below.

time1 = time.time()
get_data = np.zeros(10)
msg = vehicle.recv_match(type="ATTITUDE", blocking=True)
roll, pitch, yaw = msg.roll, msg.pitch, msg.yaw
rollspeed, pitchspeed, yawspeed = msg.rollspeed, msg.pitchspeed, msg.yawspeed

time2 = time.time()
msg22 = vehicle.recv_match(type="SCALED_IMU2", blocking=True)
# extract parameters of interest
xacc, yacc, zacc = msg22.xacc, msg22.yacc, msg22.zacc
time3 = time.time()
xacc = 0
yacc = 0
zacc = 0
msg22 = vehicle.recv_match(type="RAW_IMU", blocking=True)
xacc, yacc, zacc = msg22.xacc, msg22.yacc, msg22.zacc
time4 = time.time()

msg3 = vehicle.recv_match(type="VFR_HUD", blocking=True)
# extract parameters of interest
dep = msg3.alt


I got the data four times with request_message_interval(mavutil.mavlink.MAVLINK_MSG_ID_AHRS2, 50) and request_message_interval(mavutil.mavlink.MAVLINK_MSG_ID_ATTITUDE, 50), but it seems that the interval of getting them can’t stay stable. Is there anything wrong with my usage or something else?

There are multiple potential problems here:

  1. Taking measurements and sending data both take time, and the autopilot has other things to do as well.
    • Your requested consistent 50 microsecond period (20 kHz rate) between messages of the same type is too short, and will not be achievable.
    • I did some testing and requested only the AHRS2 message, and was able to receive it reasonably consistently at about a 5000 microsecond period (200 Hz), and less consistently a bit faster. The maximum rate will likely slow down if several other messages are requested at a similar rate.
    • If you need high data rates then you most likely should be working on code that runs on the autopilot (e.g. a custom flight mode in ArduSub), rather than trying to do something external via MAVlink. That will also give lower measurement and control latency, which can be important/beneficial.
  2. Each blocking call to recv_match means messages will be received and discarded until the specified type is found.
    • That includes messages of other types that you’re looking for, so you may be measuring incorrect slow rates because you’re throwing away desired messages that are received when your code is waiting for a different one.
    • If you’re looking for multiple message types you can either
      • wait for any message from a set of types (instead of a single type), and handle the messages as they arrive (regardless of order)
        from time import perf_counter
        from pymavlink import mavutil
        
        ... # set up vehicle connection, request messages as required
        
        message_types = {'ATTITUDE', 'SCALED_IMU2', 'AHRS2'}
        
        def handle_attitude_message(msg):
            roll, pitch, yaw = msg.roll, msg.pitch, msg.yaw
            print('ATTITUDE', roll, pitch, yaw)
        
        def handle_imu_message(msg):
            xacc, yacc, zacc = msg.xacc, msg.yacc, msg.zacc
            print('SCALED_IMU2', xacc, yacc, zacc)
        
        message_handlers = {
            'ATTITUDE': handle_attitude_message,
            'SCALED_IMU2': handle_imu_message
        }
        
        def handle_message(message):
            type_ = message.get_type()
            if type_ in message_handlers:
                message_handlers[type_](message)
            else:
                print(type_)
        
        print('press CTRL+C to stop')
        while "receiving messages":
            message = vehicle.recv_match(type=message_types, blocking=True)
            handle_message(message)
        
      • wait from a set of types that you reduce (using set.remove(msg.get_type())) as each type arrives (e.g. you can put the messages into a dictionary or dataclass (based on their ID) as they arrive, and once the set is empty you can process all the messages as a batch, in the order you want to)
        ... # imports / vehicle / handlers setup
        
        latest_messages = {}
        
        prev = perf_counter()
        for batch in range(15):
            waiting_for_messages = message_types.copy()
            while waiting_for_messages:
                message = vehicle.recv_match(type=waiting_for_messages, blocking=True)
                type_ = message.get_type()
                # store the message
                latest_messages[type_] = message
                # stop waiting for it
                waiting_for_messages.remove(type_)
            new = perf_counter()
            print(f'batch arrived after {new - prev : .5f} seconds')
            prev = new
            # handle messages (specific order)
            handle_attitude_message(latest_messages['ATTITUDE'])
            handle_imu_message(latest_messages['SCALED_IMU2'])
            # OR handle messages (all in batch)
            #for type_ in message_types:
            #    handle_message(latest_messages[type_])
            new = perf_counter()
            print(f'handling took {new - prev : .5f} seconds')
            prev = new
        
      • create one or more callback functions to handle the message(s) you care about, and add them to the vehicle.message_hooks list so they get called every time any message is received (e.g. you can then have a main loop that just does blocking waits for heartbeat messages, and useful actions are instead handled within the callback function(s))
        ... # imports / vehicle / handlers setup
        
        def message_hook(vehicle, message):
            type_ = message.get_type()
            if type_ in message_handlers:
                message_handlers[type_](message)
            else:
                print(type_)
        
        vehicle.message_hooks.append(message_hook)
        
        print('press CTRL+C or disconnect vehicle to stop')
        while "handling messages":
            msg = vehicle.recv_match(type='HEARTBEAT', blocking=True, timeout=1.5)
            if msg is None:
                print('HEARTBEAT lost! Stopping program')
                break
            ... # can also be a good place to _send_ heartbeats to the vehicle
        
        This kind of approach would likely also work well together with periodic events.

By the way, I’ve changed your code screenshot into a code block, which makes it easier to copy and test with. You can read more about that in the Formatting a Post/Comment section of the How to Use the Blue Robotics Forums post :slight_smile: