mirror of https://github.com/ArduPilot/ardupilot
Copter: compassmot and motor_test set_soft_armed
This commit is contained in:
parent
1a7284ca73
commit
bce5154b2d
|
@ -125,6 +125,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
|
||||||
init_rc_out();
|
init_rc_out();
|
||||||
enable_motor_output();
|
enable_motor_output();
|
||||||
motors->armed(true);
|
motors->armed(true);
|
||||||
|
hal.util->set_soft_armed(true);
|
||||||
|
|
||||||
// initialise run time
|
// initialise run time
|
||||||
last_run_time = millis();
|
last_run_time = millis();
|
||||||
|
@ -230,6 +231,7 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
|
||||||
// stop motors
|
// stop motors
|
||||||
motors->output_min();
|
motors->output_min();
|
||||||
motors->armed(false);
|
motors->armed(false);
|
||||||
|
hal.util->set_soft_armed(false);
|
||||||
|
|
||||||
// set and save motor compensation
|
// set and save motor compensation
|
||||||
if (updated) {
|
if (updated) {
|
||||||
|
|
|
@ -41,6 +41,7 @@ void Copter::motor_test_output()
|
||||||
motor_test_start_ms = now;
|
motor_test_start_ms = now;
|
||||||
if (!motors->armed()) {
|
if (!motors->armed()) {
|
||||||
motors->armed(true);
|
motors->armed(true);
|
||||||
|
hal.util->set_soft_armed(true);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return;
|
return;
|
||||||
|
@ -152,6 +153,7 @@ MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t
|
||||||
init_rc_out();
|
init_rc_out();
|
||||||
enable_motor_output();
|
enable_motor_output();
|
||||||
motors->armed(true);
|
motors->armed(true);
|
||||||
|
hal.util->set_soft_armed(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
// disable throttle and gps failsafe
|
// disable throttle and gps failsafe
|
||||||
|
@ -197,6 +199,7 @@ void Copter::motor_test_stop()
|
||||||
|
|
||||||
// disarm motors
|
// disarm motors
|
||||||
motors->armed(false);
|
motors->armed(false);
|
||||||
|
hal.util->set_soft_armed(false);
|
||||||
|
|
||||||
// reset timeout
|
// reset timeout
|
||||||
motor_test_start_ms = 0;
|
motor_test_start_ms = 0;
|
||||||
|
|
Loading…
Reference in New Issue