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/motor_test.cpp
Views: 1798
#include "Rover.h"12/*3mavlink motor test - implements the MAV_CMD_DO_MOTOR_TEST mavlink command so that the GCS/pilot can test an individual motor or flaps4to ensure proper wiring, rotation.5*/67// motor test definitions8static const int16_t MOTOR_TEST_PWM_MAX = 2200; // max pwm value accepted by the test9static const int16_t MOTOR_TEST_TIMEOUT_MS_MAX = 30000; // max timeout is 30 seconds1011static uint32_t motor_test_start_ms = 0; // system time the motor test began12static uint32_t motor_test_timeout_ms = 0; // test will timeout this many milliseconds after the motor_test_start_ms13static AP_MotorsUGV::motor_test_order motor_test_instance; // motor instance number of motor being tested (see AP_MotorsUGV::motor_test_order)14static uint8_t motor_test_throttle_type = 0; // motor throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through)15static int16_t motor_test_throttle_value = 0; // throttle to be sent to motor, value depends upon it's type1617// motor_test_output - checks for timeout and sends updates to motors objects18void Rover::motor_test_output()19{20// exit immediately if the motor test is not running21if (!motor_test) {22return;23}2425// check for test timeout26if ((AP_HAL::millis() - motor_test_start_ms) >= motor_test_timeout_ms) {27// stop motor test28motor_test_stop();29} else {30bool test_result = false;31// calculate based on throttle type32switch (motor_test_throttle_type) {33case MOTOR_TEST_THROTTLE_PERCENT:34test_result = g2.motors.output_test_pct(motor_test_instance, motor_test_throttle_value);35break;3637case MOTOR_TEST_THROTTLE_PWM:38test_result = g2.motors.output_test_pwm(motor_test_instance, motor_test_throttle_value);39break;4041case MOTOR_TEST_THROTTLE_PILOT:42if (motor_test_instance == AP_MotorsUGV::MOTOR_TEST_STEERING) {43test_result = g2.motors.output_test_pct(motor_test_instance, channel_steer->norm_input_dz() * 100.0f);44} else {45test_result = g2.motors.output_test_pct(motor_test_instance, channel_throttle->get_control_in());46}47break;4849default:50// do nothing51return;52}53// stop motor test on failure54if (!test_result) {55motor_test_stop();56}57}58}5960// mavlink_motor_test_check - perform checks before motor tests can begin61// return true if tests can continue, false if not62bool Rover::mavlink_motor_test_check(const GCS_MAVLINK &gcs_chan, bool check_rc, AP_MotorsUGV::motor_test_order motor_seq, uint8_t throttle_type, int16_t throttle_value)63{64// check board has initialised65if (!initialised) {66gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: Board initialising");67return false;68}6970// check rc has been calibrated71if (check_rc && !arming.rc_calibration_checks(true)) {72gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: RC not calibrated");73return false;74}7576// check if safety switch has been pushed77if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {78gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: Safety switch");79return false;80}8182// check motor_seq83if (motor_seq > AP_MotorsUGV::MOTOR_TEST_THROTTLE_RIGHT) {84gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: invalid motor (%d)", (int)motor_seq);85return false;86}8788// check throttle type89if (throttle_type > MOTOR_TEST_THROTTLE_PILOT) {90gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: invalid throttle type: %d", (int)throttle_type);91return false;92}9394// check throttle value95if (throttle_type == MOTOR_TEST_THROTTLE_PWM && throttle_value > MOTOR_TEST_PWM_MAX) {96gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: pwm (%d) too high", (int)throttle_value);97return false;98}99if (throttle_type == MOTOR_TEST_THROTTLE_PERCENT && throttle_value > 100) {100gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: percentage (%d) too high", (int)throttle_value);101return false;102}103104// if we got this far the check was successful and the motor test can continue105return true;106}107108// mavlink_motor_test_start - start motor test - spin a single motor at a specified pwm109// returns MAV_RESULT_ACCEPTED on success, MAV_RESULT_FAILED on failure110MAV_RESULT Rover::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, AP_MotorsUGV::motor_test_order motor_instance, uint8_t throttle_type, int16_t throttle_value, float timeout_sec)111{112// if test has not started try to start it113if (!motor_test) {114/* perform checks that it is ok to start test115The RC calibrated check can be skipped if direct pwm is116suppliedo117*/118if (!mavlink_motor_test_check(gcs_chan, throttle_type != 1, motor_instance, throttle_type, throttle_value)) {119return MAV_RESULT_FAILED;120} else {121// start test122motor_test = true;123124// arm motors125if (!arming.is_armed()) {126if (!arming.arm(AP_Arming::Method::MOTORTEST)) {127return MAV_RESULT_FAILED;128}129}130131// disable failsafes132g.fs_gcs_enabled.set(0);133g.fs_throttle_enabled.set(0);134g.fs_crash_check.set(0);135136// turn on notify leds137AP_Notify::flags.esc_calibration = true;138}139}140141// set timeout142motor_test_start_ms = AP_HAL::millis();143motor_test_timeout_ms = MIN(timeout_sec * 1000, MOTOR_TEST_TIMEOUT_MS_MAX);144145// store required output146motor_test_instance = motor_instance;147motor_test_throttle_type = throttle_type;148motor_test_throttle_value = throttle_value;149150// return success151return MAV_RESULT_ACCEPTED;152}153154// motor_test_stop - stops the motor test155void Rover::motor_test_stop()156{157// exit immediately if the test is not running158if (!motor_test) {159return;160}161162// disarm motors163AP::arming().disarm(AP_Arming::Method::MOTORTEST);164165// reset timeout166motor_test_start_ms = 0;167motor_test_timeout_ms = 0;168169// re-enable failsafes170g.fs_gcs_enabled.load();171g.fs_throttle_enabled.load();172g.fs_crash_check.load();173174// turn off notify leds175AP_Notify::flags.esc_calibration = false;176177// flag test is complete178motor_test = false;179}180181182