From 5f56a603a823785e140b67eaeffac58b090d26d3 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 31 Jan 2023 01:55:04 +0000 Subject: [PATCH] Plane: Quadplane: use new motors thrust linearization, don't send air density ratio --- ArduPlane/ArduPlane.cpp | 6 ------ ArduPlane/tailsitter.cpp | 6 +++--- 2 files changed, 3 insertions(+), 9 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index ba93f53037..16b7fcfb94 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -511,12 +511,6 @@ void Plane::update_alt() { barometer.update(); -#if HAL_QUADPLANE_ENABLED - if (quadplane.available()) { - quadplane.motors->set_air_density_ratio(barometer.get_air_density_ratio()); - } -#endif - // calculate the sink rate. float sink_rate; Vector3f vel; diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index 815aac3c65..947391be30 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -302,11 +302,11 @@ void Tailsitter::output(void) */ if (!is_negative(transition_throttle_vtol)) { // Q_TAILSIT_THR_VT is positive use it until transition is complete - throttle = motors->actuator_to_thrust(MIN(transition_throttle_vtol*0.01,1.0)); + throttle = motors->thr_lin.actuator_to_thrust(MIN(transition_throttle_vtol*0.01,1.0)); } else { throttle = motors->get_throttle_hover(); // work out equivelent motors throttle level for cruise - throttle = MAX(throttle,motors->actuator_to_thrust(plane.aparm.throttle_cruise.get() * 0.01)); + throttle = MAX(throttle,motors->thr_lin.actuator_to_thrust(plane.aparm.throttle_cruise.get() * 0.01)); } SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, 0.0); @@ -321,7 +321,7 @@ void Tailsitter::output(void) // convert the hover throttle to the same output that would result if used via AP_Motors // apply expo, battery scaling and SPIN min/max. - throttle = motors->thrust_to_actuator(throttle); + throttle = motors->thr_lin.thrust_to_actuator(throttle); // override AP_MotorsTailsitter throttles during back transition