#include "Rover.h"
static const int16_t MOTOR_TEST_PWM_MAX = 2200;
static const int16_t MOTOR_TEST_TIMEOUT_MS_MAX = 30000;
static uint32_t motor_test_start_ms = 0;
static uint32_t motor_test_timeout_ms = 0;
static AP_MotorsUGV::motor_test_order motor_test_instance;
static uint8_t motor_test_throttle_type = 0;
static int16_t motor_test_throttle_value = 0;
void Rover::motor_test_output()
{
if (!motor_test) {
return;
}
if ((AP_HAL::millis() - motor_test_start_ms) >= motor_test_timeout_ms) {
motor_test_stop();
} else {
bool test_result = false;
switch (motor_test_throttle_type) {
case MOTOR_TEST_THROTTLE_PERCENT:
test_result = g2.motors.output_test_pct(motor_test_instance, motor_test_throttle_value);
break;
case MOTOR_TEST_THROTTLE_PWM:
test_result = g2.motors.output_test_pwm(motor_test_instance, motor_test_throttle_value);
break;
case MOTOR_TEST_THROTTLE_PILOT:
if (motor_test_instance == AP_MotorsUGV::MOTOR_TEST_STEERING) {
test_result = g2.motors.output_test_pct(motor_test_instance, channel_steer->norm_input_dz() * 100.0f);
} else {
test_result = g2.motors.output_test_pct(motor_test_instance, channel_throttle->get_control_in());
}
break;
default:
return;
}
if (!test_result) {
motor_test_stop();
}
}
}
bool 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)
{
if (!initialised) {
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: Board initialising");
return false;
}
if (check_rc && !arming.rc_calibration_checks(true)) {
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: RC not calibrated");
return false;
}
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: Safety switch");
return false;
}
if (motor_seq > AP_MotorsUGV::MOTOR_TEST_THROTTLE_RIGHT) {
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: invalid motor (%d)", (int)motor_seq);
return false;
}
if (throttle_type > MOTOR_TEST_THROTTLE_PILOT) {
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: invalid throttle type: %d", (int)throttle_type);
return false;
}
if (throttle_type == MOTOR_TEST_THROTTLE_PWM && throttle_value > MOTOR_TEST_PWM_MAX) {
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: pwm (%d) too high", (int)throttle_value);
return false;
}
if (throttle_type == MOTOR_TEST_THROTTLE_PERCENT && throttle_value > 100) {
gcs_chan.send_text(MAV_SEVERITY_CRITICAL, "Motor Test: percentage (%d) too high", (int)throttle_value);
return false;
}
return true;
}
MAV_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)
{
if (!motor_test) {
if (!mavlink_motor_test_check(gcs_chan, throttle_type != 1, motor_instance, throttle_type, throttle_value)) {
return MAV_RESULT_FAILED;
} else {
motor_test = true;
if (!arming.is_armed()) {
if (!arming.arm(AP_Arming::Method::MOTORTEST)) {
return MAV_RESULT_FAILED;
}
}
g.fs_gcs_enabled.set(0);
g.fs_throttle_enabled.set(0);
g.fs_crash_check.set(0);
AP_Notify::flags.esc_calibration = true;
}
}
motor_test_start_ms = AP_HAL::millis();
motor_test_timeout_ms = MIN(timeout_sec * 1000, MOTOR_TEST_TIMEOUT_MS_MAX);
motor_test_instance = motor_instance;
motor_test_throttle_type = throttle_type;
motor_test_throttle_value = throttle_value;
return MAV_RESULT_ACCEPTED;
}
void Rover::motor_test_stop()
{
if (!motor_test) {
return;
}
AP::arming().disarm(AP_Arming::Method::MOTORTEST);
motor_test_start_ms = 0;
motor_test_timeout_ms = 0;
g.fs_gcs_enabled.load();
g.fs_throttle_enabled.load();
g.fs_crash_check.load();
AP_Notify::flags.esc_calibration = false;
motor_test = false;
}