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

Leonard's new Loiter #7258

Closed
wants to merge 53 commits into from
Closed

Conversation

rmackay9
Copy link
Contributor

This PR from @lthall and I does the following:

  • new more responsive Loiter mode which accept lean angle inputs from the pilot making it feel more like AltHold mode. Despite accepting lean-angle inputs the position, velocity and acceleration controllers remain active at all times ensuring the vehicle fights against disturbances. This is quite different from PosHold mode which does not attempt to maintain position or velocity while the pilot provides stick input.
  • new Loiter also includes active braking when the pilot releases the sticks.
  • AC_PositionController's horizontal velocity controller changes from a AC_PI_2D to AC_PID_2D object. This new object includes a D gain and a D_FILT (d input filter).
  • vertical and horizontal P and PID objects are moved from the vehicle parameters list into the AC_PositionControl class (which leads to the parameters changing from POS_XY_P and VEL_XY_P to PSC_POXXY_P and PSC_VELXY_P, etc).
  • all flight modes that use the position controller now attempt to maintain altitude by limiting vehicle lean-angle (this feature is within the position controller itself and is now always active - previously it could be enabled/disabled by the caller). This should resolve the porpoising problem sometimes seen in Auto mode especially when flying against the wind near the vehicle's physical speed limits.
  • Attitude Controller gets angular velocity limits (see ATC_ANG_V_R/P/Y_MAX)

New/Changed Parameters include:

  • WPNAV_LOIT_ANGM allows the pilot to specify the maximum lean angle in Loiter. If left at the default of zero, the vehicle leans at 2/3rds the ANGLE_MAX parameter value.
  • WPNAV_LOIT_DELA holds the delay in seconds between when the pilot releases the transmitter sticks and the active braking begins (defaults to 1 second).
  • WPNAV_LOIT_TRAN holds the transition time in seconds between when the vehicle starts braking and achieves maximum braking. Lower number means brake engages more quickly.
  • WPNAV_LOIT_JERK has been removed (perhaps @lthall can explain why it's no longer needed).
  • POS_XY_P becomes PSC_POSXY_P
  • VEL_XY_P/I/IMAX/FILT becomes PSC_VELXY_P/I/IMAX/FILT/D_FILT
  • ACCEL_XY_P/I/D/FILT becomes PSC_ACCELXY_P/I/D/FILT
  • POS_Z_P becomes PSC_POSZ_P
  • VEL_Z_P becomes PSC_VELZ_P
  • ACCEL_Z_P/I/D/FILT becomes PSC_ACCELZ_P/I/D/FILT
  • ATC_ANG_V_R/P/Y_MAX angular velocity limits in degrees/second

There are some outstanding issues that need to be resolved before this can go into master:

  • are we happy with some of the new parametesr using deg or deg/sec while many of the older parameters use centi-degrees or centi-degrees/second. ATC_ANG_V_R and WPNAV_LOIT_ANGM are examples of this change.
  • QuadPlane and Sub position controller gains have changed (they are the same as Copter) so we need to either pass in the default gains to the position controller constructor or have the vehicles actively set the defaults as part of their startup.
  • more testing of Copter to ensure the vehicle doesn't move around too much after the pilot releases the sticks
  • more testing that the porpoising problem in auto has been resolved
  • more testing of Sub and Quadplane to ensure nothing has been broken

@lthall
Copy link
Contributor

lthall commented Nov 21, 2017

WPNAV_LOIT_JERK was added because optical flow needed to limit the maximum rotation rate to function reliably. As this parameter limits the rate of change of acceleration, not the rate of change of angle, it did not directly address the need to limit rate of change of angle. It also unnecessarily complicated the attitude controller and could cause poor performance if set incorrectly (the default value was compromising performance). The Attitude controller now provides the function to limit maximum rotation rate directly.

The maximum rotation rate has a number of uses:

  • Limit the optical flow to within usable limits.
  • Limit maximum rotation rate when recovering from a large error
  • Limit maximum rotation rate after a large commanded attitude change
  • Ensure that gimbal payloads are not saturated by high aircraft rotation rates

@Pedals2Paddles
Copy link
Contributor

all flight modes that use the position controller now attempt to maintain altitude by limiting vehicle lean-angle (this feature is within the position controller itself and is now always active - previously it could be enabled/disabled by the caller). This should resolve the porpoising problem sometimes seen in Auto mode especially when flying against the wind near the vehicle's physical speed limits.

Does this also mean that if you are flying around manually in loiter or on autopilot in guided, auto, RTL, etc, and you start going too fast to maintain altitude, it will back off the lean angle to prevent the altitude decay? Wheras before you could continue to go faster and faster as altitude decayed faster and faster. And in Alt Hold, pos hold, sport, acro, and stabilize, it is unchanged?

@lthall
Copy link
Contributor

lthall commented Nov 21, 2017

@Pedals2Paddles
Yes, the maximum lean angle will be limited in any Alt_Hold based mode to ensure the aircraft can maintain altitude. Before all but a few of the flight modes would prioritise the lean angle over maintaining altitude and could be flow into the ground.

@Pedals2Paddles
Copy link
Contributor

Ah, ok. So this will apply to all modes except stab, acro, and drift since I believe those are the only three modes that do not use the altitude hold controller. Very cool. Is there a parameter to enable/disable this functionality, or is it always on?

@lthall
Copy link
Contributor

lthall commented Nov 21, 2017

@Pedals2Paddles It is always on now.

@lthall
Copy link
Contributor

lthall commented Nov 21, 2017

My main question is where should we set PSC_VELXY_D on the range from 0 to 1?
Higher values will encourage porpoising in AUTO missions when fighting into a head wind.
Lower values may require PSC_VELXY_P and PSC_VELXY_I to drop from 2 and 1 down to 1 and 0.5. You will be able to tell this is the case because the aircraft bobs around a bit after a large stick input in loiter.

To set up Loiter correctly you should set WPNAV_LOIT_SPEED to your maximum speed when holding 30 degrees lean angle assuming you have default maximum lean angle set. So I would be interested in what people think we should set this to. I am thinking approximately 1500 at this stage.

@Pedals2Paddles
Copy link
Contributor

To set up Loiter correctly you should set WPNAV_LOIT_SPEED to your maximum speed when holding 30 degrees lean angle assuming you have default maximum lean angle set. So I would be interested in what people think we should set this to. I am thinking approximately 1500 at this stage.

Would it be problematic or act strangely if the max loiter speed and max angle are not close together as described? The loiter speed is something that the operator would commonly adjust based on mission needs. And in those cases, the user changing the max angle to correspond is pretty rare. Is making the parameter default max speed and lean angle just for consistency, or is the programmatic and handling reason for it?

@lthall
Copy link
Contributor

lthall commented Nov 21, 2017

@Pedals2Paddles
Not really.

If the maximum speed is a little low the aircraft tends to lean over and level out. Then after the stick is released it tends go into an immediate gentle braking maneuver.

If the maximum speed is a little high the aircraft tends to lean over then slowly lean a little further as speed builds. When the stick is released the aircraft does not come all the way back to level then levels out as it slows.

I generally find that the pilot experience is much better when the speed is set too high than too low.

lthall and others added 20 commits November 25, 2017 10:35
Also constify existing get_accel_roll/pitch/yaw_max methods
Smoothing gain value should be set once when entering a mode
also add limit_vector_length and sqrt_controller helper functions
enforce angle limits
rename accel-feedforward to accel-desired
remove freeze_ff_xy
remove unused VEL_XY_MAX_FROM_POS_ERR
remove xy mode
remove Jerk Limiting code
move get_horizontal_error declaration to be with other xy method declarations
clarify set-accel-xy sets maximum acceleration
remove blank line
}
if (!is_zero(ang_vel_pitch_max)) {
euler_rad.y = constrain_float(euler_rad.y, -ang_vel_pitch_max, ang_vel_pitch_max);
}
Copy link
Contributor

