mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AC_AttControl: allow enabling/disabling feedforward and accel limiting
This commit is contained in:
parent
a2f54fdf2c
commit
46f25c52a4
@ -640,6 +640,24 @@ float AC_AttitudeControl::rate_bf_to_motor_yaw(float rate_target_cds)
|
|||||||
// To-Do: allow logging of PIDs?
|
// To-Do: allow logging of PIDs?
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// accel_limiting - enable or disable accel limiting
|
||||||
|
void AC_AttitudeControl::accel_limiting(bool enable_limits)
|
||||||
|
{
|
||||||
|
if (enable_limits) {
|
||||||
|
// if enabling limits, reload from eeprom or set to defaults
|
||||||
|
if (_accel_rp_max == 0.0f) {
|
||||||
|
_accel_rp_max.load();
|
||||||
|
}
|
||||||
|
if (_accel_y_max == 0.0f) {
|
||||||
|
_accel_y_max.load();
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
// if disabling limits, set to zero
|
||||||
|
_accel_rp_max = 0.0f;
|
||||||
|
_accel_y_max = 0.0f;
|
||||||
|
}
|
||||||
|
hal.console->printf_P(PSTR("AccLim:%d"),(int)enable_limits);
|
||||||
|
}
|
||||||
|
|
||||||
//
|
//
|
||||||
// throttle functions
|
// throttle functions
|
||||||
|
@ -134,6 +134,12 @@ public:
|
|||||||
void rate_bf_pitch_target(float rate_cds) { _rate_bf_target.y = rate_cds; }
|
void rate_bf_pitch_target(float rate_cds) { _rate_bf_target.y = rate_cds; }
|
||||||
void rate_bf_yaw_target(float rate_cds) { _rate_bf_target.z = rate_cds; }
|
void rate_bf_yaw_target(float rate_cds) { _rate_bf_target.z = rate_cds; }
|
||||||
|
|
||||||
|
// enable_bf_feedforward - enable or disable body-frame feed forward
|
||||||
|
void bf_feedforward(bool enable_or_disable) { _rate_bf_ff_enabled = enable_or_disable; }
|
||||||
|
|
||||||
|
// enable_bf_feedforward - enable or disable body-frame feed forward
|
||||||
|
void accel_limiting(bool enable_or_disable);
|
||||||
|
|
||||||
//
|
//
|
||||||
// throttle functions
|
// throttle functions
|
||||||
//
|
//
|
||||||
|
Loading…
Reference in New Issue
Block a user