Skip to content

Improve quadplane use of forward throttle in VTOL modes #13760

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

Merged
merged 30 commits into from
Sep 27, 2023

Conversation

priseborough
Copy link
Contributor

This patch provides a more direct control of forward thrust motor throttle during quadplane Q modes. I have found it to provide more precise position control in varying wind conditions in Q_LOITER and better control with less pitch/dive when operating in QSTABILIZE and QHOVER and applying forward tilt to reposition or hold position in wind.

I would be interested to get feedback from other quadplane flyers.

@Hwurzburg
Copy link
Contributor

Paul some questions on this...first ..is this adding forward motor when only pitch would be used is QMODEs to fly forward rapidly? like Mark manual forward throttle?

what modes is this active? what about VTOL waypoint moves is AUTO?

does 0 gain disable it? (if so should be noted in metadata)

@priseborough
Copy link
Contributor Author

Paul some questions on this...first ..is this adding forward motor when only pitch would be used is QMODEs to fly forward rapidly? like Mark manual forward throttle?

It performs te following:

  1. Limits forward tilt to a value that allows the wing to go to a zero lift angle of attack but no more
  2. Replaces the forward acceleration that would have been produced by the tilt with thrust fro the forward motor

what modes is this active? what about VTOL waypoint moves is AUTO?

This method works in all VTOL modes other than auto-tune

does 0 gain disable it? (if so should be noted in metadata)

Yes it does and metadata has been updated to make this clear. Also I have updated metadata to make it clear that this method replaces the velocity controller method controlled by Q_VFWD_GAIN that is less accurate and only works on flight modes that use the velocity controller.

@priseborough priseborough force-pushed the pr-QuadPlaneFwdThrottle branch from 751a072 to 45f7699 Compare July 2, 2023 01:10
@pompecukor
Copy link

Going to test this soon. Will report back

@pompecukor
Copy link

pompecukor commented Jul 4, 2023

This method works in all VTOL modes other than auto-tune

Correction, it also does NOT work in Qstabilize mode.... Which is a good thing.

@priseborough priseborough force-pushed the pr-QuadPlaneFwdThrottle branch 2 times, most recently from 77667b9 to d247fab Compare July 4, 2023 23:45
@priseborough
Copy link
Contributor Author

I've consolidated the patches, fixed the bug preventing use with tilt rotors and incorporated feedback on parameter names and descriptions.

@pompecukor
Copy link

@priseborough
Tested, seems to work very nice. Logs sent.

@IamPete1
Copy link
Member

IamPete1 commented Jul 7, 2023

This is essentially adding an acceleration P gain. I completely agree that this is the way we need to go.

However I don't think this is the correct place. I would like to see a full PID acceleration controller implemented in the position controller and integrated with the 6DoF work @lthall and @bnsgeyer are working on. It will take a bit longer to get there, but the final result should be better.

@priseborough
Copy link
Contributor Author

This is essentially adding an acceleration P gain. I completely agree that this is the way we need to go.

However I don't think this is the correct place. I would like to see a full PID acceleration controller implemented in the position controller and integrated with the 6DoF work @lthall and @bnsgeyer are working on. It will take a bit longer to get there, but the final result should be better.

It is not adding a P gain, ie there is no new feedback loop. It is replacing the use of forward pitch to achieve acceleration with forward throttle to replace the acceleration lost due to pitch limiting,. As such I see this as being downstream of any acceleration feedback controller and belonging in a control mixer.

@IamPete1
Copy link
Member

IamPete1 commented Jul 8, 2023

It is not adding a P gain, ie there is no new feedback loop. It is replacing the use of forward pitch to achieve acceleration with forward throttle to replace the acceleration lost due to pitch limiting,. As such I see this as being downstream of any acceleration feedback controller and belonging in a control mixer.

Sorry, your of course right. I'm confusing what I had in mind and what you actually did.

However I still think this is in the wrong place, the position controller needs visibility of this extra degree of freedom. For example this lets the vehicle go quite fast while staying level, however that speed is still constrained by Q_ANGLE_MAX, dispute the pitch angle staying at 0.

