aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/state_machine_helper.cpp
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-08-24 16:26:42 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-08-24 16:26:42 +0200
commite52f7770be443301a40ee6df40498c64083b4884 (patch)
tree4ce8013d008e2e78cbca76fba72813bc4f918c02 /src/modules/commander/state_machine_helper.cpp
parentbdccd69030e56381d906afeabc8305dbe18e2de6 (diff)
parent3454c42596d8c0c1bec59dec87f4a53910f83731 (diff)
downloadpx4-firmware-e52f7770be443301a40ee6df40498c64083b4884.tar.gz
px4-firmware-e52f7770be443301a40ee6df40498c64083b4884.tar.bz2
px4-firmware-e52f7770be443301a40ee6df40498c64083b4884.zip
Merge remote-tracking branch 'upstream/master' into obcfailsafe
Diffstat (limited to 'src/modules/commander/state_machine_helper.cpp')
-rw-r--r--src/modules/commander/state_machine_helper.cpp19
1 files changed, 13 insertions, 6 deletions
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 4506942ab..098ff1a3d 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -182,12 +182,19 @@ arming_state_transition(struct vehicle_status_s *status, ///< current vehicle s
// Fail transition if power levels on the avionics rail
// are measured but are insufficient
- if (status->condition_power_input_valid && ((status->avionics_power_rail_voltage > 0.0f) &&
- (status->avionics_power_rail_voltage < 4.9f))) {
-
- mavlink_log_critical(mavlink_fd, "NOT ARMING: Avionics power low: %6.2f V.", (double)status->avionics_power_rail_voltage);
- feedback_provided = true;
- valid_transition = false;
+ if (status->condition_power_input_valid && (status->avionics_power_rail_voltage > 0.0f)) {
+ // Check avionics rail voltages
+ if (status->avionics_power_rail_voltage < 4.75f) {
+ mavlink_log_critical(mavlink_fd, "NOT ARMING: Avionics power low: %6.2f Volt", (double)status->avionics_power_rail_voltage);
+ feedback_provided = true;
+ valid_transition = false;
+ } else if (status->avionics_power_rail_voltage < 4.9f) {
+ mavlink_log_critical(mavlink_fd, "CAUTION: Avionics power low: %6.2f Volt", (double)status->avionics_power_rail_voltage);
+ feedback_provided = true;
+ } else if (status->avionics_power_rail_voltage > 5.4f) {
+ mavlink_log_critical(mavlink_fd, "CAUTION: Avionics power high: %6.2f Volt", (double)status->avionics_power_rail_voltage);
+ feedback_provided = true;
+ }
}
}