From e81973cd292312e6887fae48c1a7d516eef667a3 Mon Sep 17 00:00:00 2001 From: Grant Morphett Date: Fri, 30 Oct 2015 16:57:17 +1100 Subject: [PATCH] Rover: motor_active method similar to the plane is_flying but simpler --- APMrover2/Rover.h | 4 ++-- APMrover2/control_modes.cpp | 11 +++++++++++ APMrover2/radio.cpp | 10 ++++++---- 3 files changed, 19 insertions(+), 6 deletions(-) diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index d799087f98..3ebe22ae78 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -372,7 +372,7 @@ private: uint32_t rudder_arm_timer; // true if we are in an auto-throttle mode, which means - // we need to run the speed/height controller + // we need to run the speed controller bool auto_throttle_mode; @@ -522,7 +522,7 @@ private: void change_arm_state(void); bool disarm_motors(void); bool arm_motors(AP_Arming::ArmingMethod method); - bool is_moving(); + bool motor_active(); void update_home(); public: diff --git a/APMrover2/control_modes.cpp b/APMrover2/control_modes.cpp index e2940e7eea..dc2efb8af2 100644 --- a/APMrover2/control_modes.cpp +++ b/APMrover2/control_modes.cpp @@ -117,3 +117,14 @@ void Rover::read_trim_switch() } } +bool Rover::motor_active() +{ + // Check if armed and throttle is not neutral + if (hal.util->get_soft_armed()) { + if (!channel_throttle->in_trim_dz()) { + return true; + } + } + + return false; +} diff --git a/APMrover2/radio.cpp b/APMrover2/radio.cpp index f3e8fec371..955e1bef61 100644 --- a/APMrover2/radio.cpp +++ b/APMrover2/radio.cpp @@ -49,8 +49,10 @@ void Rover::init_rc_out() // setup PWM values to send if the FMU firmware dies RC_Channel::setup_failsafe_trim_all(); - // setup PX4 to output the min throttle when safety off if arming - // is setup for min on disarm + // output throttle trim when safety off if arming + // is setup for min on disarm. MIN is from plane where MIN is effectively no throttle. + // For Rover's no throttle means TRIM as rovers can go backwards i.e. MIN throttle is + // full speed backward. if (arming.arming_required() == AP_Arming::YES_MIN_PWM) { hal.rcout->set_safety_pwm(1UL<<(rcmap.throttle()-1), channel_throttle->radio_trim); } @@ -94,8 +96,8 @@ void Rover::rudder_arm_disarm_check() // not at full right rudder rudder_arm_timer = 0; } - } else if (!is_moving()) { - // when armed and not moving, full left rudder starts disarming counter + } else if (!motor_active()) { + // when armed and motor not active (not moving), full left rudder starts disarming counter if (channel_steer->control_in < -4000) { uint32_t now = millis();