mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 09:22:18 +00:00
HITL startup: Further simplification of boot logic in commander
This commit is contained in:
@@ -470,7 +470,7 @@ then
|
||||
# Needs to be this early for in-air-restarts
|
||||
if [ $OUTPUT_MODE == hil ]
|
||||
then
|
||||
commander start -hil
|
||||
commander start --hil
|
||||
else
|
||||
commander start
|
||||
fi
|
||||
|
||||
@@ -156,17 +156,12 @@ static constexpr uint8_t COMMANDER_MAX_GPS_NOISE = 60; /**< Maximum percentage
|
||||
|
||||
#define INAIR_RESTART_HOLDOFF_INTERVAL 500000
|
||||
|
||||
#define HIL_ID_MIN 1000
|
||||
#define HIL_ID_MAX 1999
|
||||
|
||||
/* Controls the probation period which is the amount of time required for position and velocity checks to pass before the validity can be changed from false to true*/
|
||||
#define POSVEL_PROBATION_TAKEOFF 30E6 /**< probation duration set at takeoff (usec) */
|
||||
#define POSVEL_PROBATION_MIN 1E6 /**< minimum probation duration (usec) */
|
||||
#define POSVEL_PROBATION_MAX 100E6 /**< maximum probation duration (usec) */
|
||||
#define POSVEL_VALID_PROBATION_FACTOR 10 /**< the rate at which the probation duration is increased while checks are failing */
|
||||
|
||||
static bool startup_in_hil = false;
|
||||
|
||||
/*
|
||||
* Probation times for position and velocity validity checks to pass if failed
|
||||
* Signed integers are used because these can become negative values before constraints are applied
|
||||
@@ -694,9 +689,9 @@ transition_result_t arm_disarm(bool arm, orb_advert_t *mavlink_log_pub_local, co
|
||||
|
||||
// For HIL platforms, require that simulated sensors are connected
|
||||
if (arm && hrt_absolute_time() > commander_boot_timestamp + INAIR_RESTART_HOLDOFF_INTERVAL &&
|
||||
startup_in_hil && status.hil_state != vehicle_status_s::HIL_STATE_ON) {
|
||||
status.hil_state == vehicle_status_s::HIL_STATE_ON) {
|
||||
|
||||
mavlink_log_critical(mavlink_log_pub_local, "HIL platform: Connect to simulator before arming");
|
||||
mavlink_log_critical(mavlink_log_pub_local, "HITL: Connect to simulator before arming.");
|
||||
return TRANSITION_DENIED;
|
||||
}
|
||||
|
||||
@@ -1291,9 +1286,14 @@ int commander_thread_main(int argc, char *argv[])
|
||||
argv += 1;
|
||||
#endif
|
||||
|
||||
/* vehicle status topic */
|
||||
status = {};
|
||||
|
||||
status.hil_state = vehicle_status_s::HIL_STATE_OFF;
|
||||
|
||||
if (argc > 2) {
|
||||
if (!strcmp(argv[2],"-hil")) {
|
||||
startup_in_hil = true;
|
||||
if (!strcmp(argv[2],"--hil")) {
|
||||
status.hil_state = vehicle_status_s::HIL_STATE_ON;
|
||||
} else {
|
||||
PX4_ERR("Argument %s not supported, abort.", argv[2]);
|
||||
thread_should_exit = true;
|
||||
@@ -1401,9 +1401,6 @@ int commander_thread_main(int argc, char *argv[])
|
||||
PX4_ERR("Failed to register power notification callback");
|
||||
}
|
||||
|
||||
/* vehicle status topic */
|
||||
memset(&status, 0, sizeof(status));
|
||||
|
||||
// We want to accept RC inputs as default
|
||||
status_flags.rc_input_blocked = false;
|
||||
status.rc_input_mode = vehicle_status_s::RC_IN_MODE_DEFAULT;
|
||||
@@ -1413,11 +1410,6 @@ int commander_thread_main(int argc, char *argv[])
|
||||
status.nav_state = vehicle_status_s::NAVIGATION_STATE_MANUAL;
|
||||
status.arming_state = vehicle_status_s::ARMING_STATE_INIT;
|
||||
|
||||
if (startup_in_hil) {
|
||||
status.hil_state = vehicle_status_s::HIL_STATE_ON;
|
||||
} else {
|
||||
status.hil_state = vehicle_status_s::HIL_STATE_OFF;
|
||||
}
|
||||
status.failsafe = false;
|
||||
|
||||
/* neither manual nor offboard control commands have been received */
|
||||
@@ -1703,7 +1695,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||
arm_mission_required = (arm_mission_required_param == 1);
|
||||
|
||||
status.rc_input_mode = rc_in_off;
|
||||
if (startup_in_hil) {
|
||||
if (status.hil_state == vehicle_status_s::HIL_STATE_ON) {
|
||||
// HIL configuration selected: real sensors will be disabled
|
||||
status_flags.condition_system_sensors_initialized = false;
|
||||
set_tune_override(TONE_STARTUP_TUNE); //normal boot tune
|
||||
@@ -1960,7 +1952,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||
telemetry_preflight_checks_reported[i] = hotplug_timeout;
|
||||
|
||||
/* provide RC and sensor status feedback to the user */
|
||||
if (startup_in_hil) {
|
||||
if (status.hil_state == vehicle_status_s::HIL_STATE_ON) {
|
||||
/* HIL configuration: check only RC input */
|
||||
(void)Commander::preflightCheck(&mavlink_log_pub, false, false, false, false, false,
|
||||
(status.rc_input_mode == vehicle_status_s::RC_IN_MODE_DEFAULT), false,
|
||||
|
||||
@@ -482,7 +482,7 @@ transition_result_t hil_state_transition(hil_state_t new_state, orb_advert_t sta
|
||||
} else {
|
||||
switch (new_state) {
|
||||
case vehicle_status_s::HIL_STATE_OFF:
|
||||
/* we're in HIL and unexpected things can happen if we dis HITL. Sable HIL now */
|
||||
/* The system is in HITL mode and unexpected things can happen if we disable HITL without rebooting. */
|
||||
mavlink_log_critical(mavlink_log_pub, "Set SYS_HITL to 0 and reboot to disable HITL.");
|
||||
ret = TRANSITION_DENIED;
|
||||
break;
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2015 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2013-2017 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -67,11 +67,12 @@ PARAM_DEFINE_INT32(SYS_AUTOCONFIG, 0);
|
||||
/**
|
||||
* Enable HITL mode on next boot
|
||||
*
|
||||
* Set to 1 to enable HITL on next boot. The system will automatically
|
||||
* reset it on reboot.
|
||||
* While enabled the system will boot in HITL mode and not enable all sensors and checks.
|
||||
* When disabled the same vehicle can be normally flown outdoors.
|
||||
*
|
||||
* @boolean
|
||||
* @reboot_required true
|
||||
*
|
||||
* @value 0 HITL off
|
||||
* @value 1 HITL on
|
||||
* @group System
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SYS_HITL, 0);
|
||||
|
||||
@@ -49,7 +49,7 @@ const char *get_commands()
|
||||
"param set CAL_MAG0_ID 196608\n"
|
||||
// "rgbled start\n"
|
||||
// "tone_alarm start\n"
|
||||
"commander start -hil\n"
|
||||
"commander start --hil\n"
|
||||
"sensors start\n"
|
||||
"attitude_estimator_q start\n"
|
||||
"position_estimator_inav start\n"
|
||||
|
||||
Reference in New Issue
Block a user