9 #define MOTOR_TEST_PWM_MIN 800 // min pwm value accepted by the test 10 #define MOTOR_TEST_PWM_MAX 2200 // max pwm value accepted by the test 11 #define MOTOR_TEST_TIMEOUT_MS_MAX 30000 // max timeout is 30 seconds 54 case MOTOR_TEST_COMPASS_CAL:
59 case MOTOR_TEST_THROTTLE_PERCENT:
61 #if FRAME_CONFIG != HELI_FRAME 63 int16_t pwm_min =
motors->get_pwm_output_min();
64 int16_t pwm_max =
motors->get_pwm_output_max();
70 case MOTOR_TEST_THROTTLE_PWM:
74 case MOTOR_TEST_THROTTLE_PILOT:
100 if (!
ap.initialised) {
101 gcs_chan.
send_text(MAV_SEVERITY_CRITICAL,
"Motor Test: Board initialising");
107 gcs_chan.
send_text(MAV_SEVERITY_CRITICAL,
"Motor Test: RC not calibrated");
112 if (!
ap.land_complete) {
113 gcs_chan.
send_text(MAV_SEVERITY_CRITICAL,
"Motor Test: vehicle not landed");
119 gcs_chan.
send_text(MAV_SEVERITY_CRITICAL,
"Motor Test: Safety switch");
130 float timeout_sec, uint8_t motor_count)
132 if (motor_count == 0) {
136 if (!
ap.motor_test) {
137 gcs().
send_text(MAV_SEVERITY_INFO,
"starting motor test");
144 return MAV_RESULT_FAILED;
147 ap.motor_test =
true;
181 return MAV_RESULT_ACCEPTED;
188 if (!
ap.motor_test) {
192 gcs().
send_text(MAV_SEVERITY_INFO,
"finished motor test");
195 ap.motor_test =
false;
void per_motor_calibration_end(void)
static uint16_t motor_test_throttle_value
int16_t get_radio_in() const
MAV_RESULT mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value, float timeout_sec, uint8_t motor_count)
bool mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc)
static uint8_t motor_test_count
void per_motor_calibration_update(void)
bool rc_calibration_checks(bool display_failure) override
#define MOTOR_TEST_PWM_MIN
static uint32_t motor_test_start_ms
RC_Channel * channel_throttle
virtual enum safety_state safety_switch_state(void)
GCS_MAVLINK_Copter & chan(const uint8_t ofs) override
void send_text(MAV_SEVERITY severity, const char *fmt,...)
void send_text(MAV_SEVERITY severity, const char *fmt,...)
#define MOTOR_TEST_PWM_MAX
void set_voltage(float voltage)
void per_motor_calibration_start(void)
static struct notify_flags_and_values_type flags
static uint8_t motor_test_throttle_type
AP_Int8 failsafe_throttle
#define MOTOR_TEST_TIMEOUT_MS_MAX
static uint8_t motor_test_seq
float voltage(uint8_t instance) const
void enable_motor_output()
static uint32_t motor_test_timeout_ms