AP_Arming: allow checking of pre-arm without reporting

useful for updating AP_Notify LEDs
This commit is contained in:
Andrew Tridgell 2014-01-23 21:39:55 +11:00
parent 330a4649fd
commit aae0e3c0e5
2 changed files with 55 additions and 31 deletions

View File

@ -72,12 +72,14 @@ void AP_Arming::set_enabled_checks(uint16_t ap) {
checks_to_perform = ap;
}
bool AP_Arming::barometer_checks()
bool AP_Arming::barometer_checks(bool report)
{
if ((checks_to_perform & ARMING_CHECK_ALL) ||
(checks_to_perform & ARMING_CHECK_BARO)) {
if (! barometer.healthy) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Baro not healthy!"));
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Baro not healthy!"));
}
return false;
}
}
@ -85,7 +87,7 @@ bool AP_Arming::barometer_checks()
return true;
}
bool AP_Arming::compass_checks()
bool AP_Arming::compass_checks(bool report)
{
if ((checks_to_perform) & ARMING_CHECK_ALL ||
(checks_to_perform) & ARMING_CHECK_COMPASS) {
@ -94,7 +96,9 @@ bool AP_Arming::compass_checks()
//if there is no compass and the user has specifically asked to check
//the compass, then there is a problem
if (compass == NULL && (checks_to_perform & ARMING_CHECK_COMPASS)) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: No compass detected."));
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: No compass detected."));
}
return false;
} else if (compass == NULL) {
//if the user's not asking to check and there isn't a compass
@ -103,13 +107,17 @@ bool AP_Arming::compass_checks()
}
if (! compass->healthy()) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Compass not healthy!"));
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Compass not healthy!"));
}
return false;
}
// check compass learning is on or offsets have been set
Vector3f offsets = compass->get_offsets();
if(!compass->_learn && offsets.length() == 0) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Compass not calibrated"));
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Compass not calibrated"));
}
return false;
}
@ -118,7 +126,7 @@ bool AP_Arming::compass_checks()
return true;
}
bool AP_Arming::gps_checks()
bool AP_Arming::gps_checks(bool report)
{
if ((checks_to_perform & ARMING_CHECK_ALL) ||
(checks_to_perform & ARMING_CHECK_GPS)) {
@ -127,7 +135,9 @@ bool AP_Arming::gps_checks()
//If no GPS and the user has specifically asked to check GPS, then
//there is a problem
if (gps == NULL && (checks_to_perform & ARMING_CHECK_GPS)) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: No GPS detected."));
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: No GPS detected."));
}
return false;
} else if (gps == NULL) {
//assume the user doesn't have a GPS on purpose
@ -138,7 +148,9 @@ bool AP_Arming::gps_checks()
if (!home_is_set || gps->status() != GPS::GPS_OK_FIX_3D ||
AP_Notify::flags.gps_glitching ||
AP_Notify::flags.failsafe_gps) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Bad GPS Pos"));
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Bad GPS Pos"));
}
return false;
}
}
@ -146,13 +158,15 @@ bool AP_Arming::gps_checks()
return true;
}
bool AP_Arming::battery_checks()
bool AP_Arming::battery_checks(bool report)
{
if ((checks_to_perform & ARMING_CHECK_ALL) ||
(checks_to_perform & ARMING_CHECK_BATTERY)) {
if (AP_Notify::flags.failsafe_battery) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Battery failsafe on."));
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Battery failsafe on."));
}
return false;
}
}
@ -160,24 +174,28 @@ bool AP_Arming::battery_checks()
return true;
}
bool AP_Arming::hardware_safety_check()
bool AP_Arming::hardware_safety_check(bool report)
{
// check if safety switch has been pushed
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Hardware Safety Switch"));
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Hardware Safety Switch"));
}
return false;
}
return true;
}
bool AP_Arming::manual_transmitter_checks()
bool AP_Arming::manual_transmitter_checks(bool report)
{
if ((checks_to_perform & ARMING_CHECK_ALL) ||
(checks_to_perform & ARMING_CHECK_RC)) {
if (AP_Notify::flags.failsafe_radio) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Radio failsafe on."));
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Radio failsafe on."));
}
return false;
}
@ -189,24 +207,30 @@ bool AP_Arming::manual_transmitter_checks()
return true;
}
bool AP_Arming::pre_arm_checks()
bool AP_Arming::pre_arm_checks(bool report)
{
if (! hardware_safety_check())
if (armed || require == NONE) {
// if we are already armed or don't need any arming checks
// then skip the checks
return true;
}
if (! hardware_safety_check(report))
return false;
if (! barometer_checks())
if (! barometer_checks(report))
return false;
if (! compass_checks())
if (! compass_checks(report))
return false;
if (! gps_checks())
if (! gps_checks(report))
return false;
if (! battery_checks())
if (! battery_checks(report))
return false;
if (! manual_transmitter_checks())
if (! manual_transmitter_checks(report))
return false;
//all checks passed, allow arming!
@ -228,7 +252,7 @@ bool AP_Arming::arm(uint8_t method)
return true;
}
if (pre_arm_checks()) {
if (pre_arm_checks(true)) {
armed = true;
arming_method = method;

View File

@ -48,6 +48,8 @@ public:
bool rudder_arming_enabled();
uint16_t get_enabled_checks();
bool pre_arm_checks(bool report);
//for params
static const struct AP_Param::GroupInfo var_info[];
@ -70,19 +72,17 @@ private:
void set_enabled_checks(uint16_t);
bool barometer_checks();
bool barometer_checks(bool report);
bool compass_checks();
bool compass_checks(bool report);
bool gps_checks();
bool gps_checks(bool report);
bool battery_checks();
bool battery_checks(bool report);
bool hardware_safety_check();
bool hardware_safety_check(bool report);
bool manual_transmitter_checks();
bool pre_arm_checks();
bool manual_transmitter_checks(bool report);
};
#endif //__AP_ARMING_H__