Obtaining BlueROV2 IMU Readings Via Pymavlink

Hi all,

I’m interested in reading data from the BlueROV2 IMU magnetometer utilizing Pymavlink, so I can get the compass reading. I’ve referenced the following hyperlinks: Pymavlink · GitBook, Full Parameter List · GitBook, Python (mavgen) · MAVLink Developer Guide, Messages (common) · MAVLink Developer Guide, Messages (common) · MAVLink Developer Guide and

Messages (common) · MAVLink Developer Guide. Below is my python script:

I know that I have to request the IMU readings by requesting a data stream. When I utilize the message ID “SCALED_IMU” or “RAW_IMU” I get the following errors:

“Traceback (most recent call last):

File “Read_BlueROV2_Magnetometer.py”, line 23, in

mavutil.mavlink.SCALED_IMU, 0, 1)

AttributeError: ‘module’ object has no attribute ‘SCALED_IMU’”

“Traceback (most recent call last):

File “Read_BlueROV2_Magnetometer.py”, line 23, in

mavutil.mavlink.RAW_IMU, 0, 1)

AttributeError: ‘module’ object has no attribute ‘RAW_IMU’”

I’d appreciate any ideas to help in solving how to obtain the IMU readings from the Autopilot.

Hi @CBW3750,

I just tried this and the new broadcast already sends both the SCALED_IMU2 and RAW_IMU messages by default, so you should be able to just do

from pymavlink import mavutil

master = mavutil.mavlink_connection('udpin:0.0.0.0:513')
master.wait_heartbeat()

while True:
    msg = master.recv_match(type='SCALED_IMU2', blocking=True).to_dict()
    ... # do something with 'msg'

without needing to request a new data stream.

Note that your try-except block likely won’t work because wait_heartbeat doesn’t raise any exceptions (as far as I’m aware). If there’s something already using the UDP port you’ll get an OSError when you create the connection (before wait_heartbeat can be called), and if there’s nothing sending data to the port then wait_heartbeat by default will just wait forever. If you’re wanting to check for the second case (no data) then I’d suggest you instead do something like

timeout = 5 # maximum seconds to wait for a message
if not master.wait_heartbeat(timeout=timeout):
    raise TimeoutError(f"No heartbeat within {timeout=} seconds!")

With the >1Hz requirement for heartbeats, the timeout could in theory just be 1, but a larger number may be relevant if you want to leave time for the other device(s) to start up.

For reference, the issue you were having is a naming error. I wrote up a quick filtered list comprehension in the interactive python shell to find out what the actual name is, which you may find a useful process if you have a similar issue in future (where you know a module but not the variable/function/class name you’re after):

>>> from pymavlink import mavutil
>>> [p for p in dir(mavutil.mavlink) if '_IMU' in p]
['MAVLINK_MSG_ID_HIGHRES_IMU', 'MAVLINK_MSG_ID_RAW_IMU', 'MAVLINK_MSG_ID_SCALED_IMU', 'MAVLINK_MSG_ID_SCALED_IMU2', 'MAVLINK_MSG_ID_SCALED_IMU3', 'MAV_COMP_ID_IMU', 'MAV_COMP_ID_IMU_2', 'MAV_COMP_ID_IMU_3']
>>> mavutil.mavlink.MAVLINK_MSG_ID_RAW_IMU
27

This also matches the naming convention in our request message interval pymavlink example. I understand those examples are a bit difficult to navigate at the moment, so am currently involved in reordering them, and adding a hyperlinked table of contents and some extra examples that we’ve been meaning to add for a while. That should hopefully be sorted out by next week, and be a bit easier to see and get to the range of examples :slight_smile:

2 Likes

Thank you very much! That post was very useful. It helped me in learning that you can get the compass reading by using the MAVLink message “VFR_HUD” and the field “heading”.
Below is my code:

1 Like