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

[Multirotor] add yaw rate low pass filter #24173

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open

Conversation

bresch
Copy link
Member

@bresch bresch commented Jan 6, 2025

replaces #21434

Solved Problem

On multirotors, yaw torque is produced by two effects:

  1. Change in angular momentum of the rotors when RPM varies (inertia wheel effect): this is a high-frequency effect and is null when RPM is constant
  2. Rotor drag: this is a low-frequency effect and is the main component we wish to use for yaw rate control

Due to 1., the yaw rate loop gain is often limited as this high-frequency torque amplifies vibrations through the feedback loop.

Solution

Reduce the inertia wheel effect by low-passing the yaw torque setpoint. This allows higher yaw rate gains and reduces vibrations.

A default value of 2Hz should be good for most drones and should reduce vibrations without affecting the yaw rate stability.

Changelog Entry

For release notes:

Feature: [Multirotor] add yaw rate low pass filter
New parameter: MC_YAWRATE_FC
Documentation: TBD, should be added in MC tuning guide

Test coverage

Tested on a QAV250 with Pixhawk4 mini
Without filtering (MC_YAWRATE_FC = 0):
https://logs.px4.io/plot_app?log=5b8bf4af-3107-4257-8b89-99579cfabd45
no_yaw_lpf

With default filtering (MC_YAWRATE_FC = 2Hz):
https://logs.px4.io/plot_app?log=e13d88d0-8d9a-405e-ab09-a284c88c9af0
yaw_lpf

The control signal is smoother and no control degradation is visible.

co-authored-by: danielmellinger <[email protected]>
co-authored-by: Eric Katzfey <[email protected]>
@bresch bresch requested a review from MaEtUgR January 6, 2025 10:46
@bresch bresch self-assigned this Jan 6, 2025
Copy link

