ArduPilot飞行前检查 主要包括两个部分: 可见里面是对遥控器通道的检查,只有检查通过之后,才允许最后PWM输出。(此时输出为ShutDown状态) 执行跳转后为: 再次跳转查看,得: 同时,在最后一句
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 (uint8_t i=0; i<ARRAY_SIZE(channel_names);i++) { const RC_Channel *channel = channels[i]; const char *channel_name = channel_names[i]; // check if radio has been calibrated if (channel->get_radio_min() > 1300) { check_failed(ARMING_CHECK_RC, display_failure, "%s radio min too high", channel_name); ret = false; } if (channel->get_radio_max() < 1700) { check_failed(ARMING_CHECK_RC, display_failure, "%s radio max too low", channel_name); ret = false; } bool fail = true; if (i == 2) { // skip checking trim for throttle as older code did not check it fail = false; } if (channel->get_radio_trim() < channel->get_radio_min()) { check_failed(ARMING_CHECK_RC, display_failure, "%s radio trim below min", channel_name); if (fail) { ret = false; } } if (channel->get_radio_trim() > channel->get_radio_max()) { check_failed(ARMING_CHECK_RC, display_failure, "%s radio trim above max", channel_name); if (fail) { ret = false; } } } return ret; }
2. 1Hz解锁前检查
// performs pre-arm checks. expects to be called at 1hz. void AP_Arming_Copter::update(void) { // perform pre-arm checks & display failures every 30 seconds static uint8_t pre_arm_display_counter = PREARM_DISPLAY_PERIOD/2; pre_arm_display_counter++; bool display_fail = false; if (pre_arm_display_counter >= PREARM_DISPLAY_PERIOD) { display_fail = true; pre_arm_display_counter = 0; } pre_arm_checks(display_fail); }
bool AP_Arming_Copter::pre_arm_checks(bool display_failure) { const bool passed = run_pre_arm_checks(display_failure); set_pre_arm_check(passed); return passed; }
bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure) { // exit immediately if already armed if (copter.motors->armed()) { return true; } // check if motor interlock and Emergency Stop aux switches are used // at the same time. This cannot be allowed. if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_INTERLOCK) && rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP)){ check_failed(display_failure, "Interlock/E-Stop Conflict"); return false; } // check if motor interlock aux switch is in use // if it is, switch needs to be in disabled position to arm // otherwise exit immediately. This check to be repeated, // as state can change at any time. if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) { check_failed(display_failure, "Motor Interlock Enabled"); } // if pre arm checks are disabled run only the mandatory checks if (checks_to_perform == 0) { return mandatory_checks(display_failure); } return fence_checks(display_failure) & parameter_checks(display_failure) & motor_checks(display_failure) & pilot_throttle_checks(display_failure) & oa_checks(display_failure) & gcs_failsafe_check(display_failure) & AP_Arming::pre_arm_checks(display_failure); }
AP_Arming::pre_arm_checks(display_failure);
中,我们继续深挖,可以看到还有如下检查内容:bool AP_Arming::pre_arm_checks(bool report) { #if !APM_BUILD_TYPE(APM_BUILD_ArduCopter) if (armed || require == (uint8_t)Required::NO) { // if we are already armed or don't need any arming checks // then skip the checks return true; } #endif return hardware_safety_check(report) & barometer_checks(report) & ins_checks(report) & compass_checks(report) & gps_checks(report) & battery_checks(report) & logging_checks(report) & manual_transmitter_checks(report) & mission_checks(report) & rangefinder_checks(report) & servo_checks(report) & board_voltage_checks(report) & system_checks(report) & can_checks(report) & proximity_checks(report) & camera_checks(report) & aux_auth_checks(report); }
显示地面站信息:
通过这样的组合,我们就在地面站上看到了 熟悉的 PreArm: Barometer not healthy
本网页所有视频内容由 imoviebox边看边下-网页视频下载, iurlBox网页地址收藏管理器 下载并得到。
ImovieBox网页视频下载器 下载地址: ImovieBox网页视频下载器-最新版本下载
本文章由: imapbox邮箱云存储,邮箱网盘,ImageBox 图片批量下载器,网页图片批量下载专家,网页图片批量下载器,获取到文章图片,imoviebox网页视频批量下载器,下载视频内容,为您提供.
阅读和此文章类似的: 全球云计算