ArduPilot飞行前检查 主要包括两个部分:
1. 初始化中遥控器输入检查;
2. 1Hz解锁前检查。
附: 显示地面站信息
参考文章:Ardupilot Pre-Arm安全检查程序分析
1. 初始化中遥控器输入检查
直接跳转进去查看函数为;
bool AP_Arming_Copter::rc_calibration_checks(bool display_failure)
{
const RC_Channel *channels[] = {
copter.channel_roll,
copter.channel_pitch,
copter.channel_throttle,
copter.channel_yaw
};
copter.ap.pre_arm_rc_check = rc_checks_copter_sub(display_failure, channels)
& AP_Arming::rc_calibration_checks(display_failure);
return copter.ap.pre_arm_rc_check;
}
// Copter and sub share the same RC input limits
// Copter checks that min and max have been configured by default, Sub does not
bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channel *channels[4]) const
{
// set rc-checks to success if RC checks are disabled
if ((checks_to_perform != ARMING_CHECK_ALL) && !(checks_to_perform & ARMING_CHECK_RC)) {
return true;
}
bool ret = true;
const char *channel_names[] = {
"Roll", "Pitch", "Throttle", "Yaw" };
for (