Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Rover/AP_Arming.cpp
Views: 1798
#include "AP_Arming.h"1#include "Rover.h"23// perform pre_arm_rc_checks checks4bool AP_Arming_Rover::rc_calibration_checks(const bool display_failure)5{6// set rc-checks to success if RC checks are disabled7if (!check_enabled(ARMING_CHECK_RC)) {8return true;9}1011const RC_Channel *channels[] = {12rover.channel_steer,13rover.channel_throttle14};15const char *channel_names[] = {"Steer", "Throttle"};1617for (uint8_t i= 0 ; i < ARRAY_SIZE(channels); i++) {18const RC_Channel *channel = channels[i];19const char *channel_name = channel_names[i];20// check if radio has been calibrated21if (channel->get_radio_min() > RC_Channel::RC_CALIB_MIN_LIMIT_PWM) {22check_failed(ARMING_CHECK_RC, display_failure, "%s radio min too high", channel_name);23return false;24}25if (channel->get_radio_max() < RC_Channel::RC_CALIB_MAX_LIMIT_PWM) {26check_failed(ARMING_CHECK_RC, display_failure, "%s radio max too low", channel_name);27return false;28}29}30return AP_Arming::rc_calibration_checks(display_failure);31}3233// performs pre_arm gps related checks and returns true if passed34bool AP_Arming_Rover::gps_checks(bool display_failure)35{36if (!rover.control_mode->requires_position() && !rover.control_mode->requires_velocity()) {37// we don't care!38return true;39}4041// call parent gps checks42if (!AP_Arming::gps_checks(display_failure)) {43return false;44}4546const AP_AHRS &ahrs = AP::ahrs();4748// always check if inertial nav has started and is ready49char failure_msg[50] = {};50if (!ahrs.pre_arm_check(true, failure_msg, sizeof(failure_msg))) {51check_failed(display_failure, "AHRS: %s", failure_msg);52return false;53}5455// check for ekf failsafe56if (rover.failsafe.ekf) {57check_failed(display_failure, "EKF failsafe");58return false;59}6061// ensure position estimate is ok62if (!rover.ekf_position_ok()) {63// vehicle level position estimate checks64check_failed(display_failure, "Need Position Estimate");65return false;66}6768return true;69}7071bool AP_Arming_Rover::pre_arm_checks(bool report)72{73if (armed) {74// if we are already armed then skip the checks75return true;76}7778//are arming checks disabled?79if (checks_to_perform == 0) {80return mandatory_checks(report);81}8283if (rover.g2.sailboat.sail_enabled() && !rover.g2.windvane.enabled()) {84check_failed(report, "Sailing enabled with no WindVane");85return false;86}8788return (AP_Arming::pre_arm_checks(report)89& motor_checks(report)90#if AP_OAPATHPLANNER_ENABLED91& oa_check(report)92#endif93& parameter_checks(report)94& mode_checks(report));95}9697bool AP_Arming_Rover::arm_checks(AP_Arming::Method method)98{99//are arming checks disabled?100if (checks_to_perform == 0) {101return true;102}103return AP_Arming::arm_checks(method);104}105106void AP_Arming_Rover::update_soft_armed()107{108hal.util->set_soft_armed(is_armed() &&109hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);110#if HAL_LOGGING_ENABLED111AP::logger().set_vehicle_armed(hal.util->get_soft_armed());112#endif113}114115/*116arm motors117*/118bool AP_Arming_Rover::arm(AP_Arming::Method method, const bool do_arming_checks)119{120if (!AP_Arming::arm(method, do_arming_checks)) {121AP_Notify::events.arming_failed = true;122return false;123}124125// Set the SmartRTL home location. If activated, SmartRTL will ultimately try to land at this point126rover.g2.smart_rtl.set_home(true);127128// initialize simple mode heading129rover.mode_simple.init_heading();130131// save home heading for use in sail vehicles132rover.g2.windvane.record_home_heading();133134update_soft_armed();135136send_arm_disarm_statustext("Throttle armed");137138return true;139}140141/*142disarm motors143*/144bool AP_Arming_Rover::disarm(const AP_Arming::Method method, bool do_disarm_checks)145{146if (!AP_Arming::disarm(method, do_disarm_checks)) {147return false;148}149if (rover.control_mode != &rover.mode_auto) {150// reset the mission on disarm if we are not in auto151rover.mode_auto.mission.reset();152}153154update_soft_armed();155156send_arm_disarm_statustext("Throttle disarmed");157158return true;159}160161#if AP_OAPATHPLANNER_ENABLED162// check object avoidance has initialised correctly163bool AP_Arming_Rover::oa_check(bool report)164{165char failure_msg[50] = {};166if (rover.g2.oa.pre_arm_check(failure_msg, ARRAY_SIZE(failure_msg))) {167return true;168}169170check_failed(report, "%s", failure_msg);171return false;172}173#endif // AP_OAPATHPLANNER_ENABLED174175// perform parameter checks176bool AP_Arming_Rover::parameter_checks(bool report)177{178// success if parameter checks are disabled179if (!check_enabled(ARMING_CHECK_PARAMETERS)) {180return true;181}182183// check waypoint speed is positive184if (!is_positive(rover.g2.wp_nav.get_default_speed())) {185check_failed(ARMING_CHECK_PARAMETERS, report, "WP_SPEED too low");186return false;187}188189return true;190}191192// check if arming allowed from this mode193bool AP_Arming_Rover::mode_checks(bool report)194{195//display failure if arming in this mode is not allowed196if (!rover.control_mode->allows_arming()) {197check_failed(report, "Mode not armable");198return false;199}200return true;201}202203// check motors are ready204bool AP_Arming_Rover::motor_checks(bool report)205{206bool ret = rover.g2.motors.pre_arm_check(report);207208#if HAL_TORQEEDO_ENABLED209char failure_msg[50] = {};210AP_Torqeedo *torqeedo = AP_Torqeedo::get_singleton();211if (torqeedo != nullptr) {212if (!torqeedo->pre_arm_checks(failure_msg, ARRAY_SIZE(failure_msg))) {213check_failed(report, "Torqeedo: %s", failure_msg);214ret = false;215}216}217#endif218219return ret;220}221222223