To elaborate on the approach I was thinking about. We add a 2D acceleration controller, unlike the current position controller we align to vehicle yaw so we can have different forward/back and left/right gains. The closed loop nature of this controller means that we can just hard code the mixing that you have parameterized with Q_FWD_THR_GAIN. It should also deal with none-linearity in throttle -> thrust response such as those we fix with the expo parameter for vertical motors. It should also deal with moving between angle and control and the new degree of freedom. Having the acceleration controller also means we can define acceleration limits, which we cannot currently do. I hope that the new acceleration controller would be like our other position controllers that are quite robust and easy to tune to a reasonable level (half it until it stops wobbling).

@priseborough
Copy link
Contributor Author

priseborough commented Jul 22, 2023

It is not adding a P gain, ie there is no new feedback loop. It is replacing the use of forward pitch to achieve acceleration with forward throttle to replace the acceleration lost due to pitch limiting,. As such I see this as being downstream of any acceleration feedback controller and belonging in a control mixer.

Sorry, your of course right. I'm confusing what I had in mind and what you actually did.

However I still think this is in the wrong place, the position controller needs visibility of this extra degree of freedom.

I would propose a different way of architecting the required functionality. How about making the position controller agnostic to the method that is used to generate a specific force in the Front Right Down directions and let the vehicle libraries to the required mapping as this is gong to be unique to different vehicle types. I don't think long term the position controller should be responsible for the mapping from specific force demand to actuation.

@priseborough
Copy link
Contributor Author

These changes should not impact on future position controller restructuring. The attached sketch shows how the position controller (PSC) pitch setpoint is limited in the quadplane code and converted to the forward throttle demand in quadplane::calc_fwd_tilt_throttle() This is all done open loop.

IMG_2103

Extending this to the tilt rotor case was trivial f896636 as the functionality required to convert a forward thrust demand to a rotor tilt already exisited.

What I would like to see us adopt in the future is a more generic position controller interface that outputs specific force demands in the forward and right direction. The vehicle code would then convert that to whatever combination of vehicle attitude, actuation angles and motor throttle required to produce the required force. This would require the vehicle code to provide the position controller with dynamically updated saturation limits for specific force in the front, back, right, left directions.

@timtuxworth
Copy link
Contributor

I'm expecting to see a position controller class. Am I missing something?

@priseborough
Copy link
Contributor Author

Here is an example acceleration into wind in QLOITER mode from @pompecukor 's testing with

Q_FWD_PIT_LIM 500
Q_FWD_THR_GAIN 2.0
Q_VFWD_GAIN 0.000000

The aircraft can now achieve over 30 m/s of airspeed in QLOITER without porpoising or losing height. The following figure shows a stick forward acceleration to maximum ground speed followed by a stick release decel.

Screen Shot 2023-07-25 at 8 47 52 pm

Note the height gain during decel which is due to the pitch back and increase in wing lift. This PR does not modify that behaviour. Height control accuracy was good during the acceleration phase.

Screen Shot 2023-07-25 at 8 52 09 pm

The following figure shows right and left rotor tilt servo PWM demand where forward tilt are larger values.

Screen Shot 2023-07-25 at 8 56 47 pm

The position controller was able to control horizontal position accurately throughout.

Screen Shot 2023-07-25 at 9 00 23 pm

@@ -92,7 +92,7 @@ void ModeQLoiter::run()

// call attitude controller with conservative smoothing gain of 4.0f
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
plane.nav_pitch_cd,
MAX(plane.nav_pitch_cd, quadplane.q_fwd_nav_pitch_lim_cd),
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We should apply this up on 84, the set_VTOL_roll_pitch_limit call will be limiting to the wrong value other wise. So 84 would become:

plane.nav_pitch_cd = MAX(loiter_nav->get_pitch(), quadplane.q_fwd_nav_pitch_lim_cd);

Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The throttle handling stuff all looks good. But I think we need to be very careful where we apply the angle limit, since were now directly affecting what a mode it doing by taking away pitch forward rather than just adding extra throttle I think we should output the throttle in the same place we apply the angle limit such that we can never get one without the other.

