mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
fix(dshot): map MAVLink standard ACTUATOR_OUTPUT_FUNCTION to PX4 OutputFunction (#26909)
The MAVLink standard defines ACTUATOR_OUTPUT_FUNCTION_MOTOR1=1..MOTOR16=16, but PX4 internally uses OutputFunction::Motor1=101..Motor12=112. The DShot driver only handled PX4 internal values (101+) and QGC legacy values (1101+), so any standards-compliant GCS sending the MAVLink enum values would get VEHICLE_CMD_RESULT_UNSUPPORTED back from MAV_CMD_CONFIGURE_ACTUATOR. Add a mapping from MAVLink standard values (1-16) to PX4 internal values (101-116) by adding 100, matching the existing QGC backwards-compat pattern.
This commit is contained in:
parent
1d81ecb08d
commit
d5d2ce26d7
@ -785,6 +785,11 @@ void DShot::handle_configure_actuator(const vehicle_command_s &command)
|
||||
if (function > 1000) {
|
||||
// NOTE: backwards compatibility for QGC - 1101=Motor1, 1102=Motor2, etc
|
||||
function -= 1000;
|
||||
|
||||
} else if (function >= 1 && function <= 16) {
|
||||
// MAVLink standard: ACTUATOR_OUTPUT_FUNCTION_MOTOR1=1 .. MOTOR16=16
|
||||
// PX4 internal: OutputFunction::Motor1=101 .. Motor12=112
|
||||
function += 100;
|
||||
}
|
||||
|
||||
int motor_index = -1;
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user