Merge remote-tracking branch 'upstream/master' into obcfailsafe

This commit is contained in:
Thomas Gubler 2014-07-20 17:40:38 +02:00
commit 74417f1439
4 changed files with 201 additions and 11 deletions

View File

@ -1415,8 +1415,12 @@ int commander_thread_main(int argc, char *argv[])
arming_state_changed = true;
} else if (arming_ret == TRANSITION_DENIED) {
/* DENIED here indicates bug in the commander */
mavlink_log_critical(mavlink_fd, "arming state transition denied");
/*
* the arming transition can be denied to a number of reasons:
* - pre-flight check failed (sensors not ok or not calibrated)
* - safety not disabled
* - system not in manual mode
*/
tune_negative(true);
}

View File

@ -110,8 +110,8 @@ arming_state_transition(struct vehicle_status_s *status, /// current
ASSERT(ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1);
transition_result_t ret = TRANSITION_DENIED;
arming_state_t current_arming_state = status->arming_state;
bool feedback_provided = false;
/* only check transition if the new state is actually different from the current one */
if (new_arming_state == current_arming_state) {
@ -156,13 +156,15 @@ arming_state_transition(struct vehicle_status_s *status, /// current
// Fail transition if pre-arm check fails
if (prearm_ret) {
/* the prearm check already prints the reject reason */
feedback_provided = true;
valid_transition = false;
// Fail transition if we need safety switch press
} else if (safety->safety_switch_available && !safety->safety_off) {
mavlink_log_critical(mavlink_fd, "NOT ARMING: Press safety switch!");
mavlink_log_critical(mavlink_fd, "NOT ARMING: Press safety switch first!");
feedback_provided = true;
valid_transition = false;
}
@ -173,6 +175,7 @@ arming_state_transition(struct vehicle_status_s *status, /// current
if (!status->condition_power_input_valid) {
mavlink_log_critical(mavlink_fd, "NOT ARMING: Connect power module.");
feedback_provided = true;
valid_transition = false;
}
@ -182,6 +185,7 @@ arming_state_transition(struct vehicle_status_s *status, /// current
(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;
}
}
@ -200,6 +204,8 @@ arming_state_transition(struct vehicle_status_s *status, /// current
/* Sensors need to be initialized for STANDBY state */
if (new_arming_state == ARMING_STATE_STANDBY && !status->condition_system_sensors_initialized) {
mavlink_log_critical(mavlink_fd, "NOT ARMING: Sensors not operational.");
feedback_provided = true;
valid_transition = false;
}
@ -216,11 +222,14 @@ arming_state_transition(struct vehicle_status_s *status, /// current
}
if (ret == TRANSITION_DENIED) {
static const char *errMsg = "INVAL: %s - %s";
const char * str = "INVAL: %s - %s";
/* only print to console here by default as this is too technical to be useful during operation */
warnx(str, state_names[status->arming_state], state_names[new_arming_state]);
mavlink_log_critical(mavlink_fd, errMsg, state_names[status->arming_state], state_names[new_arming_state]);
warnx(errMsg, state_names[status->arming_state], state_names[new_arming_state]);
/* print to MAVLink if we didn't provide any feedback yet */
if (!feedback_provided) {
mavlink_log_critical(mavlink_fd, str, state_names[status->arming_state], state_names[new_arming_state]);
}
}
return ret;
@ -648,8 +657,7 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd)
float accel_magnitude = sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z);
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");
mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL RANGE, hold still");
/* this is frickin' fatal */
failed = true;
goto system_eval;

View File

@ -40,22 +40,196 @@
#include "position_estimator_inav_params.h"
/**
* Z axis weight for barometer
*
* Weight (cutoff frequency) for barometer altitude measurements.
*
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_W_Z_BARO, 0.5f);
/**
* Z axis weight for GPS
*
* Weight (cutoff frequency) for GPS altitude measurements. GPS altitude data is very noisy and should be used only as slow correction for baro offset.
*
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_P, 0.005f);
/**
* Z axis weight for sonar
*
* Weight (cutoff frequency) for sonar measurements.
*
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_W_Z_SONAR, 3.0f);
/**
* XY axis weight for GPS position
*
* Weight (cutoff frequency) for GPS position measurements.
*
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_P, 1.0f);
/**
* XY axis weight for GPS velocity
*
* Weight (cutoff frequency) for GPS velocity measurements.
*
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f);
/**
* XY axis weight for optical flow
*
* Weight (cutoff frequency) for optical flow (velocity) measurements.
*
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_W_XY_FLOW, 5.0f);
/**
* XY axis weight for resetting velocity
*
* When velocity sources lost slowly decrease estimated horizontal velocity with this weight.
*
* @min 0.0
* @max 10.0
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_W_XY_RES_V, 0.5f);
/**
* XY axis weight factor for GPS when optical flow available
*
* When optical flow data available, multiply GPS weights (for position and velocity) by this factor.
*
* @min 0.0
* @max 1.0
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_W_GPS_FLOW, 0.1f);
/**
* Accelerometer bias estimation weight
*
* Weight (cutoff frequency) for accelerometer bias estimation. 0 to disable.
*
* @min 0.0
* @max 0.1
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.05f);
/**
* Optical flow scale factor
*
* Factor to convert raw optical flow (in pixels) to radians [rad/px].
*
* @min 0.0
* @max 1.0
* @unit rad/px
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_FLOW_K, 0.15f);
/**
* Minimal acceptable optical flow quality
*
* 0 - lowest quality, 1 - best quality.
*
* @min 0.0
* @max 1.0
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_FLOW_Q_MIN, 0.5f);
/**
* Weight for sonar filter
*
* Sonar filter detects spikes on sonar measurements and used to detect new surface level.
*
* @min 0.0
* @max 1.0
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_SONAR_FILT, 0.05f);
/**
* Sonar maximal error for new surface
*
* If sonar measurement error is larger than this value it skiped (spike) or accepted as new surface level (if offset is stable).
*
* @min 0.0
* @max 1.0
* @unit m
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_SONAR_ERR, 0.5f);
/**
* Land detector time
*
* Vehicle assumed landed if no altitude changes happened during this time on low throttle.
*
* @min 0.0
* @max 10.0
* @unit s
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_LAND_T, 3.0f);
/**
* Land detector altitude dispersion threshold
*
* Dispersion threshold for triggering land detector.
*
* @min 0.0
* @max 10.0
* @unit m
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_LAND_DISP, 0.7f);
/**
* Land detector throttle threshold
*
* Value should be lower than minimal hovering thrust. Half of it is good choice.
*
* @min 0.0
* @max 1.0
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_LAND_THR, 0.2f);
/**
* GPS delay
*
* GPS delay compensation
*
* @min 0.0
* @max 1.0
* @unit s
* @group Position Estimator INAV
*/
PARAM_DEFINE_FLOAT(INAV_DELAY_GPS, 0.2f);
int parameters_init(struct position_estimator_inav_param_handles *h)

View File

@ -648,6 +648,10 @@ pwm_main(int argc, char *argv[])
/* force failsafe */
ret = ioctl(fd, PWM_SERVO_SET_FORCE_FAILSAFE, 0);
}
if (ret != OK) {
warnx("FAILED setting forcefail %s", argv[2]);
}
}
exit(0);
}