Copter: allow motor test using raw pwm without RC cal
This commit is contained in:
parent
2e6d79f449
commit
d9342ed854
@ -67,11 +67,11 @@ static void motor_test_output()
|
||||
|
||||
// mavlink_motor_test_check - perform checks before motor tests can begin
|
||||
// return true if tests can continue, false if not
|
||||
static bool mavlink_motor_test_check(mavlink_channel_t chan)
|
||||
static bool mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc)
|
||||
{
|
||||
// check rc has been calibrated
|
||||
pre_arm_rc_checks();
|
||||
if(!ap.pre_arm_rc_check) {
|
||||
if(check_rc && !ap.pre_arm_rc_check) {
|
||||
gcs[chan-MAVLINK_COMM_0].send_text_P(SEVERITY_HIGH,PSTR("Motor Test: RC not calibrated"));
|
||||
return false;
|
||||
}
|
||||
@ -98,8 +98,11 @@ static uint8_t mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_se
|
||||
{
|
||||
// if test has not started try to start it
|
||||
if (!ap.motor_test) {
|
||||
// perform checks that it is ok to start test
|
||||
if (!mavlink_motor_test_check(chan)) {
|
||||
/* perform checks that it is ok to start test
|
||||
The RC calibrated check can be skipped if direct pwm is
|
||||
supplied
|
||||
*/
|
||||
if (!mavlink_motor_test_check(chan, throttle_type != 1)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
} else {
|
||||
// start test
|
||||
|
Loading…
Reference in New Issue
Block a user