github-actions bot commented Jan 6, 2025

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 352 byte (0.02 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.0%    +352  +0.0%    +352    .text
  +2.8%    +164  +2.8%    +164    ../../src/modules/mc_rate_control/MulticopterRateControl.cpp
  +0.0%     +84  +0.0%     +84    ROMFS/nsh_romfsimg.c
  +0.3%     +64  +0.3%     +64    ../../src/lib/parameters/parameters.cpp
  +0.0%     +40  +0.0%     +40    [section .text]
+0.0%     +86  [ = ]       0    .debug_abbrev
   +11%     +56  [ = ]       0    ../../src/lib/version/version.c
  +0.8%     +30  [ = ]       0    ../../src/modules/mc_rate_control/MulticopterRateControl.cpp
-0.0%      -8  [ = ]       0    .debug_aranges
  -5.0%      -8  [ = ]       0    ../../src/lib/version/version.c
+0.0%      +8  [ = ]       0    .debug_frame
+0.0% +12.2Ki  [ = ]       0    .debug_info
  +0.0%      +8  [ = ]       0    ../../src/drivers/batt_smbus/batt_smbus.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/cdcacm_autostart/cdcacm_autostart.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/dshot/DShot.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/heater/heater.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/lights/rgbled/rgbled.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/lights/rgbled_is31fl3195/rgbled_is31fl3195.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/lights/rgbled_lp5562/rgbled_lp5562.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/lights/rgbled_ncp5623c/rgbled_ncp5623c.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/osd/msp_osd/msp_osd.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/ina226/ina226.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/ina226/ina226_main.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/ina228/ina228.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/ina228/ina228_main.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/ina238/ina238.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/ina238/ina238_main.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/pm_selector_auterion/PowerMonitorSelectorAuterion.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/pwm_out/PWMOut.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/px4io/px4io.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/rc/crsf_rc/CrsfRc.cpp
 -99.9% +12.0Ki  [ = ]       0    [175 Others]
+0.0%    +530  [ = ]       0    .debug_line
  +0.1%     +29  [ = ]       0    ../../src/lib/parameters/parameters.cpp
  +0.0%      +2  [ = ]       0    ../../src/lib/system_identification/system_identification.cpp
  +0.0%      +3  [ = ]       0    ../../src/lib/tecs/TECS.cpp
  -1.3%     -25  [ = ]       0    ../../src/lib/version/version.c
  +0.1%      +2  [ = ]       0    ../../src/modules/ekf2/EKF/bias_estimator/bias_estimator.cpp
  +0.0%      +2  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp
  +0.0%      +1  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Transition/FlightTaskTransition.cpp
  +0.0%      +2  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.cpp
  +0.1%      +2  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Utility/StickYaw.cpp
  +0.0%      +2  [ = ]       0    ../../src/modules/manual_control/ManualControl.cpp
  -0.0%      -9  [ = ]       0    ../../src/modules/mc_pos_control/MulticopterPositionControl.cpp
  +2.9%    +523  [ = ]       0    ../../src/modules/mc_rate_control/MulticopterRateControl.cpp
  -0.0%      -1  [ = ]       0    ../../src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.cpp
  -0.0%      -1  [ = ]       0    src/modules/ekf2/modules__ekf2_unity.cpp
  -0.2%      -2  [ = ]       0    task/task_cancelpt.c
+0.0%    +881  [ = ]       0    .debug_loc
  +0.2%     +15  [ = ]       0    ../../src/drivers/rc/crsf_rc/CrsfRc.cpp
  -0.0%      -2  [ = ]       0    ../../src/drivers/uavcan/uavcan_main.cpp
  +0.0%     +28  [ = ]       0    ../../src/drivers/uavcan/uavcan_servers.cpp
  -0.1%     -15  [ = ]       0    ../../src/lib/avoidance/ObstacleAvoidance.cpp
  -0.1%     -50  [ = ]       0    ../../src/lib/parameters/parameters.cpp
  +0.2%     +15  [ = ]       0    ../../src/lib/rtl/rtl_time_estimator.cpp
  +0.0%      +3  [ = ]       0    ../../src/lib/system_identification/system_identification.cpp
  -0.1%     -15  [ = ]       0    ../../src/modules/commander/failure_detector/FailureDetector.cpp
  +0.6%     +48  [ = ]       0    ../../src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectivenessTiltrotorVTOL.cpp
  +0.3%     +15  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.cpp
  -0.0%     -13  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp
  -0.1%     -15  [ = ]       0    ../../src/modules/fw_att_control/FixedwingAttitudeControl.cpp
  -0.3%     -15  [ = ]       0    ../../src/modules/land_detector/FixedwingLandDetector.cpp
  -0.1%     -15  [ = ]       0    ../../src/modules/mag_bias_estimator/MagBiasEstimator.cpp
  +3.3%    +965  [ = ]       0    ../../src/modules/mc_rate_control/MulticopterRateControl.cpp
  -0.1%     -15  [ = ]       0    ../../src/modules/navigator/mission_base.cpp
  -0.4%     -15  [ = ]       0    ../../src/modules/navigator/rtl_mission_fast_reverse.cpp
  -0.0%      -3  [ = ]       0    ../../src/modules/sensors/vehicle_imu/VehicleIMU.cpp
  +0.1%     +15  [ = ]       0    ../../src/modules/sensors/vehicle_magnetometer/VehicleMagnetometer.cpp
  +0.1%     +15  [ = ]       0    ../../src/modules/sensors/vehicle_optical_flow/VehicleOpticalFlow.cpp
 -100.0%     -65  [ = ]       0    [3 Others]
+0.0%    +343  [ = ]       0    .debug_ranges
  -2.6%      -8  [ = ]       0    ../../src/lib/version/version.c
  +3.5%    +352  [ = ]       0    ../../src/modules/mc_rate_control/MulticopterRateControl.cpp
  -1.5%      -1  [ = ]       0    task/task_cancelpt.c
+0.0% +1.16Ki  [ = ]       0    .debug_str
  +0.1%     +17  [ = ]       0    ../../src/drivers/batt_smbus/batt_smbus.cpp
  +0.1%     +37  [ = ]       0    ../../src/modules/airspeed_selector/airspeed_selector_main.cpp
  +6.0%    +966  [ = ]       0    ../../src/modules/mc_rate_control/MulticopterRateControl.cpp
  +0.1%    +172  [ = ]       0    src/modules/ekf2/modules__ekf2_unity.cpp
-2.3%    -352  [ = ]       0    [Unmapped]
+0.0% +15.1Ki  +0.0%    +352    TOTAL

px4_fmu-v6x [Total VM Diff: 208 byte (0.01 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.0%    +208  +0.0%    +208    .text
  +2.8%    +164  +2.8%    +164    ../../src/modules/mc_rate_control/MulticopterRateControl.cpp
  +0.0%     +77  +0.0%     +77    ROMFS/nsh_romfsimg.c
  +0.0%     +44  +0.0%     +44    [section .text]
  +0.2%      +3  +0.2%      +3    ../../src/systemcmds/ver/ver.cpp
  -0.3%     -80  -0.3%     -80    ../../src/lib/parameters/parameters.cpp
+0.0%     +86  [ = ]       0    .debug_abbrev
   +11%     +56  [ = ]       0    ../../src/lib/version/version.c
  +0.8%     +30  [ = ]       0    ../../src/modules/mc_rate_control/MulticopterRateControl.cpp
-0.0%      -8  [ = ]       0    .debug_aranges
  -5.0%      -8  [ = ]       0    ../../src/lib/version/version.c
-0.0%      -4  [ = ]       0    .debug_frame
+0.0% +12.1Ki  [ = ]       0    .debug_info
  +0.0%      +8  [ = ]       0    ../../src/drivers/cdcacm_autostart/cdcacm_autostart.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/dshot/DShot.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/heater/heater.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/lights/rgbled/rgbled.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/lights/rgbled_is31fl3195/rgbled_is31fl3195.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/lights/rgbled_lp5562/rgbled_lp5562.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/lights/rgbled_ncp5623c/rgbled_ncp5623c.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/osd/msp_osd/msp_osd.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/ina226/ina226.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/ina226/ina226_main.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/ina228/ina228.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/ina228/ina228_main.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/ina238/ina238.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/ina238/ina238_main.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/power_monitor/pm_selector_auterion/PowerMonitorSelectorAuterion.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/pwm_out/PWMOut.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/px4io/px4io.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/rc_input/RCInput.cpp
  +0.0%      +8  [ = ]       0    ../../src/drivers/uavcan/actuators/esc.cpp
 -99.9% +11.9Ki  [ = ]       0    [164 Others]
+0.0%    +430  [ = ]       0    .debug_line
  -0.3%     -66  [ = ]       0    ../../src/lib/parameters/parameters.cpp
  +0.0%      +2  [ = ]       0    ../../src/lib/system_identification/system_identification.cpp
  +0.0%      +3  [ = ]       0    ../../src/lib/tecs/TECS.cpp
  -1.3%     -25  [ = ]       0    ../../src/lib/version/version.c
  +0.1%      +2  [ = ]       0    ../../src/modules/ekf2/EKF/bias_estimator/bias_estimator.cpp
  +0.0%      +2  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Auto/FlightTaskAuto.cpp
  +0.0%      +1  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Transition/FlightTaskTransition.cpp
  +0.0%      +2  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Utility/StickAccelerationXY.cpp
  +0.1%      +2  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Utility/StickYaw.cpp
  +0.0%      +2  [ = ]       0    ../../src/modules/manual_control/ManualControl.cpp
  -0.0%      -9  [ = ]       0    ../../src/modules/mc_pos_control/MulticopterPositionControl.cpp
  +2.9%    +523  [ = ]       0    ../../src/modules/mc_rate_control/MulticopterRateControl.cpp
  -0.0%      -1  [ = ]       0    ../../src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.cpp
  -0.0%      -1  [ = ]       0    src/modules/ekf2/modules__ekf2_unity.cpp
  -0.6%      -7  [ = ]       0    task/task_cancelpt.c
+0.0% +1.02Ki  [ = ]       0    .debug_loc
  -0.1%     -15  [ = ]       0    ../../src/drivers/px4io/px4io.cpp
  -0.1%     -15  [ = ]       0    ../../src/drivers/uavcan/remoteid.cpp
  -0.0%     -13  [ = ]       0    ../../src/drivers/uavcan/uavcan_servers.cpp
  +0.1%     +15  [ = ]       0    ../../src/lib/avoidance/ObstacleAvoidance.cpp
  +0.1%     +15  [ = ]       0    ../../src/lib/collision_prevention/CollisionPrevention.cpp
  +0.1%     +16  [ = ]       0    ../../src/lib/mixer_module/mixer_module.cpp
  +0.2%     +52  [ = ]       0    ../../src/lib/parameters/parameters.cpp
  -0.2%     -15  [ = ]       0    ../../src/lib/rtl/rtl_time_estimator.cpp
  +0.0%      +3  [ = ]       0    ../../src/lib/system_identification/system_identification.cpp
  +0.0%      +1  [ = ]       0    ../../src/modules/commander/HealthAndArmingChecks/checks/externalChecks.cpp
  -0.1%     -15  [ = ]       0    ../../src/modules/commander/failure_detector/FailureDetector.cpp
  -0.3%     -15  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/FlightTask/FlightTask.cpp
  -0.2%     -15  [ = ]       0    ../../src/modules/flight_mode_manager/tasks/Transition/FlightTaskTransition.cpp
  +0.1%     +15  [ = ]       0    ../../src/modules/gyro_calibration/GyroCalibration.cpp
  +0.1%     +15  [ = ]       0    ../../src/modules/mag_bias_estimator/MagBiasEstimator.cpp
  +3.3%    +965  [ = ]       0    ../../src/modules/mc_rate_control/MulticopterRateControl.cpp
  -0.1%     -15  [ = ]       0    ../../src/modules/navigator/mission_base.cpp
  +0.1%     +15  [ = ]       0    ../../src/modules/navigator/rtl.cpp
  +0.1%     +15  [ = ]       0    ../../src/modules/sensors/sensors.cpp
  -0.1%     -29  [ = ]       0    ../../src/modules/sensors/vehicle_angular_velocity/VehicleAngularVelocity.cpp
 -100.0%     +65  [ = ]       0    [8 Others]
+0.0%    +287  [ = ]       0    .debug_ranges
  -0.4%     -56  [ = ]       0    ../../src/lib/parameters/parameters.cpp
  -2.6%      -8  [ = ]       0    ../../src/lib/version/version.c
  +3.5%    +352  [ = ]       0    ../../src/modules/mc_rate_control/MulticopterRateControl.cpp
  -1.5%      -1  [ = ]       0    task/task_cancelpt.c
+0.0% +1.16Ki  [ = ]       0    .debug_str
  +0.1%     +17  [ = ]       0    ../../src/drivers/cdcacm_autostart/cdcacm_autostart.cpp
  +0.1%     +37  [ = ]       0    ../../src/modules/airspeed_selector/airspeed_selector_main.cpp
  +5.9%    +954  [ = ]       0    ../../src/modules/mc_rate_control/MulticopterRateControl.cpp
  +0.0%     +12  [ = ]       0    ../../src/modules/navigator/navigator_main.cpp
  +0.1%    +172  [ = ]       0    src/modules/ekf2/modules__ekf2_unity.cpp
-0.3%    -208  [ = ]       0    [Unmapped]
+0.0% +15.1Ki  +0.0%    +208    TOTAL

Updated: 2025-01-09T16:32:29

MaEtUgR
MaEtUgR previously approved these changes Jan 8, 2025
Copy link
Member

@MaEtUgR MaEtUgR left a comment

Choose a reason for hiding this comment

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

I thought about the much quicker and opposite sign yaw torque from inertia change of the rotor before but wasn't sure how to compensate it since it depends on the model and could lead to an additional undesired tuning configuration space. It might be possible to find adequate defaults for such a compensation.

But since that's not guaranteed and extensive testing is currently not on the plan I like your solution to attenuate the effect limiting the yaw dynamics. Given the limited yaw authority of a typical planar multirotor I don't see any limitation arising with this. The racer you tested with has small rather high drag propellers and obviously already benefits so I'd expect it to be even better on large low drag propellers.

@@ -89,6 +89,16 @@ class AlphaFilter
return true;
}

void setCutoffFreq(float cutoff_freq)
Copy link
Member

Choose a reason for hiding this comment

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

This function could potentially be misleading in the case you call setCutoffFreq(float cutoff_freq) which sets _time_constant but then use update(const T &sample) for the update which assumes setParameters(dt, _time_constant) was already called. I don't have a great idea how to make it clear but see the potential for people to run into this 😬

Copy link
Member Author

Choose a reason for hiding this comment

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

Yes, I was wondering about this too. Should we instead have two distinct classes? One where dt needs to be set during the update call and the other one that uses the setParameters to update the alpha.

Copy link
Member

Choose a reason for hiding this comment

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

Seems overkill no? Would it be a performance hit to just always use the "One where dt needs to be set during the update" and in the cases it's static just pass a constant? Seems way easier compared to the multiple options for basically the same thing.

Copy link
Member

Choose a reason for hiding this comment

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

It does seem like overkill, but having separate classes could make each individually a bit easier to use, harder to misuse. Having to know which update to call when used a certain way is a leaky abstraction.

@DronecodeBot
Copy link

This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/px4-sync-q-a-jan-08-2025/43156/1

* @decimal 3
* @group Multicopter Rate Control
*/
PARAM_DEFINE_FLOAT(MC_YAWRATE_FC, 2.f);
Copy link
Member

Choose a reason for hiding this comment

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

I'm not sure if I have a better suggestion, but does this naming make sense?

Something more along the lines of yaw torque filter cutoff or in someway distinguish that it's specifically the output?

Copy link
Member Author

Choose a reason for hiding this comment

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

The suggested name from #21434 was MC_YAW_CUTOFF. I like the _CUTOFF prefix but MC_YAW is too inaccurate. Also, it would be problematic if we want to add a yaw filter (not yawrate like now).
What about MC_YAW_TQ_CUTOFF or MC_Y_TRQ_CUTOFF ?

Copy link
Member Author

Choose a reason for hiding this comment

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

Changed it to MC_YAW_TQ_CUTOFF in 28bc950

@bresch
Copy link
Member Author

bresch commented Jan 10, 2025

Tested on an X500, looks good as well
Screenshot from 2025-01-10 12-09-42

@bresch bresch requested review from dagar and MaEtUgR January 10, 2025 15:37
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
Status: No status
Development

Successfully merging this pull request may close these issues.

4 participants