aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/state_machine_helper.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/commander/state_machine_helper.cpp')
-rw-r--r--src/modules/commander/state_machine_helper.cpp75
1 files changed, 32 insertions, 43 deletions
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 6b96e3a3f..372ba9d7d 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -52,6 +52,7 @@
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/differential_pressure.h>
+#include <uORB/topics/airspeed.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
@@ -70,8 +71,6 @@
#endif
static const int ERROR = -1;
-static int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd);
-
// This array defines the arming state transitions. The rows are the new state, and the columns
// are the current state. Using new state and current state you can index into the array which
// will be true for a valid transition or false for a invalid transition. In some cases even
@@ -89,7 +88,7 @@ static const bool arming_transitions[ARMING_STATE_MAX][ARMING_STATE_MAX] = {
};
// You can index into the array with an arming_state_t in order to get it's textual representation
-static const char *state_names[ARMING_STATE_MAX] = {
+static const char * const state_names[ARMING_STATE_MAX] = {
"ARMING_STATE_INIT",
"ARMING_STATE_STANDBY",
"ARMING_STATE_ARMED",
@@ -162,7 +161,7 @@ arming_state_transition(struct vehicle_status_s *status, /// current
// Fail transition if we need safety switch press
} else if (safety->safety_switch_available && !safety->safety_off) {
- mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Press safety switch!");
+ mavlink_log_critical(mavlink_fd, "NOT ARMING: Press safety switch!");
valid_transition = false;
}
@@ -173,16 +172,16 @@ arming_state_transition(struct vehicle_status_s *status, /// current
// Fail transition if power is not good
if (!status->condition_power_input_valid) {
- mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Connect power module.");
+ mavlink_log_critical(mavlink_fd, "NOT ARMING: Connect power module.");
valid_transition = false;
}
// 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)) {
+ 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, "#audio: NOT ARMING: Avionics power low: %6.2f V.", (double)status->avionics_power_rail_voltage);
+ mavlink_log_critical(mavlink_fd, "NOT ARMING: Avionics power low: %6.2f V.", (double)status->avionics_power_rail_voltage);
valid_transition = false;
}
}
@@ -622,19 +621,21 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd)
{
int ret;
+ bool failed = false;
int fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
if (fd < 0) {
- mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL SENSOR MISSING");
- ret = fd;
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL SENSOR MISSING");
+ failed = true;
goto system_eval;
}
ret = ioctl(fd, ACCELIOCSELFTEST, 0);
if (ret != OK) {
- mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL CALIBRATION");
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL CALIBRATION");
+ failed = true;
goto system_eval;
}
@@ -644,55 +645,43 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd)
if (ret == sizeof(acc)) {
/* evaluate values */
- float accel_scale = sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z);
-
- if (accel_scale < 9.78f || accel_scale > 9.83f) {
- mavlink_log_info(mavlink_fd, "#audio: Accelerometer calibration recommended.");
- }
+ float accel_magnitude = sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z);
- if (accel_scale > 30.0f /* m/s^2 */) {
- mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL RANGE");
+ if (accel_magnitude < 4.0f || accel_magnitude > 15.0f /* m/s^2 */) {
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL RANGE");
+ mavlink_log_critical(mavlink_fd, "hold still while arming");
/* this is frickin' fatal */
- ret = ERROR;
+ failed = true;
goto system_eval;
- } else {
- ret = OK;
}
} else {
- mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL READ");
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL READ");
/* this is frickin' fatal */
- ret = ERROR;
+ failed = true;
goto system_eval;
}
if (!status->is_rotary_wing) {
- fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY);
+ /* accel done, close it */
+ close(fd);
+ fd = orb_subscribe(ORB_ID(airspeed));
+
+ struct airspeed_s airspeed;
- if (fd < 0) {
- mavlink_log_critical(mavlink_fd, "#audio: FAIL: AIRSPEED SENSOR MISSING");
- ret = fd;
+ if ((ret = orb_copy(ORB_ID(airspeed), fd, &airspeed)) ||
+ (hrt_elapsed_time(&airspeed.timestamp) > (50 * 1000))) {
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: AIRSPEED SENSOR MISSING");
+ failed = true;
goto system_eval;
}
- struct differential_pressure_s diff_pres;
-
- ret = read(fd, &diff_pres, sizeof(diff_pres));
-
- if (ret == sizeof(diff_pres)) {
- if (fabsf(diff_pres.differential_pressure_filtered_pa > 5.0f)) {
- mavlink_log_critical(mavlink_fd, "#audio: WARNING AIRSPEED CALIBRATION MISSING");
- // XXX do not make this fatal yet
- ret = OK;
- }
- } else {
- mavlink_log_critical(mavlink_fd, "#audio: FAIL: AIRSPEED READ");
- /* this is frickin' fatal */
- ret = ERROR;
- goto system_eval;
+ if (fabsf(airspeed.indicated_airspeed_m_s > 6.0f)) {
+ mavlink_log_critical(mavlink_fd, "AIRSPEED WARNING: WIND OR CALIBRATION MISSING");
+ // XXX do not make this fatal yet
}
}
system_eval:
close(fd);
- return ret;
+ return (failed);
}