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
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 10 additions & 0 deletions src/lib/mathlib/math/filter/AlphaFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.

{
if (cutoff_freq > FLT_EPSILON) {
_time_constant = 1.f / (M_TWOPI_F * cutoff_freq);

} else {
_time_constant = 0.f;
}
}

/**
* Set filter parameter alpha directly without time abstraction
*
Expand Down
7 changes: 6 additions & 1 deletion src/modules/mc_rate_control/MulticopterRateControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,8 @@ MulticopterRateControl::parameters_updated()
// manual rate control acro mode rate limits
_acro_rate_max = Vector3f(radians(_param_mc_acro_r_max.get()), radians(_param_mc_acro_p_max.get()),
radians(_param_mc_acro_y_max.get()));

_output_lpf_yaw.setCutoffFreq(_param_mc_yawrate_fc.get());
}

void
Expand Down Expand Up @@ -214,9 +216,12 @@ MulticopterRateControl::Run()
}

// run rate controller
const Vector3f torque_setpoint =
Vector3f torque_setpoint =
_rate_control.update(rates, _rates_setpoint, angular_accel, dt, _maybe_landed || _landed);

// apply low-pass filtering on yaw axis to reduce high frequency torque caused by rotor acceleration
torque_setpoint(2) = _output_lpf_yaw.update(torque_setpoint(2), dt);

// publish rate controller status
rate_ctrl_status_s rate_ctrl_status{};
_rate_control.getRateControlStatus(rate_ctrl_status);
Expand Down
4 changes: 4 additions & 0 deletions src/modules/mc_rate_control/MulticopterRateControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#pragma once

#include <lib/rate_control/rate_control.hpp>
#include <lib/mathlib/math/filter/AlphaFilter.hpp>
#include <lib/matrix/matrix/math.hpp>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/defines.h>
Expand Down Expand Up @@ -129,6 +130,8 @@ class MulticopterRateControl : public ModuleBase<MulticopterRateControl>, public
float _energy_integration_time{0.0f};
float _control_energy[4] {};

AlphaFilter<float> _output_lpf_yaw;

DEFINE_PARAMETERS(
(ParamFloat<px4::params::MC_ROLLRATE_P>) _param_mc_rollrate_p,
(ParamFloat<px4::params::MC_ROLLRATE_I>) _param_mc_rollrate_i,
Expand All @@ -150,6 +153,7 @@ class MulticopterRateControl : public ModuleBase<MulticopterRateControl>, public
(ParamFloat<px4::params::MC_YAWRATE_D>) _param_mc_yawrate_d,
(ParamFloat<px4::params::MC_YAWRATE_FF>) _param_mc_yawrate_ff,
(ParamFloat<px4::params::MC_YAWRATE_K>) _param_mc_yawrate_k,
(ParamFloat<px4::params::MC_YAWRATE_FC>) _param_mc_yawrate_fc,

(ParamFloat<px4::params::MC_ACRO_R_MAX>) _param_mc_acro_r_max,
(ParamFloat<px4::params::MC_ACRO_P_MAX>) _param_mc_acro_p_max,
Expand Down
14 changes: 14 additions & 0 deletions src/modules/mc_rate_control/mc_rate_control_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -292,3 +292,17 @@ PARAM_DEFINE_FLOAT(MC_YAWRATE_K, 1.0f);
* @group Multicopter Rate Control
*/
PARAM_DEFINE_INT32(MC_BAT_SCALE_EN, 0);

/**
* First order low pass filter cutoff frequency for yaw rate control
*
* Reduces vibrations by lowering high frequency torque caused by rotor acceleration.
* 0 disables the filter
*
* @min 0
* @max 10
* @unit Hz
* @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

Loading