|
|
|
@ -32,21 +32,21 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
@@ -32,21 +32,21 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
|
|
|
|
|
|
|
|
|
|
if (plane.g.roll_limit_cd < 300) { |
|
|
|
|
if (report) { |
|
|
|
|
GCS_MAVLINK::send_statustext_all(PSTR("PreArm: LIM_ROLL_CD too small (%u)"), plane.g.roll_limit_cd); |
|
|
|
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: LIM_ROLL_CD too small (%u)"), plane.g.roll_limit_cd); |
|
|
|
|
} |
|
|
|
|
ret = false;
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (plane.aparm.pitch_limit_max_cd < 300) { |
|
|
|
|
if (report) { |
|
|
|
|
GCS_MAVLINK::send_statustext_all(PSTR("PreArm: LIM_PITCH_MAX too small (%u)"), plane.aparm.pitch_limit_max_cd); |
|
|
|
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: LIM_PITCH_MAX too small (%u)"), plane.aparm.pitch_limit_max_cd); |
|
|
|
|
} |
|
|
|
|
ret = false;
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (plane.aparm.pitch_limit_min_cd > -300) { |
|
|
|
|
if (report) { |
|
|
|
|
GCS_MAVLINK::send_statustext_all(PSTR("PreArm: LIM_PITCH_MIN too large (%u)"), plane.aparm.pitch_limit_min_cd); |
|
|
|
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: LIM_PITCH_MIN too large (%u)"), plane.aparm.pitch_limit_min_cd); |
|
|
|
|
} |
|
|
|
|
ret = false;
|
|
|
|
|
} |
|
|
|
@ -56,7 +56,7 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
@@ -56,7 +56,7 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
|
|
|
|
|
plane.g.throttle_fs_value <
|
|
|
|
|
plane.channel_throttle->radio_max) { |
|
|
|
|
if (report) { |
|
|
|
|
GCS_MAVLINK::send_statustext_all(PSTR("PreArm: invalid THR_FS_VALUE for rev throttle"));
|
|
|
|
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: invalid THR_FS_VALUE for rev throttle"));
|
|
|
|
|
} |
|
|
|
|
ret = false; |
|
|
|
|
} |
|
|
|
|