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

Fixed-wing speed modes #18605

Closed
wants to merge 14 commits into from
Closed

Fixed-wing speed modes #18605

wants to merge 14 commits into from

Conversation

sfuhrer
Copy link
Contributor

@sfuhrer sfuhrer commented Nov 9, 2021

Describe problem solved by this pull request

  • no interface to change airspeed in auto flight if not in mission
  • no interface at all to change climb/descend speed
  • TECS can only be tuned properly for one single airspeed setpoint
  • flying in high wind with an airspeed setpoint close to stall is dangerous due to increased external disturbances, so the airspeed setpoint should ideally be increased in these situations

Describe your solution

  • add logic to enable fixed-wing speed modes (Normal, Eco, Dash)
  • adapt airspeed setpoint adaption in Auto modes

Speed modes:
The idea is to introduce speed modes that the user can easily and without in-depth knowledge of the system trigger to fly slow and thus safe energy ("Eco"), normally or fast ("Dash").

Eco: Flying in Eco reduces the airspeed setpoint to FW_AIRSPD_MIN, the climb rate to FW_T_CLMB_R_SP_E and allows to change internal TECS tuning via the speed weight and the altitude time constant, such that it uses less energy trying to keep the altitude very precisely and instead can exploit thermals to climb to some extend.

Dash: Sets the airspeed setpoint to FW_AIRSPD_MAX. No other settings are are changed atm, but it would be straight forward to e.g. add separate climb/descend rates.

Setting of speed mode:
Currently enabled via parameter FW_SPD_MODE_SET, but should be replaced by a mavlink message as it should be easy to set in flight by the user. FW_SPD_MODE_SET has 5 options:

  • 0: Normal
  • 1: Eco when in cruise (level flight)
  • 2: Eco (also when not in level flight)
  • 3: Dash when in cruise
  • 4: Dash
    Additionally to the setting done by the user, there are customizable checks in place to disable Eco and Dash if flying low (below FW_ALT_MIN) or if the current altitude error is high (there are separate limits for below and above the setpoint, FW_ALT_ERR_U and FW_ALT_ERR_O).

Airspeed adaption in Auto modes:
The following graph roughly shows the data flow for the airspeed setpoint. Some of it was already in place (groundspeed undershoot, load-factor based airspeed setpoint constraining). Let me know if you think the logic should be cleaned up a bit, it's currently quite patched together with the legacy setpoint adaptions.
image

Wind-based adaption:
If flying in Eco mode (thus normally close to stall speed), there is an offset added to the airspeed setpoint: setpoint += FW_WIND_ARSP_SC * abs(wind). So if the scale is set to 0.2, then for 10m/s there are 2m/s added to the setpoint that help making the vehicle's attitude control more robust to disturbances caused by the high wind, plus reduces the chance of a groundspeed undershoot.

How could interface on ground station look like
There could be a slider for the 5 speed options, something like this:
image

The closes mavlink message we have for setting the flight speed is MAV_CMD_DO_CHANGE_SPEED. Likely it's though cleaner to introduce a new message, e.g. DO_SET_SPEED_MODE. I guess this could also be useful for Multicopter applications? To be able to speed up the execution of a mission part, or to have it fast going to a a place.

Describe possible alternatives
Currently all the airspeed setpoint adaptions are only happening in Auto flight. We should also think about enabling them (or some of them) in Manual flight modes containing an airspeed setpoint (Position, Altitude).
Are the names "Eco" and "Dash" descriptive? Or how about "Eco" and "Sport"?

Test data / coverage
SITL tested, and party flight tested on real vehicles.

Additional context


} else {
// stay in flight phase level if only small altitude changes are demanded (<10m)
if (altitude_sp_amsl - _alt_control_traj_generator.getCurrentPosition() > 10.0f) {
Copy link
Contributor Author

@sfuhrer sfuhrer Nov 9, 2021

Choose a reason for hiding this comment

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

Instead of hard-coding the limits (10m atm), we could link it to FW_ALT_ERR_U and FW_ALT_ERR_O.

src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp Outdated Show resolved Hide resolved
src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp Outdated Show resolved Hide resolved
{
float airspeed_setpoint = _param_fw_airspd_trim.get();

if (_speed_mode_current == FW_SPEED_MODE::FW_SPEED_MODE_ECO) {
Copy link
Member

Choose a reason for hiding this comment

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

Rather than using the global variable, can we make this a parameter of the function? That way the behavior is more consistent

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Yep, have a look at 008a14d. Do you like that more? Agree that it's more consistent with the current architecture of FW Pos Control

src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp Outdated Show resolved Hide resolved
src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp Outdated Show resolved Hide resolved
src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp Outdated Show resolved Hide resolved
src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp Outdated Show resolved Hide resolved
src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp Outdated Show resolved Hide resolved
src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c Outdated Show resolved Hide resolved
src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c Outdated Show resolved Hide resolved
src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c Outdated Show resolved Hide resolved
src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c Outdated Show resolved Hide resolved
@sfuhrer
Copy link
Contributor Author

sfuhrer commented Nov 11, 2021

Thanks for the initial reviews @Jaeyoung-Lim and @RomanBapst . I've addressed your points, please have a look again.

I want to stress again that this here only presents an intermediate solution - eventually FW_SPD_MODE_SET needs to be replaced by a mavlink message. See PR description. Would be great to get feedback on that as well!

RomanBapst
RomanBapst previously approved these changes Nov 12, 2021
@roman-dvorak
Copy link
Contributor

Hi @sfuhrer, this PR seems very useful. I feel better, that the target airspeed can then be set continuously from airspeed_min to airspeed_max. Not only with three values (eco/trim/dash). This would be useful because UAVs may have different optimal speeds in terms of flight path length or flight duration. And it would be good to be able to change these values somehow dynamically. Independent of min and max values.

I think AIRSPEED_MIN and AIRSPEED_MAX should be the limit values of drone design. Not the values that should normally be flown.

I would imagine something in the form of a parameter that I would set between 0-1 (minimum and maximum flight airspeed). And some "buttons" that would set certain values of this parameter. These presets could be controlled from some RC channel or as a mavlink message.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
…flight in single function

Adapt the airspeed setpoint by:
- speed mode (ECO/NORMAL/DASH --> airspeed MIN, TRIM, MAX)
- if position setpoint contains valid airspeed setpoint use that instead
- increase setpoint if groundspeed gets low
- increase setpoint if close to MIN and banking (compensate higher load factor)

There is a slew rate limiting in place that allows max 1m/s/s rate of change of
the airspeed setpoint.

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
…auto modes

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
setpoint = FW_AIRSPD_MIN + FW_LND_AIRSPD_SC * wind

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Separate settings in Eco mode (beside airspeed):
- FW_T_CLMB_R_SP_E (slower climb for more efficiency)
- FW_T_ALT_TC_E (larger to reduce motor action due to altitude errors)
- FW_T_SPDWEIGHT_E (more weight to airspeed to reduce motor action due to altitude errors)

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
…nstead pass it as argument

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
@sfuhrer sfuhrer force-pushed the pr-fw-tecs-modes-master branch from 30f0fc4 to 1e80478 Compare November 25, 2021 09:22
@sfuhrer
Copy link
Contributor Author

sfuhrer commented Jan 13, 2022

Closing in favor of #18834

@sfuhrer sfuhrer closed this Jan 13, 2022
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