PX4 / PX4-Autopilot

PX4 Autopilot Software
https://px4.io
BSD 3-Clause "New" or "Revised" License
8.16k stars 13.36k forks source link

[VTOL] Broken Weathervane & broken MPC_YAW_MODE #15673

Open ThomasRigi opened 4 years ago

ThomasRigi commented 4 years ago

Describe the bug The weather vane does not work anymore in Mission (MC mode). Neither does MPC_YAW_MODE have an effect on the heading. So the drone ends up flying in all directions with the same heading, which is ugly to watch and can be dangerous in high winds.

To Reproduce

Tested in SITL on v1.11.0:

  1. Launch Gazebo with make px4_sitl gazebo_standard_vtol__windy (by default 4m/s wind from South to North)
  2. Execute some mission which contains navigation in MC mode (e.g. Dummy_MC_loop.zip)
  3. Observe the heading.

Expected behavior As stated in the docs (https://docs.px4.io/master/en/config_vtol/vtol_weathervane.html#mission-mode-behaviour). The drone should head into the wind. Also, MPC_YAW_MODE should behave as for a normal MC. I'm open to discussion whether the weather vane should have precedence over the heading calculations of MPC_YAW_MODE or not or if both should be active at the same time and you end up with a compromise. But certainly not changing the heading at all is not good.

Log Files and Screenshots https://logs.px4.io/plot_app?log=41546a93-eaeb-45c8-af75-fcfd2af6b967 : always heading east, neither weathervaning nor heading towards waypoint.

https://review.px4.io/plot_app?log=5cd8b35e-390b-476c-85fb-30ac2fd3ff42 : high winds on a custom branch with minor modifications from v1.11-beta. The drone gets carried away because it can't fight the wind in its bad orientation. --> dangerous situation.

Drone (please complete the following information): gazebo_standard_vtol

xdwgood commented 4 years ago

@ThomasRigi I tried to increase the simulated wind speed to 10, and then execute take off, I can clearly observe that the drone's head is rotating correctly

But I noticed that when the mission has the yaw setting value, follow the yaw generated by the weather vane? Or mission setting yaw? , This may need to be clear. But in takeoff and lioter modes, there is no problem with the rotation of the heading

ThomasRigi commented 4 years ago

In mission also at 10m/s there is the heading issue: windy setup: <windDirectionMean>1 0 0</windDirectionMean> <windVelocityMean>10.0</windVelocityMean>

Log: https://logs.px4.io/plot_app?log=89f49258-1649-4af9-ad1c-39ba0271a870

But good to know that the weather vane works at least in take off and loiter mode. :)

xdwgood commented 4 years ago

Judging from the current code logic, the yaw generated by the weather vane will give priority to the yaw generated by the mission.

if (_ext_yaw_handler != nullptr && _ext_yaw_handler->is_active()) {
        _yaw_setpoint = _yaw;
        // use the yawrate setpoint from WV only if not moving lateral (velocity setpoint below half of _param_mpc_xy_cruise)
        // otherwise, keep heading constant (as output from WV is not according to wind in this case)
        bool vehicle_is_moving_lateral = _velocity_setpoint.xy().longerThan(_param_mpc_xy_cruise.get() / 2.0f);

        if (vehicle_is_moving_lateral) {
            _yawspeed_setpoint = 0.0f;

        } else {
            _yawspeed_setpoint = _ext_yaw_handler->get_weathervane_yawrate();
        }

    } else if (_type == WaypointType::follow_target && _sub_triplet_setpoint.get().current.yawspeed_valid) {
        _yawspeed_setpoint = _sub_triplet_setpoint.get().current.yawspeed;
        _yaw_setpoint = NAN;

    } else {
        if ((_type != WaypointType::takeoff || _sub_triplet_setpoint.get().current.disable_weather_vane)
            && _sub_triplet_setpoint.get().current.yaw_valid) {
            // Use the yaw computed in Navigator except during takeoff because
            // Navigator is not handling the yaw reset properly.
            // But: use if from Navigator during takeoff if disable_weather_vane is true,
            // because we're then aligning to the transition waypoint.
            // TODO: fix in navigator
            _yaw_setpoint = _sub_triplet_setpoint.get().current.yaw;

        } else {
            _set_heading_from_mode();
        }

        _yawspeed_setpoint = NAN;
    }
sfuhrer commented 3 years ago

Yes, since https://github.com/PX4/Firmware/pull/13782 WV is disabled when moving. The idea of WV how I understand it (yes, the docs would need some updating) is that the nose of the VTOL is always pointed into the (external) wind, as that is the dangerous factor for VTOLS, rather than the airspeed it picks up when moving lateral (wind can be at 15 m/s, normally VTOLs move laterally at 5 m/s or so). So it doesn't look nice when a VTOL is moving sideways and backwards, but compared to facing the wind from the rear/side in my perspective it's the lesser evil.

Happy for some discussion around this, and how we potentially could parametrize it better, or even change the logic (how about disabling WV completely if the estimated wind speed is below some threshold, and the confidence in the wind estimate is high enough?)

ThomasRigi commented 3 years ago

The problem with the current logic of just disabling the windvane when moving laterally is that you never align in the first place. In all simulated missions the vtol was never facing the wind, neither the relative (including airspeed from moving) nor the external only. Instead it just rolls and pitches, which is dangerous as it's not aligned.

In my opinion we can ignore mpc_yaw_mode at all times (as I agree that facing the wind is more important), but weather vane should remain enabled, also to readjust to changing wind directions.

As to whether it should only take into account only the external wind or the relative including the airspeed induced by the drone moving, I think the relative is more important. This is the one that instantaneously affects the drone. The only small problem I see with this approach is that when changing direction you are not aligned in the beginning. But to me this is a minor issue compared to the case where the drone advances with say 7m/s with 3m/s wind from the side and vaning only to the 3m/s side wind.

A side effect of taking the relative wind is that the current WV logic works. If you really want to consider only the external wind you need to adapt the logics.

On Mon, 7 Sep 2020, 10:00 Silvan Fuhrer, notifications@github.com wrote:

Yes, since #13782 https://github.com/PX4/Firmware/pull/13782 WV is disabled when moving. The idea of WV how I understand it (yes, the docs would need some updating) is that the nose of the VTOL is always pointed into the (external) wind, as that is the dangerous factor for VTOLS, rather than the airspeed it picks up when moving lateral (wind can be at 15 m/s, normally VTOLs move laterally at 5 m/s or so). So it doesn't look nice when a VTOL is moving sideways and backwards, but compared to facing the wind from the rear/side in my perspective it's the lesser evil.

Happy for some discussion around this, and how we potentially could parametrize it better, or even change the logic (how about disabling WV completely if the estimated wind speed is below some threshold, and the confidence in the wind estimate is high enough?)

— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/PX4/Firmware/issues/15673#issuecomment-688125034, or unsubscribe https://github.com/notifications/unsubscribe-auth/ALPZHBLOZGWLXCIC6XWD7BLSESHJNANCNFSM4QS7IIZA .

stale[bot] commented 3 years ago

This issue has been automatically marked as stale because it has not had recent activity. Thank you for your contributions.