-
Notifications
You must be signed in to change notification settings - Fork 17.9k
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Plane: tilt quadplane fixes #28960
base: master
Are you sure you want to change the base?
Plane: tilt quadplane fixes #28960
Conversation
@IamPete1 I've added a patch to allow THR_SLEWRATE to apply to tilted motors, by adding a new k_throttle_tilt actuator function |
this copes with a Q_TILT_RATE_DN that is too slow for the configured Q_TRANSITION_MS
use the proportion we have moved the tilt rotors forward for controlling the VTOL throttle in transition. This prevents a too short Q_TRANSITION_MS from causing oscillations in transition
it makes no sense for it to be above AIRSPEED_MIN
used for slew limiting tilted motors
this reduces the sudden change in throttle on fwd transition completion and allows for THR_SLEWRATE to work on tilt quadplanes
@@ -229,7 +231,9 @@ void Tiltrotor::continuous_update(void) | |||
|
|||
max_change = tilt_max_change(false); | |||
|
|||
float new_throttle = constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)*0.01, 0, 1); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I was expecting to just be able to change this to get_slew_limited_output_scaled
, but I guess that does not slew step when we change over from VTOL to FW throttle?
@@ -150,6 +150,8 @@ void Tiltrotor::setup() | |||
} | |||
quadplane.transition = transition; | |||
|
|||
SRV_Channels::set_range(SRV_Channel::k_throttle_tilt, 100); // match k_throttle |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I really would like to get everything to use a range of 1. But I do see that it would be a bit odd to not match throttle here.
@@ -229,7 +231,9 @@ void Tiltrotor::continuous_update(void) | |||
|
|||
max_change = tilt_max_change(false); | |||
|
|||
float new_throttle = constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)*0.01, 0, 1); | |||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle_tilt, SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I think this should constrain to not be negative before the set. Normal throttle can be negative.
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle_tilt, SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)); | |
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle_tilt, MAX(0, SRV_Channels::get_output_scaled(SRV_Channel::k_throttle))); |
float new_throttle = constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)*0.01, 0, 1); | ||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle_tilt, SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)); | ||
float new_throttle = constrain_float(SRV_Channels::get_slew_limited_output_scaled(SRV_Channel::k_throttle_tilt)*0.01, 0, 1); | ||
|
||
if (current_tilt < get_fully_forward_tilt()) { | ||
current_throttle = constrain_float(new_throttle, |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This constrain could be achieved with the new slew limited function.
@@ -245,7 +249,7 @@ void Tiltrotor::continuous_update(void) | |||
} | |||
if (!quadplane.motor_test.running) { | |||
// the motors are all the way forward, start using them for fwd thrust | |||
const uint16_t mask = is_zero(current_throttle)?0U:tilt_mask.get(); | |||
const uint16_t mask = tilt_mask.get(); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I think will mean you get spin min in motor test rather than no motors spinning?
if (!fully_fwd()) { | ||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle_tilt, largest_tilted*100); | ||
} |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I guess this is to make sure the slew starts off in the right place? I would prefer to see it done with the throttle output value from motors. You should be able to use motors thrust linearisation like we do for tailsitter here:
ardupilot/ArduPlane/tailsitter.cpp
Lines 321 to 323 in 5f8a655
// 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->thr_lin.thrust_to_actuator(throttle); |
@@ -189,6 +189,7 @@ class SRV_Channel { | |||
k_rcin15_mapped = 154, | |||
k_rcin16_mapped = 155, | |||
k_lift_release = 156, | |||
k_throttle_tilt = 157, |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Should we enforce that users don't assign this to a actual output? It does not abide by safety state for example (or E-stop).
#29011 is a alternate approach to get slew limiting for tiltrottor throttle outputs. |
this fixes some issues with tilt quadplanes.
The first fix is to ensure we don't complete the transition till the rotors are fully tilted forward. The demanded VTOL throttle during the 2nd stage of the transition is also fixed to be based on the tilt angle, not the time.
The 2nd fix is to prevent oscillation of the assisted_flight flag
fixes some of the issues in #28957