Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

mavproxy_param: handle param set requests asynchronously #1408

Merged
merged 1 commit into from
Dec 22, 2024

Conversation

peterbarker
Copy link
Contributor

Stop using pymavlink's mavparm.mavset method as its retry logic is synchronous, meaning MAVProxy stops processing in the main loop in the case there are link issues occuring

Creates an internal queue of parameters to send. These are copied into a dictionary which is processed in mavproy_param's idle task.

Tested:

  • can set values(!)
  • good error message when invalid value supplied
  • SITL and real board
  • returned value matches sent value (and good message for mismatch)
  • setting parameters when the autopilot goes away times out
  • new-sets override old-sets
  • retry logic works (SITL-only by ctrl-z'ing the simulation while attempting the set, fg'ing after 1 second has passed, inspecting PARAM_VALUE messages received)
ACRO> param set RC3_OPTION 43
ACRO> param fetch RC3_OPTION
ACRO> Requested parameter RC3_OPTION
RC3_OPTION = 43.0000000

ACRO> 
ACRO> param set RC3_OPTION 48
ACRO> param fetch RC3_OPTION
ACRO> Requested parameter RC3_OPTION
RC3_OPTION = 48.0000000
param set RC3_OPTION bob
ACRO> can't convert RC3_OPTION (bob, <class 'str'>) to float
can't send RC3_OPTION of type None
Failed to set RC3_OPTION to bob (no PARAM_VALUE received)
ACRO> param set RC3_OPTION 78.2
ACRO> Failed to set RC3_OPTION to 78.2 (invalid returned value 78.0)
ACRO> param fetch RC3_OPTION
ACRO> Requested parameter RC3_OPTION
RC3_OPTION = 78.0000000

ACRO> param set RC3_OPTION 9
ACRO> AP: PreArm: check firmware or FRAME_CLASS
Device /dev/serial/by-id/usb-Hex_ProfiCNC_CubeOrange_3C0028001151383439343731-if00 is dead

ACRO> param set RC3_OPTION 9link 1 down
10
ACRO> no link
Failed to set RC3_OPTION to 10 (no PARAM_VALUE received)
no link
no link

ACRO> param set RC3_OPTION 10
ACRO> param set RC3_OPTION 9
ACRO> no link
Failed to set RC3_OPTION to 9 (no PARAM_VALUE received)
no link
no link
no link

ACRO> param set RC3_OPTION 9no link
13
ACRO> param set RC14 no link13
Failed to set RC3_OPTION to 13 (no PARAM_VALUE received)

ACRO> no link

ACRO> 
ACRO> param set no linkION 13

ACRO> param set RC4no link 13

ACRO> 
ACRO> 
ACRO> 
ACRO> 
ACRO> no link
Failed to set RC4_OPTION to 13 (no PARAM_VALUE received)
no link
no link
no link

ACRO> 
ACRO> no link
param set RC4_OPTION 13no link

ACRO> 
ACRO> param set RC4no link 13
3
ACRO> Failed to set RC4_OPTION to 13 (no PARAM_VALUE received)
no link
Failed to set RC3_OPTION to 13 (no PARAM_VALUE received)

Stop using pymavlink's mavparm.mavset method as its retry logic is synchronous, meaning MAVProxy stops processing in the main loop in the case there are link issues occuring

Creates an internal queue of parameters to send.  These are copied into a dictionary which is processed in mavproy_param's idle task.
@peterbarker peterbarker merged commit 7aecc5a into ArduPilot:master Dec 22, 2024
2 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

1 participant