ardupilot/ArduSub/motors.cpp

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

181 lines
6.3 KiB
C++
Raw Permalink Normal View History

2016-01-14 15:30:56 -04:00
#include "Sub.h"
2017-04-05 17:25:03 -03:00
// enable_motor_output() - enable and output lowest possible value to motors
void Sub::enable_motor_output()
{
motors.output_min();
}
// motors_output - send output to motors library which will adjust and send to ESCs and servos
2016-01-14 15:30:56 -04:00
void Sub::motors_output()
{
// Motor detection mode controls the thrusters directly
2023-04-03 09:11:21 -03:00
if (control_mode == Mode::Number::MOTOR_DETECT){
return;
}
// check if we are performing the motor test
if (ap.motor_test) {
2018-04-19 16:12:42 -03:00
verify_motor_test();
} else {
motors.set_interlock(true);
motors.output();
}
}
2018-04-19 16:12:42 -03:00
// Initialize new style motor test
// Perform checks to see if it is ok to begin the motor test
// Returns true if motor test has begun
bool Sub::init_motor_test()
{
uint32_t tnow = AP_HAL::millis();
// Ten second cooldown period required with no do_set_motor requests required
// after failure.
if (tnow < last_do_motor_test_fail_ms + 10000 && last_do_motor_test_fail_ms > 0) {
2019-09-16 11:02:59 -03:00
gcs().send_text(MAV_SEVERITY_CRITICAL, "10 second cooldown required after motor test");
return false;
2018-04-19 16:12:42 -03:00
}
// check if safety switch has been pushed
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
gcs().send_text(MAV_SEVERITY_CRITICAL,"Disarm hardware safety switch before testing motors.");
return false;
}
// Make sure we are on the ground
if (!motors.armed()) {
gcs().send_text(MAV_SEVERITY_WARNING, "Arm motors before testing motors.");
return false;
}
enable_motor_output(); // set all motor outputs to zero
ap.motor_test = true;
return true;
}
// Verify new style motor test
// The motor test will fail if the interval between received
// MAV_CMD_DO_SET_MOTOR requests exceeds a timeout period
// Returns true if it is ok to proceed with new style motor test
bool Sub::verify_motor_test()
{
bool pass = true;
// Require at least 2 Hz incoming do_set_motor requests
if (AP_HAL::millis() > last_do_motor_test_ms + 500) {
gcs().send_text(MAV_SEVERITY_INFO, "Motor test timed out!");
2018-04-19 16:12:42 -03:00
pass = false;
}
if (!pass) {
ap.motor_test = false;
AP::arming().disarm(AP_Arming::Method::MOTORTEST);
2018-04-19 16:12:42 -03:00
last_do_motor_test_fail_ms = AP_HAL::millis();
return false;
}
return true;
}
bool Sub::handle_do_motor_test(mavlink_command_int_t command) {
2018-04-19 16:12:42 -03:00
last_do_motor_test_ms = AP_HAL::millis();
// If we are not already testing motors, initialize test
static uint32_t tLastInitializationFailed = 0;
2018-04-19 16:12:42 -03:00
if(!ap.motor_test) {
// Do not allow initializations attempt under 2 seconds
// If one fails, we need to give the user time to fix the issue
// instead of spamming error messages
if (AP_HAL::millis() > (tLastInitializationFailed + 2000)) {
if (!init_motor_test()) {
gcs().send_text(MAV_SEVERITY_WARNING, "motor test initialization failed!");
tLastInitializationFailed = AP_HAL::millis();
return false; // init fail
}
} else {
return false;
2018-04-19 16:12:42 -03:00
}
}
float motor_number = command.param1;
float throttle_type = command.param2;
float throttle = command.param3;
// float timeout_s = command.param4; // not used
// float motor_count = command.param5; // not used
const uint32_t test_type = command.y;
2018-04-19 16:12:42 -03:00
if (test_type != MOTOR_TEST_ORDER_BOARD) {
2018-04-19 16:12:42 -03:00
gcs().send_text(MAV_SEVERITY_WARNING, "bad test type %0.2f", (double)test_type);
return false; // test type not supported here
}
if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PILOT)) {
gcs().send_text(MAV_SEVERITY_WARNING, "bad throttle type %0.2f", (double)throttle_type);
return false; // throttle type not supported here
}
if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PWM)) {
return motors.output_test_num(motor_number, throttle); // true if motor output is set
}
if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PERCENT)) {
throttle = constrain_float(throttle, 0.0f, 100.0f);
throttle = channel_throttle->get_radio_min() + throttle / 100.0f * (channel_throttle->get_radio_max() - channel_throttle->get_radio_min());
return motors.output_test_num(motor_number, throttle); // true if motor output is set
}
return false;
}
// translate wpnav roll/pitch outputs to lateral/forward
void Sub::translate_wpnav_rp(float &lateral_out, float &forward_out)
{
// get roll and pitch targets in centidegrees
int32_t lateral = wp_nav.get_roll();
int32_t forward = -wp_nav.get_pitch(); // output is reversed
// constrain target forward/lateral values
// The outputs of wp_nav.get_roll and get_pitch should already be constrained to these values
lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
// Normalize
lateral_out = (float)lateral/(float)aparm.angle_max;
forward_out = (float)forward/(float)aparm.angle_max;
}
2017-03-04 15:41:26 -04:00
// translate wpnav roll/pitch outputs to lateral/forward
void Sub::translate_circle_nav_rp(float &lateral_out, float &forward_out)
{
// get roll and pitch targets in centidegrees
int32_t lateral = circle_nav.get_roll();
int32_t forward = -circle_nav.get_pitch(); // output is reversed
// constrain target forward/lateral values
2017-03-06 22:29:03 -04:00
lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
// Normalize
lateral_out = (float)lateral/(float)aparm.angle_max;
forward_out = (float)forward/(float)aparm.angle_max;
}
// translate pos_control roll/pitch outputs to lateral/forward
void Sub::translate_pos_control_rp(float &lateral_out, float &forward_out)
{
// get roll and pitch targets in centidegrees
int32_t lateral = pos_control.get_roll_cd();
int32_t forward = -pos_control.get_pitch_cd(); // output is reversed
2017-03-06 22:29:03 -04:00
// constrain target forward/lateral values
2017-03-04 15:41:26 -04:00
lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);
forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);
// Normalize
lateral_out = (float)lateral/(float)aparm.angle_max;
forward_out = (float)forward/(float)aparm.angle_max;
}