Browse Source

Copter: Change throttle_zero to check interlock and E-stop status

mission-4.1.18
Robert Lefebvre 10 years ago committed by Randy Mackay
parent
commit
9b15ea6f5c
  1. 2
      ArduCopter/ArduCopter.pde
  2. 2
      ArduCopter/control_acro.pde
  3. 2
      ArduCopter/control_autotune.pde
  4. 2
      ArduCopter/control_flip.pde
  5. 2
      ArduCopter/control_sport.pde
  6. 2
      ArduCopter/control_stabilize.pde
  7. 11
      ArduCopter/radio.pde

2
ArduCopter/ArduCopter.pde

@ -353,7 +353,7 @@ static union { @@ -353,7 +353,7 @@ static union {
uint8_t motor_test : 1; // 24 // true if we are currently performing the motors test
uint8_t initialised : 1; // 25 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
uint8_t land_complete_maybe : 1; // 26 // true if we may have landed (less strict version of land_complete)
uint8_t throttle_zero : 1; // 27 // true if the throttle stick is at zero, debounced
uint8_t throttle_zero : 1; // 27 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
uint8_t system_time_set : 1; // 28 // true if the system time has been set from the GPS
uint8_t gps_base_pos_set : 1; // 29 // true when the gps base position has been set (used for RTK gps only)
enum HomeState home_state : 2; // 30,31 // home status (unset, set, locked)

2
ArduCopter/control_acro.pde

@ -19,7 +19,7 @@ static void acro_run() @@ -19,7 +19,7 @@ static void acro_run()
int16_t pilot_throttle_scaled;
// if motors not running reset angle targets
if(!motors.armed() || g.rc_3.control_in <= 0) {
if(!motors.armed() || ap.throttle_zero) {
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
return;
}

2
ArduCopter/control_autotune.pde

@ -233,7 +233,7 @@ static bool autotune_start(bool ignore_checks) @@ -233,7 +233,7 @@ static bool autotune_start(bool ignore_checks)
}
// ensure throttle is above zero
if (g.rc_3.control_in <= 0) {
if (ap.throttle_zero) {
return false;
}

2
ArduCopter/control_flip.pde

@ -45,7 +45,7 @@ static bool flip_init(bool ignore_checks) @@ -45,7 +45,7 @@ static bool flip_init(bool ignore_checks)
}
// if in acro or stabilize ensure throttle is above zero
if ((g.rc_3.control_in <= 0) && (control_mode == ACRO || control_mode == STABILIZE)) {
if (ap.throttle_zero && (control_mode == ACRO || control_mode == STABILIZE)) {
return false;
}

2
ArduCopter/control_sport.pde

@ -26,7 +26,7 @@ static void sport_run() @@ -26,7 +26,7 @@ static void sport_run()
float takeoff_climb_rate = 0.0f;
// if not armed or throttle at zero, set throttle to zero and exit immediately
if(!motors.armed() || g.rc_3.control_in <= 0) {
if(!motors.armed() || ap.throttle_zero) {
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(g.rc_3.control_in)-throttle_average);
return;

2
ArduCopter/control_stabilize.pde

@ -24,7 +24,7 @@ static void stabilize_run() @@ -24,7 +24,7 @@ static void stabilize_run()
int16_t pilot_throttle_scaled;
// if not armed or throttle at zero, set throttle to zero and exit immediately
if(!motors.armed() || g.rc_3.control_in <= 0) {
if(!motors.armed() || ap.throttle_zero) {
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
return;
}

11
ArduCopter/radio.pde

@ -172,14 +172,19 @@ static void set_throttle_and_failsafe(uint16_t throttle_pwm) @@ -172,14 +172,19 @@ static void set_throttle_and_failsafe(uint16_t throttle_pwm)
}
#define THROTTLE_ZERO_DEBOUNCE_TIME_MS 400
// set_throttle_zero_flag - set throttle_zero flag from debounced throttle control_in
// set_throttle_zero_flag - set throttle_zero flag from debounced throttle control
// throttle_zero is used to determine if the pilot intends to shut down the motors
// Basically, this signals when we are not flying. We are either on the ground
// or the pilot has shut down the copter in the air and it is free-falling
static void set_throttle_zero_flag(int16_t throttle_control)
{
static uint32_t last_nonzero_throttle_ms = 0;
uint32_t tnow_ms = millis();
// if non-zero throttle immediately set as non-zero
if (throttle_control > 0) {
// if not using throttle interlock and non-zero throttle and not E-stopped,
// or using motor interlock and it's enabled, then motors are running,
// and we are flying. Immediately set as non-zero
if ((!ap.using_interlock && (throttle_control > 0) && !ap.motor_estop) || (ap.using_interlock && ap.motor_interlock)) {
last_nonzero_throttle_ms = tnow_ms;
ap.throttle_zero = false;
} else if (tnow_ms - last_nonzero_throttle_ms > THROTTLE_ZERO_DEBOUNCE_TIME_MS) {

Loading…
Cancel
Save