VTOL transition switch parameter checking (#5545)

* VTOL transition switch parameter checking

* Code style
This commit is contained in:
Sander Smeets 2016-09-26 10:18:23 +02:00 committed by Lorenz Meier
parent bd922e4eed
commit c4eabbd083
6 changed files with 33 additions and 7 deletions

View File

@ -383,7 +383,7 @@ static bool gnssCheck(orb_advert_t *mavlink_log_pub, bool report_fail)
}
bool preflightCheck(orb_advert_t *mavlink_log_pub, bool checkMag, bool checkAcc, bool checkGyro,
bool checkBaro, bool checkAirspeed, bool checkRC, bool checkGNSS, bool checkDynamic, bool reportFailures)
bool checkBaro, bool checkAirspeed, bool checkRC, bool checkGNSS, bool checkDynamic, bool isVTOL, bool reportFailures)
{
#ifdef __PX4_QURT
@ -524,7 +524,7 @@ bool preflightCheck(orb_advert_t *mavlink_log_pub, bool checkMag, bool checkAcc,
/* ---- RC CALIBRATION ---- */
if (checkRC) {
if (rc_calibration_check(mavlink_log_pub, reportFailures) != OK) {
if (rc_calibration_check(mavlink_log_pub, reportFailures, isVTOL) != OK) {
if (reportFailures) {
mavlink_and_console_log_critical(mavlink_log_pub, "RC calibration check failed");
}

View File

@ -67,7 +67,7 @@ namespace Commander
* true if the GNSS receiver should be checked
**/
bool preflightCheck(orb_advert_t *mavlink_log_pub, bool checkMag, bool checkAcc,
bool checkGyro, bool checkBaro, bool checkAirspeed, bool checkRC, bool checkGNSS, bool checkDynamic, bool reportFailures = false);
bool checkGyro, bool checkBaro, bool checkAirspeed, bool checkRC, bool checkGNSS, bool checkDynamic, bool isVTOL, bool reportFailures = false);
const unsigned max_mandatory_gyro_count = 1;
const unsigned max_optional_gyro_count = 3;

View File

@ -1572,7 +1572,7 @@ int commander_thread_main(int argc, char *argv[])
// sensor diagnostics done continuously, not just at boot so don't warn about any issues just yet
status_flags.condition_system_sensors_initialized = Commander::preflightCheck(&mavlink_log_pub, true, true, true, true,
checkAirspeed, (status.rc_input_mode == vehicle_status_s::RC_IN_MODE_DEFAULT),
!can_arm_without_gps, /*checkDynamic */ false, /* reportFailures */ false);
!can_arm_without_gps, /*checkDynamic */ false, is_vtol(&status), /* reportFailures */ false);
set_tune_override(TONE_STARTUP_TUNE); //normal boot tune
}

View File

@ -1100,7 +1100,7 @@ int preflight_check(struct vehicle_status_s *status, orb_advert_t *mavlink_log_p
bool preflight_ok = Commander::preflightCheck(mavlink_log_pub, true, true, true, true,
checkAirspeed, (status->rc_input_mode == vehicle_status_s::RC_IN_MODE_DEFAULT),
!can_arm_without_gps, true, reportFailures);
!can_arm_without_gps, true, status->is_vtol, reportFailures);
if (!status_flags->circuit_breaker_engaged_usb_check && status_flags->usb_connected && prearm) {
preflight_ok = false;

View File

@ -52,7 +52,7 @@
#define RC_INPUT_MAP_UNMAPPED 0
int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail)
int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool isVTOL)
{
char nbuf[20];
@ -68,6 +68,32 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail)
unsigned j = 0;
/* if VTOL, check transition switch mapping */
if (isVTOL) {
param_t trans_parm = param_find("RC_MAP_TRANS_SW");
if (trans_parm == PARAM_INVALID) {
if (report_fail) { mavlink_and_console_log_critical(mavlink_log_pub, "ERR: RC_MAP_TRANS_SW PARAMETER MISSING"); }
/* give system time to flush error message in case there are more */
usleep(100000);
map_fail_count++;
} else {
int32_t transition_switch;
param_get(trans_parm, &transition_switch);
if (transition_switch < 1) {
if (report_fail) { mavlink_and_console_log_critical(mavlink_log_pub, "ERR: transition switch (RC_MAP_TRANS_SW) not set"); }
map_fail_count++;
}
}
}
/* first check channel mappings */
while (rc_map_mandatory[j] != 0) {

View File

@ -49,6 +49,6 @@ __BEGIN_DECLS
* @return 0 / OK if RC calibration is ok, index + 1 of the first
* channel that failed else (so 1 == first channel failed)
*/
__EXPORT int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail);
__EXPORT int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool isVTOL);
__END_DECLS