mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Motors: remove MOT_THR_FILT parameter and add interface to configure filter
This commit is contained in:
parent
518e798f53
commit
e80776f1f5
@ -93,14 +93,6 @@ const AP_Param::GroupInfo AP_Motors::var_info[] PROGMEM = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("CURR_MAX", 12, AP_Motors, _batt_current_max, AP_MOTORS_CURR_MAX_DEFAULT),
|
||||
|
||||
// @Param: THR_FILT
|
||||
// @DisplayName: Throttle output filter
|
||||
// @Description: Frequency cutoff (in hz) of throttle output filter
|
||||
// @Range: 2 5
|
||||
// @Units: Hz
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("THR_FILT", 13, AP_Motors, _throttle_filt_hz, 0.0f),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
@ -138,7 +130,8 @@ AP_Motors::AP_Motors(RC_Channel& rc_roll, RC_Channel& rc_pitch, RC_Channel& rc_t
|
||||
_batt_voltage_filt.set_cutoff_frequency(1.0f/_loop_rate,AP_MOTORS_BATT_VOLT_FILT_HZ);
|
||||
_batt_voltage_filt.reset(1.0f);
|
||||
|
||||
_throttle_filter.set_cutoff_frequency(1.0f/_loop_rate,_throttle_filt_hz);
|
||||
// setup throttle filtering
|
||||
_throttle_filter.set_cutoff_frequency(1.0f/_loop_rate,0.0f);
|
||||
_throttle_filter.reset(0.0f);
|
||||
};
|
||||
|
||||
@ -220,10 +213,6 @@ void AP_Motors::slow_start(bool true_false)
|
||||
// update the throttle input filter
|
||||
void AP_Motors::update_throttle_filter()
|
||||
{
|
||||
if (_throttle_filter.get_cutoff_frequency() != _throttle_filt_hz) {
|
||||
_throttle_filter.set_cutoff_frequency(1.0f/_loop_rate,_throttle_filt_hz);
|
||||
}
|
||||
|
||||
if (armed()) {
|
||||
_throttle_filter.apply(_throttle_in);
|
||||
} else {
|
||||
|
@ -130,6 +130,8 @@ public:
|
||||
int16_t get_yaw() const { return _rc_yaw.servo_out; }
|
||||
int16_t get_throttle_out() const { return _rc_throttle.servo_out; }
|
||||
|
||||
void set_throttle_filter_cutoff(float filt_hz) { _throttle_filter.set_cutoff_frequency(1.0f/_loop_rate,filt_hz); }
|
||||
|
||||
// output - sends commands to the motors
|
||||
void output();
|
||||
|
||||
@ -250,7 +252,6 @@ protected:
|
||||
AP_Float _batt_voltage_max; // maximum voltage used to scale lift
|
||||
AP_Float _batt_voltage_min; // minimum voltage used to scale lift
|
||||
AP_Float _batt_current_max; // current over which maximum throttle is limited
|
||||
AP_Float _throttle_filt_hz; // throttle output filter time constant in hz
|
||||
|
||||
// internal variables
|
||||
RC_Channel& _rc_roll; // roll input in from users is held in servo_out
|
||||
|
Loading…
Reference in New Issue
Block a user