mirror of https://github.com/ArduPilot/ardupilot
Sub: Handle RC input for SITL autotest
This commit is contained in:
parent
053f0b4ce7
commit
81935f6b7c
|
@ -20,10 +20,13 @@ void Sub::update_arming_checks(void)
|
|||
// performs pre-arm checks and arming checks
|
||||
bool Sub::all_arming_checks_passing(bool arming_from_gcs)
|
||||
{
|
||||
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||
if (failsafe.manual_control) {
|
||||
gcs_send_text(MAV_SEVERITY_WARNING, "Arming requires manual control");
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (pre_arm_checks(true)) {
|
||||
set_pre_arm_check(true);
|
||||
}
|
||||
|
|
|
@ -44,6 +44,7 @@ void Sub::init_rc_in()
|
|||
// set default dead zones
|
||||
default_dead_zones();
|
||||
|
||||
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||
// initialize rc input to 1500 on control channels (rather than 0)
|
||||
for (int i = 0; i < 7; i++) {
|
||||
if (i == 4) {
|
||||
|
@ -52,6 +53,7 @@ void Sub::init_rc_in()
|
|||
hal.rcin->set_override(i, 1500);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// initialise throttle_zero flag
|
||||
ap.throttle_zero = true;
|
||||
|
|
Loading…
Reference in New Issue