Skip to content
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

Tradheli: fix yaw attitude error corrections while rotors turning on the ground #28690

Open
wants to merge 11 commits into
base: master
Choose a base branch
from

Conversation

bnsgeyer
Copy link
Contributor

This PR addresses an issue with the handling of yaw attitude error corrections being fed to the rate controller when the aircraft is on the ground with rotors turning. Currently the yaw attitude error correction is being fed to the rate controller with both integrator management schemes. This PR keeps the heading error correction when using the leaky integrator but removes it when using the integrator management that triggers on the landing detector.

This also cleans up some inconsistencies in the logic with landed and pretakeoff althold states in each of the non-manual throttle flight modes.

It also addresses the definition of behaviors for Spool up/down which was not addressed at all in the manual throttle modes. The only one that affects copter is Drift

Needs testing.

@MattKear
Copy link
Contributor

@bnsgeyer why not apply this to the leaky I case as well? I appreciate it is arguably not needed, but there is also no harm in applying it, as far as I can tell. By not applying it would reduce the amount of checks in the if statements and make the code easier to read.

@bnsgeyer
Copy link
Contributor Author

@MattKear Leaky I allows the I term to grow as soon as motor interlock is enabled. This PR assumes no change to the leaky I integrator management case. Thus the heading error corrections are allowed with motor interlock enabled if the user is using leaky I.

Are you referring to the added logic in the Drift mode? I realized as I reviewed the current code that drift mode did not conform to how heli stabilize and heli acro handled the I term. There were some other inconsistencies that I fixed as well.

@Ferruccio1984
Copy link
Contributor

Hi @bnsgeyer code looks good to me, will potentially solve the behavior reported for the tandem heli setup. There is a little window of non-safety though for traditional tail rotor helis when taking off/landing on concrete helipads. In the video attached I poked a little the "light on the skids" condition: the situation can potentially evolve into dynamic roll-over if the pilot keep the collective up but not enough to take-off. Could be problematic also for auto takeoff and landing. I would think if adjusting this implementation into a bitmask option would be a win-win for both trad-helis and tandems?
https://www.youtube.com/watch?v=Y5TvBSDiLH8

@bnsgeyer
Copy link
Contributor Author

@Ferruccio1984 I have added a option to H_OPTIONS to turn off/on heading error correction on the ground

@bnsgeyer
Copy link
Contributor Author

After working through the details of the changes, here are the desired behaviors for the yaw axis.

The goal is to allow helicopters sensitive to heading corrections on the ground to operate without these corrections. The heading error correction by the attitude controller is responsible for the heading corrections on the ground.

This change was only intended for the non-leaky I integrator scheme and leaky I only affected manual collective modes. There should be no change when using the leaky i integrator scheme.

The H_OPTIONS Bitmask was used to allow users to choose between attitude controller using heading error correction or not.

When using heading error correction, behaviors should not have changed in manual and non-manual collective modes.
landed, motor interlock disabled (althold state: Landed_Ground_Idle) - targets heading reset and zero I term
this is required to keep stick inputs from moving target heading
zeroing I term was added for non-manual collective modes - this was missed when spool logic was added
landed, motor interlock enabled (althold state: Landed_Pre_Takeoff) - target heading released but still zero I term

When NOT using heading error correction, only yaw rate feedback is used on the ground. This serves two purposes. 1) to provide pilot control of yaw axis and 2) allowing autopilot to help fight gusts.
landed, motor interlock disabled (althold state: Landed_Ground_Idle) - targets heading reset and zero I term
this is required to keep stick inputs from moving target heading
landed, motor interlock enabled (althold state: Landed_Pre_Takeoff) - target heading reset and zero I term

Copy link
Contributor

@MattKear MattKear left a comment

Choose a reason for hiding this comment

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

Generally speaking, this makes sense, as we do need to improve the heading target handling on the ground.

I do not understand why we need the separation of using leaky I or not in this though. In my mind, regardless of whether leaky I is enabled, we do not want to allow heading or yaw rate errors to build when we are on the ground.

// use leaking integrator management scheme is always false for multirotors
virtual bool using_leaky_integrator() const { return false; }
// use heading error correction which is always true for multirotors
virtual bool using_hdg_error_correction() const { return true; }
Copy link
Contributor

Choose a reason for hiding this comment

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

I do not think we should not be making these virtuals in AP_Motors_Class. We are taking something that is a heli-only option and making visible in the multi-copter code. Instead we should keep it in AP_MotorsHeli and use defines for the option, as we do else where in the code.

Copy link
Contributor

Choose a reason for hiding this comment

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

We have been trying to remove the hash defines in the shared code and instead make it flexible enough to cover all the hovering aircraft.

The aspirational goal is to not have any Heli specific code in the shared code base and instead have optional behaviour that is defined by the vehicle.

