mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_MotorsUGV: add mainsail to servo test
This commit is contained in:
parent
fa0fc5eade
commit
a59b83af9a
@ -398,6 +398,12 @@ bool AP_MotorsUGV::output_test_pct(motor_test_order motor_seq, float pct)
|
||||
}
|
||||
break;
|
||||
}
|
||||
case MOTOR_TEST_MAINSAIL: {
|
||||
if (SRV_Channels::function_assigned(SRV_Channel::k_mainsail_sheet)) {
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_mainsail_sheet, pct);
|
||||
}
|
||||
break;
|
||||
}
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
@ -452,6 +458,12 @@ bool AP_MotorsUGV::output_test_pwm(motor_test_order motor_seq, float pwm)
|
||||
}
|
||||
break;
|
||||
}
|
||||
case MOTOR_TEST_MAINSAIL: {
|
||||
if (SRV_Channels::function_assigned(SRV_Channel::k_mainsail_sheet)) {
|
||||
SRV_Channels::set_output_pwm(SRV_Channel::k_mainsail_sheet, pwm);
|
||||
}
|
||||
break;
|
||||
}
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
|
@ -23,6 +23,7 @@ public:
|
||||
MOTOR_TEST_STEERING = 2,
|
||||
MOTOR_TEST_THROTTLE_LEFT = 3,
|
||||
MOTOR_TEST_THROTTLE_RIGHT = 4,
|
||||
MOTOR_TEST_MAINSAIL = 5
|
||||
};
|
||||
|
||||
// supported custom motor configurations
|
||||
|
Loading…
Reference in New Issue
Block a user