Hi! Are there any way to read current joystick gain and the flight mode from ardusub using pymavlink
Hi @Efe,
Yes, both of those are possible, although how to do so is currently not well documented. ArduSub sends the joystick gain via NAMED_VALUE_FLOAT
messages with the name PilotGain
, and the flight mode is sent as the custom_mode
property of every HEARTBEAT
message
You can access them via something like this:
from pymavlink import mavutil, mavlink
... # connect to vehicle
def handle_named_value_float(msg):
if msg.name == 'PilotGain':
print(f'Gain is {msg.value:.2%}')
def handle_heartbeat(msg):
flight_mode = mavlink.enums['SUB_MODE'][msg.custom_mode].name
print(f'{flight_mode = }')
message_handlers = {
'NAMED_VALUE_FLOAT': handle_named_value_float,
'HEARTBEAT': handle_heartbeat,
}
... # loop and handle messages
and then use one of the approaches covered here to do the handling.
Note that depending on your onboard computer software and the other MAVLink connections involved the NAMED_VALUE_FLOAT
messages may not be sent by default (normally QGC requests them), and there may be HEARTBEAT
messages arriving from multiple different source ids and component ids (which may need to be filtered through by confirming that e.g. msg.get_srcComponent() == master.target_component
).
thanks for your response, I figured out flight modes but I couldnt read NAMED_VALUE_FLOAT. I tried changing request message interval. But it doesnt work anyway. are the messages sent periodically or when the gain changed?
Good to hear
They’re sent periodically, but because there are multiple options for that message I’m not actually certain how to request it - I tried looking into it a bit when I was writing my initial response but didn’t manage to determine which part of a setup with the vehicle connected to QGroundControl causes the NAMED_VALUE_FLOAT
messages to send.
I’ve got this on my todo list as something to look into, but I’m not sure how long it will take. In the meantime you’re welcome to do some digging yourself if you want (both QGroundControl and ArduSub are open source after all), but otherwise you can open (and close) QGroundControl before you run your script, so the messages get requested for you.
REQUEST_DATA_STREAM
may be worth looking into, since QGC seems to use that.
I came across this post while looking for the same info. Here is what I found:
MSG_NAMED_FLOAT is part of ArduSub’s EXTENDED_STATUS messages:
The ArduSub plugin in QGC asks ArduSub to send these messages at 2Hz:
This is where ArduSub sends the message up the wire:
Hi @clyde, thanks for sharing what you found
I hope this wasn’t overly arduous to do - if you weren’t already aware of it this information is likely much easier to find in ArduSub’s (recently introduced) MAVLink Support docs. Searching the page for “gain” jumps straight to NAMED_VALUE_FLOAT:PilotGain
, and NAMED_VALUE_FLOAT
is specified as being within the SRn_EXTENDED_STATUS
stream group (in the “Stream Groups” section of those docs).
Zow, that is an amazing resource @EliotBR ! This replaces various notes I was collecting. Thanks for the pointer.
I got annoyed with not knowing what messages were implemented, and not being able to easily find where/how they’re used in the code, so I wrote a parser for the ArduPilot source that auto-generates those docs. Hopefully it’s helpful