@@ -138,11 +138,15 @@ class AP_MotorsHeli : public AP_Motors {

// enum for heli optional features
enum class HeliOption {
USE_LEAKY_I = (1<<0), // 1
USE_LEAKY_I = (1<<0),
USE_HDG_CORRECTION = (1<<1),
Copy link
Contributor

Choose a reason for hiding this comment

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

I do not want to feature creep this PR, so I am just saying this as a recommendation for future work. I think it is weird that we ask AP_Motors whether we should be using leaky I and now this heading correction. I understand that it is a hang over because most of the heli specific code lives in motors, but in the future I would like to move the heli option param out of motors and up to the vehicle(copter) level. This adds to my point below as to why I would rather we didn't make it a virtual function.

attitude_control->reset_rate_controller_I_terms_smoothly();
init_wind_comp_estimate();
Copy link
Contributor

Choose a reason for hiding this comment

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

This is unrelated to this PR. Did you mean to add this?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

@MattKear maybe I was wrong here. I thought that it was needed because I removed the fallthrough. I will remove it unless told otherwise.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

fixed. Thanks.

pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target();
Copy link
Contributor

Choose a reason for hiding this comment

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

This is unrelated to this PR. Did you mean to add this?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

@MattKear @lthall This does not follow the same flow as Loiter. I changed it because loiter is done this way. Not sure why they would be different. Again I can change it back if you think it should not change. Or I can just do a separate PR.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

fixed. Thanks,

bool using_leaky_integrator() const override { return heli_option(HeliOption::USE_LEAKY_I); }

// use heading error correction
bool using_hdg_error_correction() const override { return heli_option(HeliOption::USE_HDG_CORRECTION); }
Copy link
Contributor

Choose a reason for hiding this comment

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

Do we need this as an option? What is the use case that users will be trying to drive yaw whilst on the ground?

@@ -125,17 +125,21 @@ void ModeLoiter::run()

case AltHoldModeState::MotorStopped:
attitude_control->reset_rate_controller_I_terms();
attitude_control->reset_yaw_target_and_rate();
attitude_control->reset_yaw_target_and_rate(true);
Copy link
Contributor

Choose a reason for hiding this comment

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

this is not a change in behaviour, default value is true.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Ok. I wasn't sure that I needed to do this. I saw that it was done in one place so I thought I needed to do it in all places. I can remove it.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

fixed. Thanks.

FALLTHROUGH;
attitude_control->reset_yaw_target_and_rate(false);
attitude_control->reset_rate_controller_I_terms_smoothly();
break;
Copy link
Contributor

Choose a reason for hiding this comment

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

This is a fairly significant change in behaviour by removing the fall through. We would at least want to keep the loiter_nav->init_target()?

Copy link
Contributor

Choose a reason for hiding this comment

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

Yep, we need to add the loiter_nav->init_target();

I think we can move this to the bottom:

attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false);

Copy link
Contributor Author

Choose a reason for hiding this comment

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

@lthall I think I need to move all of the lines in the pretakeoff state up to the landed ground idle since I removed the fall through.

pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
loiter_nav->init_target();
attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false);
break;

case AltHoldModeState::Landed_Ground_Idle:
attitude_control->reset_yaw_target_and_rate();
FALLTHROUGH;
attitude_control->reset_yaw_target_and_rate(false);
Copy link
Contributor

Choose a reason for hiding this comment

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

Why wouldn't we want to reset_rate on landed ground idle?

Copy link
Contributor

Choose a reason for hiding this comment

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

This provides some damping to the tail if it gets pushed by a gust or something but will stay close to zero as long as we keep the integrator zero.

Copy link
Contributor

@lthall lthall left a comment

Choose a reason for hiding this comment

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

Looks like it is close!

@@ -45,26 +45,29 @@ void ModeAcro_Heli::run()
switch (motors->get_spool_state()) {
case AP_Motors::SpoolState::SHUT_DOWN:
// Motors Stopped
attitude_control->reset_target_and_rate(false);
Copy link
Contributor

Choose a reason for hiding this comment

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

Changing this from false to true here will remove all counter talk on the tail rotor. If you can be still spinning down in this phase of flight this will let the tail move more than it would do now.

Low risk but something to consider.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

@lthall What do you mean by counter talk? I think the issue here is that when disarmed, there won't be any target reset that would cause an issue with trying to fly disarmed. I know this sounds crazy but I believe that this was intentional by my predecessor to allow users to fly in acro if the aircraft disarms unexpectedly, like due to code bug. I think that this should true so that the attitude errors are reset. However I may make this change in a separate PR to make this more visible as an intentional change.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

@Ferruccio1984 What do you think of having the attitude error correction (pitch and roll) removed for the disarmed state in acro. This means that when you move the pitch and roll stick that the swashplate will not react while disarmed which is what you probably saw in your flight today. I think it is a good idea because it would keep users from moving the swashplate while disarmed and then being surprised on spool up if the swash was not centered. I think the idea of ever having to fly in a disarmed state is very low risk.

pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
loiter_nav->init_target();
attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false);
break;

case AltHoldModeState::Landed_Ground_Idle:
attitude_control->reset_yaw_target_and_rate();
FALLTHROUGH;
attitude_control->reset_yaw_target_and_rate(false);
Copy link
Contributor

Choose a reason for hiding this comment

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

This provides some damping to the tail if it gets pushed by a gust or something but will stay close to zero as long as we keep the integrator zero.

FALLTHROUGH;
attitude_control->reset_yaw_target_and_rate(false);
attitude_control->reset_rate_controller_I_terms_smoothly();
break;
Copy link
Contributor

Choose a reason for hiding this comment

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

Yep, we need to add the loiter_nav->init_target();

I think we can move this to the bottom:

attitude_control->input_thrust_vector_rate_heading(loiter_nav->get_thrust_vector(), target_yaw_rate, false);

// use leaking integrator management scheme is always false for multirotors
virtual bool using_leaky_integrator() const { return false; }
// use heading error correction which is always true for multirotors
virtual bool using_hdg_error_correction() const { return true; }
Copy link
Contributor

Choose a reason for hiding this comment

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

We have been trying to remove the hash defines in the shared code and instead make it flexible enough to cover all the hovering aircraft.

The aspirational goal is to not have any Heli specific code in the shared code base and instead have optional behaviour that is defined by the vehicle.

@bnsgeyer bnsgeyer requested a review from lthall December 3, 2024 19:07
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.

4 participants