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/ArduSub/motors.cpp
Views: 1798
#include "Sub.h"12// enable_motor_output() - enable and output lowest possible value to motors3void Sub::enable_motor_output()4{5motors.output_min();6}78// motors_output - send output to motors library which will adjust and send to ESCs and servos9void Sub::motors_output()10{11// Motor detection mode controls the thrusters directly12if (control_mode == Mode::Number::MOTOR_DETECT){13return;14}15// check if we are performing the motor test16if (ap.motor_test) {17verify_motor_test();18} else {19motors.set_interlock(true);20auto &srv = AP::srv();21srv.cork();22SRV_Channels::calc_pwm();23SRV_Channels::output_ch_all();24motors.output();25srv.push();26}27}2829// Initialize new style motor test30// Perform checks to see if it is ok to begin the motor test31// Returns true if motor test has begun32bool Sub::init_motor_test()33{34uint32_t tnow = AP_HAL::millis();3536// Ten second cooldown period required with no do_set_motor requests required37// after failure.38if (tnow < last_do_motor_test_fail_ms + 10000 && last_do_motor_test_fail_ms > 0) {39gcs().send_text(MAV_SEVERITY_CRITICAL, "10 second cooldown required after motor test");40return false;41}4243// check if safety switch has been pushed44if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {45gcs().send_text(MAV_SEVERITY_CRITICAL,"Disarm hardware safety switch before testing motors.");46return false;47}4849// Make sure we are on the ground50if (!motors.armed()) {51gcs().send_text(MAV_SEVERITY_WARNING, "Arm motors before testing motors.");52return false;53}5455enable_motor_output(); // set all motor outputs to zero56ap.motor_test = true;5758return true;59}6061// Verify new style motor test62// The motor test will fail if the interval between received63// MAV_CMD_DO_SET_MOTOR requests exceeds a timeout period64// Returns true if it is ok to proceed with new style motor test65bool Sub::verify_motor_test()66{67bool pass = true;6869// Require at least 2 Hz incoming do_set_motor requests70if (AP_HAL::millis() > last_do_motor_test_ms + 500) {71gcs().send_text(MAV_SEVERITY_INFO, "Motor test timed out!");72pass = false;73}7475if (!pass) {76ap.motor_test = false;77AP::arming().disarm(AP_Arming::Method::MOTORTEST);78last_do_motor_test_fail_ms = AP_HAL::millis();79return false;80}8182return true;83}8485bool Sub::handle_do_motor_test(mavlink_command_int_t command) {86last_do_motor_test_ms = AP_HAL::millis();8788// If we are not already testing motors, initialize test89static uint32_t tLastInitializationFailed = 0;90if(!ap.motor_test) {91// Do not allow initializations attempt under 2 seconds92// If one fails, we need to give the user time to fix the issue93// instead of spamming error messages94if (AP_HAL::millis() > (tLastInitializationFailed + 2000)) {95if (!init_motor_test()) {96gcs().send_text(MAV_SEVERITY_WARNING, "motor test initialization failed!");97tLastInitializationFailed = AP_HAL::millis();98return false; // init fail99}100} else {101return false;102}103}104105float motor_number = command.param1;106float throttle_type = command.param2;107float throttle = command.param3;108// float timeout_s = command.param4; // not used109// float motor_count = command.param5; // not used110const uint32_t test_type = command.y;111112if (test_type != MOTOR_TEST_ORDER_BOARD) {113gcs().send_text(MAV_SEVERITY_WARNING, "bad test type %0.2f", (double)test_type);114return false; // test type not supported here115}116117if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PILOT)) {118gcs().send_text(MAV_SEVERITY_WARNING, "bad throttle type %0.2f", (double)throttle_type);119120return false; // throttle type not supported here121}122123if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PWM)) {124return motors.output_test_num(motor_number, throttle); // true if motor output is set125}126127if (is_equal(throttle_type, (float)MOTOR_TEST_THROTTLE_PERCENT)) {128throttle = constrain_float(throttle, 0.0f, 100.0f);129throttle = channel_throttle->get_radio_min() + throttle * 0.01f * (channel_throttle->get_radio_max() - channel_throttle->get_radio_min());130return motors.output_test_num(motor_number, throttle); // true if motor output is set131}132133return false;134}135136137// translate wpnav roll/pitch outputs to lateral/forward138void Sub::translate_wpnav_rp(float &lateral_out, float &forward_out)139{140// get roll and pitch targets in centidegrees141int32_t lateral = wp_nav.get_roll();142int32_t forward = -wp_nav.get_pitch(); // output is reversed143144// constrain target forward/lateral values145// The outputs of wp_nav.get_roll and get_pitch should already be constrained to these values146lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);147forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);148149// Normalize150lateral_out = (float)lateral/(float)aparm.angle_max;151forward_out = (float)forward/(float)aparm.angle_max;152}153154// translate wpnav roll/pitch outputs to lateral/forward155void Sub::translate_circle_nav_rp(float &lateral_out, float &forward_out)156{157// get roll and pitch targets in centidegrees158int32_t lateral = circle_nav.get_roll();159int32_t forward = -circle_nav.get_pitch(); // output is reversed160161// constrain target forward/lateral values162lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);163forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);164165// Normalize166lateral_out = (float)lateral/(float)aparm.angle_max;167forward_out = (float)forward/(float)aparm.angle_max;168}169170// translate pos_control roll/pitch outputs to lateral/forward171void Sub::translate_pos_control_rp(float &lateral_out, float &forward_out)172{173// get roll and pitch targets in centidegrees174int32_t lateral = pos_control.get_roll_cd();175int32_t forward = -pos_control.get_pitch_cd(); // output is reversed176177// constrain target forward/lateral values178lateral = constrain_int16(lateral, -aparm.angle_max, aparm.angle_max);179forward = constrain_int16(forward, -aparm.angle_max, aparm.angle_max);180181// Normalize182lateral_out = (float)lateral/(float)aparm.angle_max;183forward_out = (float)forward/(float)aparm.angle_max;184}185186187