From cf1f2f9aebd486bb76f49ec8a704f31fd698e555 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 6 Jun 2018 16:18:24 +1000 Subject: [PATCH] Rover: move motors_active to be motors.active This will help when we come to subclass the Motors library. --- APMrover2/APMrover2.cpp | 2 +- APMrover2/AP_MotorsUGV.cpp | 21 +++++++++++++++++++++ APMrover2/AP_MotorsUGV.h | 3 +++ APMrover2/Rover.h | 1 - APMrover2/control_modes.cpp | 21 --------------------- APMrover2/radio.cpp | 2 +- 6 files changed, 26 insertions(+), 24 deletions(-) diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index 808f0f6497..fa9dbd3797 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -105,7 +105,7 @@ constexpr int8_t Rover::_failsafe_priorities[7]; */ void Rover::stats_update(void) { - g2.stats.set_flying(motor_active()); + g2.stats.set_flying(g2.motors.active()); g2.stats.update(); } #endif diff --git a/APMrover2/AP_MotorsUGV.cpp b/APMrover2/AP_MotorsUGV.cpp index bf38e7bf0c..52d9b7820d 100644 --- a/APMrover2/AP_MotorsUGV.cpp +++ b/APMrover2/AP_MotorsUGV.cpp @@ -673,3 +673,24 @@ float AP_MotorsUGV::get_scaled_throttle(float throttle) const const float throttle_pct = constrain_float(throttle, -100.0f, 100.0f) / 100.0f; return 100.0f * sign * ((_thrust_curve_expo - 1.0f) + safe_sqrt((1.0f - _thrust_curve_expo) * (1.0f - _thrust_curve_expo) + 4.0f * _thrust_curve_expo * fabsf(throttle_pct))) / (2.0f * _thrust_curve_expo); } + +// return true if motors are moving +bool AP_MotorsUGV::active() const +{ + // if soft disarmed, motors not active + if (!hal.util->get_soft_armed()) { + return false; + } + + // check throttle is active + if (!is_zero(get_throttle())) { + return true; + } + + // skid-steering vehicles active when steering + if (have_skid_steering() && !is_zero(get_steering())) { + return true; + } + + return false; +} diff --git a/APMrover2/AP_MotorsUGV.h b/APMrover2/AP_MotorsUGV.h index bb7474d80d..b39437559f 100644 --- a/APMrover2/AP_MotorsUGV.h +++ b/APMrover2/AP_MotorsUGV.h @@ -28,6 +28,9 @@ public: // initialise motors void init(); + // return true if motors are active + bool active() const; + // setup output in case of main CPU failure void setup_safety_output(); diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 79006125e3..78f801cded 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -443,7 +443,6 @@ private: void do_aux_function_change_mode(Mode &mode, const aux_switch_pos ch_flag); void read_aux_switch(); - bool motor_active(); // crash_check.cpp void crash_check(); diff --git a/APMrover2/control_modes.cpp b/APMrover2/control_modes.cpp index b44897f503..11effb2b55 100644 --- a/APMrover2/control_modes.cpp +++ b/APMrover2/control_modes.cpp @@ -265,24 +265,3 @@ void Rover::read_aux_switch() break; } } - -// return true if motors are moving -bool Rover::motor_active() -{ - // if soft disarmed, motors not active - if (!hal.util->get_soft_armed()) { - return false; - } - - // check throttle is active - if (!is_zero(g2.motors.get_throttle())) { - return true; - } - - // skid-steering vehicles active when steering - if (g2.motors.have_skid_steering() && !is_zero(g2.motors.get_steering())) { - return true; - } - - return false; -} diff --git a/APMrover2/radio.cpp b/APMrover2/radio.cpp index 90ef83ef00..5dc59a0fc3 100644 --- a/APMrover2/radio.cpp +++ b/APMrover2/radio.cpp @@ -80,7 +80,7 @@ void Rover::rudder_arm_disarm_check() // not at full right rudder rudder_arm_timer = 0; } - } else if (!motor_active()) { + } else if (!g2.motors.active()) { // when armed and motor not active (not moving), full left rudder starts disarming counter if (channel_steer->get_control_in() < -4000) { const uint32_t now = millis();