Copter: rename manual_flight_mode to mode_has_manual_throttle
This commit is contained in:
parent
f225558dbd
commit
43ba94e99a
@ -1175,7 +1175,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
AP_Notify::flags.arming_failed = true; // init_arm_motors function will reset flag back to false
|
||||
result = MAV_RESULT_UNSUPPORTED;
|
||||
}
|
||||
} else if (packet.param1 == 0.0f && (manual_flight_mode(control_mode) || ap.land_complete)) {
|
||||
} else if (packet.param1 == 0.0f && (mode_has_manual_throttle(control_mode) || ap.land_complete)) {
|
||||
init_disarm_motors();
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
} else {
|
||||
|
@ -30,7 +30,7 @@ void fence_check()
|
||||
|
||||
// disarm immediately if we think we are on the ground or in a manual flight mode with zero throttle
|
||||
// don't disarm if the high-altitude fence has been broken because it's likely the user has pulled their throttle to zero to bring it down
|
||||
if (ap.land_complete || (manual_flight_mode(control_mode) && ap.throttle_zero && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0))){
|
||||
if (ap.land_complete || (mode_has_manual_throttle(control_mode) && ap.throttle_zero && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0))){
|
||||
init_disarm_motors();
|
||||
}else{
|
||||
// if we are within 100m of the fence, RTL
|
||||
|
@ -215,7 +215,7 @@ static void exit_mode(uint8_t old_control_mode, uint8_t new_control_mode)
|
||||
}
|
||||
|
||||
// smooth throttle transition when switching from manual to automatic flight modes
|
||||
if (manual_flight_mode(old_control_mode) && !manual_flight_mode(new_control_mode) && motors.armed() && !ap.land_complete) {
|
||||
if (mode_has_manual_throttle(old_control_mode) && !mode_has_manual_throttle(new_control_mode) && motors.armed() && !ap.land_complete) {
|
||||
// this assumes all manual flight modes use get_pilot_desired_throttle to translate pilot input to output throttle
|
||||
set_accel_throttle_I_from_pilot_throttle(get_pilot_desired_throttle(g.rc_3.control_in));
|
||||
}
|
||||
@ -246,8 +246,8 @@ static bool mode_requires_GPS(uint8_t mode) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// manual_flight_mode - returns true if flight mode is completely manual (i.e. roll, pitch, yaw and throttle are controlled by pilot)
|
||||
static bool manual_flight_mode(uint8_t mode) {
|
||||
// mode_has_manual_throttle - returns true if the flight mode has a manual throttle (i.e. pilot directly controls throttle)
|
||||
static bool mode_has_manual_throttle(uint8_t mode) {
|
||||
switch(mode) {
|
||||
case ACRO:
|
||||
case STABILIZE:
|
||||
@ -262,7 +262,7 @@ static bool manual_flight_mode(uint8_t mode) {
|
||||
// mode_allows_arming - returns true if vehicle can be armed in the specified mode
|
||||
// arming_from_gcs should be set to true if the arming request comes from the ground station
|
||||
static bool mode_allows_arming(uint8_t mode, bool arming_from_gcs) {
|
||||
if (manual_flight_mode(mode) || mode == LOITER || mode == ALT_HOLD || mode == POSHOLD || (arming_from_gcs && mode == GUIDED)) {
|
||||
if (mode_has_manual_throttle(mode) || mode == LOITER || mode == ALT_HOLD || mode == POSHOLD || (arming_from_gcs && mode == GUIDED)) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
@ -55,7 +55,7 @@ static void arm_motors_check()
|
||||
|
||||
// full left
|
||||
}else if (tmp < -4000) {
|
||||
if (!manual_flight_mode(control_mode) && !ap.land_complete) {
|
||||
if (!mode_has_manual_throttle(control_mode) && !ap.land_complete) {
|
||||
arming_counter = 0;
|
||||
return;
|
||||
}
|
||||
@ -88,7 +88,7 @@ static void auto_disarm_check()
|
||||
}
|
||||
|
||||
// allow auto disarm in manual flight modes or Loiter/AltHold if we're landed
|
||||
if (manual_flight_mode(control_mode) || ap.land_complete) {
|
||||
if (mode_has_manual_throttle(control_mode) || ap.land_complete) {
|
||||
auto_disarming_counter++;
|
||||
|
||||
if(auto_disarming_counter >= AUTO_DISARMING_DELAY) {
|
||||
|
@ -368,7 +368,7 @@ static void update_auto_armed()
|
||||
return;
|
||||
}
|
||||
// if in stabilize or acro flight mode and throttle is zero, auto-armed should become false
|
||||
if(manual_flight_mode(control_mode) && ap.throttle_zero && !failsafe.radio) {
|
||||
if(mode_has_manual_throttle(control_mode) && ap.throttle_zero && !failsafe.radio) {
|
||||
set_auto_armed(false);
|
||||
}
|
||||
}else{
|
||||
|
Loading…
Reference in New Issue
Block a user