Choose a reason for hiding this comment

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

@lthall This nested if statement doesn't make sense. first the outer if statement has a an or statement for the same test "is_zero(ang_vel_pitch_max)". Then the nested if statement tests for the reverse of the outer if statement "!is_zero(ang_vel_pitch_max)". Not say this is the issue that @ChristopherOlson found but found this inconsistency.

Copy link
Contributor

Choose a reason for hiding this comment

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

The first statement checks to see if either one is zero the nested if statements then address if one of them is not zero.

It may have been more intuitive to check to see if both were not zero then handle that case then handle if either one is not zero and the other is.

Copy link
Contributor

Choose a reason for hiding this comment

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

why does this first statement looking at pitch only in both evaluations and not pitch and roll
if (is_zero(ang_vel_pitch_max) || is_zero(ang_vel_pitch_max)) {

Copy link
Contributor

Choose a reason for hiding this comment

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

Yep, dyslexic boy strikes again!!
That should be roll then pitch!!

Thanks Bill!

Choose a reason for hiding this comment

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

@lthall Hi, so how about this PR? I'm trying to have a test but found that commit Copter: Loiter updates has disabled this function?

Copy link
Contributor

Choose a reason for hiding this comment

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

@roger-zhao Can you please explain what you are asking

Choose a reason for hiding this comment

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

@lthall Sorry for my unclear description, what I'm saying it that when I try to build a FW from source code in Randy's branch lthall-new-loiter5, I've found that branch is different with source code in your branch NewLoiter-09122017 , and after source code comparing, it seems like in your branch, the new-loiter's "mapping pilot input to lean-angle implementation" has been deleted again (mightbe I'm wrong with this becasue I'm just doing a source code comparing), so I'm not sure if I should build FW from Randy's branch lthall-new-loiter5 or your branch NewLoiter-09122017 for testing this new loiter.

Thanks to Bill for finding this
@lthall
Copy link
Contributor

lthall commented Jan 5, 2018

@roger-zhao
This is the current latest version.
https://github.com/lthall/Leonard_ardupilot/tree/newLoiter-31122017

Randy and I should be getting it into master soon too.

@roger-zhao
Copy link

@lthall Got it. I've watch this youtube demo, and can't wait to test it even might be little risky. :)

@OXINARF
Copy link
Member

OXINARF commented Jan 27, 2018

Superseded by #7606.

@OXINARF OXINARF closed this Jan 27, 2018
@rmackay9 rmackay9 deleted the lthall-new-loiter5 branch April 9, 2020 11:00
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

6 participants