I think we also need to make sure we update nav_pitch_cd to the limited value because it is used throughout the code in various odd places that might get upset if it does not represent what the vehicle is doing.

I'm happy to help with some re-work if that would be usefull.

Comment on lines 656 to 657
q_fwd_throttle = 0.0f;
q_fwd_nav_pitch_lim_cd = -aparm.angle_max;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

maybe a "is_active" method rather than keeping this copy.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't understand.

@@ -934,13 +953,13 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds)

if (use_yaw_target) {
attitude_control->input_euler_angle_roll_pitch_yaw(plane.nav_roll_cd,
plane.nav_pitch_cd,
MAX(plane.nav_pitch_cd, q_fwd_nav_pitch_lim_cd),
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think we have to set nav_pitch_cd to this limit before getting into this call. For example tailsitter transitions need to break these rules. I know that tailsitters should never have this set, but they might.

@IamPete1
Copy link
Member

IamPete1 commented Jul 25, 2023

I just thought of something else that makes this even more tricky to implement. We need to tell the position controller when we have run out of throttle or tilt so it can stop winding up I term. We do have a set_externally_limited_xy() but I'm not sure how well that would work for long periods, currently its only used temporally in the transition and for touch down.

@priseborough
Copy link
Contributor Author

priseborough commented Jul 31, 2023

I just thought of something else that makes this even more tricky to implement. We need to tell the position controller when we have run out of throttle or tilt so it can stop winding up I term. We do have a set_externally_limited_xy() but I'm not sure how well that would work for long periods, currently its only used temporally in the transition and for touch down.

I can achieve the required integrator protection by calling set_lean_angle_max_cd to provide a lean angle that corresponds to when forward throttle will be saturated. I would like to split set_lean_angle_max_cd into a separate call for forwards tilt. I'll give you a call to discuss.

@priseborough priseborough force-pushed the pr-QuadPlaneFwdThrottle branch from 59dfc69 to 918b46f Compare August 13, 2023 07:23
@priseborough
Copy link
Contributor Author

@IamPete1 I've reworked it to move the angle limiting and forward thrust calculation to just after we get the demanded pitch angle from the position controller so that a consistent pitch angle demand is guaranteed for all downstream processing.

priseborough and others added 22 commits September 26, 2023 16:10
and use a common function for the active method
Don't unnecessarily increase the forward pitch limit when position control forward action is saturated.
@@ -35,6 +35,11 @@ void ModeQStabilize::update()
plane.nav_roll_cd = roll_input * plane.quadplane.aparm.angle_max;
plane.nav_pitch_cd = pitch_input * plane.quadplane.aparm.angle_max;
}

if (plane.control_mode->mode_number() == Mode::Number::QSTABILIZE) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this check is preventing assign_tilt_to_fwd_thr() being called in QHOVER mode. I just tested QHOVER and the new functionality doesn't work with the RC switch
we can either remove the check and remove the call in qloiter, qrtl etc, or add the call into all the relevant modes
I think it is better to have it in one place?

@tridge
Copy link
Contributor

tridge commented Sep 26, 2023

I don't think we can fix the above issue by just always running in qstabilize for all modes as it would defeat the checks per-mode for things like throttle_wait, if a user put the nose down while in throttle wait it would run up the fwd motor
but that means we need to be sure we put plane.quadplane.assign_tilt_to_fwd_thr() in all modes that are missing it now, or we could end up without vfwd support where we have it now with the old system.

this prevents double calling and fixes qhover
@tridge tridge force-pushed the pr-QuadPlaneFwdThrottle branch from 68c9928 to 1d4c738 Compare September 26, 2023 08:56
@tridge
Copy link
Contributor

tridge commented Sep 26, 2023

@priseborough as discussed, I've fixed by moving the assign tilt to the run() function

@tridge tridge merged commit babdb36 into ArduPilot:master Sep 27, 2023
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

8 participants