mirror of https://github.com/ArduPilot/ardupilot
Plane: Quadplane: use new motors thrust linearization, don't send air density ratio
This commit is contained in:
parent
be275e2cac
commit
5f56a603a8
|
@ -511,12 +511,6 @@ void Plane::update_alt()
|
||||||
{
|
{
|
||||||
barometer.update();
|
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.
|
// calculate the sink rate.
|
||||||
float sink_rate;
|
float sink_rate;
|
||||||
Vector3f vel;
|
Vector3f vel;
|
||||||
|
|
|
@ -302,11 +302,11 @@ void Tailsitter::output(void)
|
||||||
*/
|
*/
|
||||||
if (!is_negative(transition_throttle_vtol)) {
|
if (!is_negative(transition_throttle_vtol)) {
|
||||||
// Q_TAILSIT_THR_VT is positive use it until transition is complete
|
// 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 {
|
} else {
|
||||||
throttle = motors->get_throttle_hover();
|
throttle = motors->get_throttle_hover();
|
||||||
// work out equivelent motors throttle level for cruise
|
// 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);
|
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
|
// convert the hover throttle to the same output that would result if used via AP_Motors
|
||||||
// apply expo, battery scaling and SPIN min/max.
|
// 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
|
// override AP_MotorsTailsitter throttles during back transition
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue