Hi @Efe,
You can set the Button Parameters using the PARAM_SET
MAVLink message. To set button 1 to arm the vehicle on normal press and disarm the vehicle on shifted-press you can set BTN1_FUNCTION
to 3 and BTN1_SFUNCTION
to 4.
Our pymavlink example is a bit dated but should still work (although the note about the value being set only temporarily is incorrect). There’s a more recent example here, as part of a more complete program (which requires Python >= 3.8).
A minimal example for specifically setting the button functions would be
from typing import Union, Iterable
from pymavlink import mavutil
import time
AXIS_UNUSED = 0x7fff # INT16_MAX (manual control)
# from ardusub.com/developers/full-parameter-list.html#btnn-parameters
ARDUSUB_BTN_FUNCTIONS = {
'disabled': 0,
'shift': 1,
'arm': 3,
'disarm': 4,
'mode_manual': 5,
'mode_depth_hold': 7,
'mount_center': 21,
'mount_tilt_up': 22,
'mount_tilt_down': 23,
'lights1_brighter': 32,
'lights1_dimmer': 33,
'gain_inc': 42,
'gain_dec': 43,
# ... any others you're interested in
}
def set_param(autopilot, name: str, value: float, type: int,
timeout: float=1):
name = name.encode('utf8')
autopilot.mav.param_set_send(
autopilot.target_system, autopilot.target_component,
name, value, type
)
msg = autopilot.recv_match(type='PARAM_VALUE', blocking=True,
timeout=timeout)
# TODO: retries and/or verification that parameter is correctly set
return msg
def set_button_function(autopilot, button: int, function: Union[int,str],
shifted=False):
shifted = 'S' if shifted else ''
param = f'BTN{button}_{shifted}FUNCTION'
if isinstance(function, str):
function = ARDUSUB_BTN_FUNCTIONS[function.lower()]
type = mavutil.mavlink.MAV_PARAM_TYPE_INT8
return set_param(autopilot, param, function, type)
def send_manual_control(autopilot, x=AXIS_UNUSED, y=AXIS_UNUSED, z=AXIS_UNUSED,
r=AXIS_UNUSED, pressed_buttons: Union[int, Iterable[int]] = 0):
'''
'pressed_buttons' is either
a bit-field with 1 bits for pressed buttons (bit 0 -> button 0), or
an iterable specifying which buttons are pressed (e.g. [0,3,4])
'''
if not isinstance(pressed_buttons, int):
# convert iterable into bit-field values
pressed_buttons = sum(1 << button for button in pressed_buttons)
autopilot.mav.manual_control_send(
autopilot.target_system,
x, y, z, r,
pressed_buttons
)
def press_release_buttons(autopilot, buttons):
send_manual_control(autopilot, pressed_buttons=buttons)
send_manual_control(autopilot, pressed_buttons=0)
autopilot = mavutil.mavlink_connection('udpin:0.0.0.0:14550')
autopilot.wait_heartbeat()
print('autopilot connected!')
# assign button 2 to the 'shift' functionality
set_button_function(autopilot, 2, 'shift')
# assign button 1 to brighten lights1 on normal press, and dim them on shifted press
set_button_function(autopilot, 1, 'lights1_brighter')
set_button_function(autopilot, 1, 'lights1_dimmer', shifted=True)
press_release_buttons(autopilot, [1]) # make lights1 brighter
time.sleep(2) # wait a couple of seconds
press_release_buttons(autopilot, [1]) # make them another step brighter
time.sleep(2.5) # wait some more
press_release_buttons(autopilot, [1, 2]) # make them dimmer
time.sleep(1)
press_release_buttons(autopilot, [1, 2]) # dim once more
Note that if you’re sending control commands programatically (and not just changing parameters) there are various failsafes built in that you’ll need to be aware of:
Accordingly, long time.sleep
calls generally shouldn’t be used. They can be used if there are additional control commands being sent in a separate thread, or if the failsafes have been lengthened or disabled, but neither of those approaches are recommended if they’re avoidable.
Note also that many of the button functionalities have equivalent more efficient functionalities via their own MAVLink messages. Using the button functionalities is generally best left to when a human controller is using a joystick/gamepad.