mirror of https://github.com/ArduPilot/ardupilot
AC_PID: use NEW_NOTHROW for new(std::nothrow)
This commit is contained in:
parent
c95624a040
commit
4c41805a3d
|
@ -162,7 +162,7 @@ void AC_PID::set_notch_sample_rate(float sample_rate)
|
||||||
|
|
||||||
if (_notch_T_filter != 0) {
|
if (_notch_T_filter != 0) {
|
||||||
if (_target_notch == nullptr) {
|
if (_target_notch == nullptr) {
|
||||||
_target_notch = new NotchFilterFloat();
|
_target_notch = NEW_NOTHROW NotchFilterFloat();
|
||||||
}
|
}
|
||||||
AP_Filter* filter = AP::filters().get_filter(_notch_T_filter);
|
AP_Filter* filter = AP::filters().get_filter(_notch_T_filter);
|
||||||
if (filter != nullptr && !filter->setup_notch_filter(*_target_notch, sample_rate)) {
|
if (filter != nullptr && !filter->setup_notch_filter(*_target_notch, sample_rate)) {
|
||||||
|
@ -174,7 +174,7 @@ void AC_PID::set_notch_sample_rate(float sample_rate)
|
||||||
|
|
||||||
if (_notch_E_filter != 0) {
|
if (_notch_E_filter != 0) {
|
||||||
if (_error_notch == nullptr) {
|
if (_error_notch == nullptr) {
|
||||||
_error_notch = new NotchFilterFloat();
|
_error_notch = NEW_NOTHROW NotchFilterFloat();
|
||||||
}
|
}
|
||||||
AP_Filter* filter = AP::filters().get_filter(_notch_E_filter);
|
AP_Filter* filter = AP::filters().get_filter(_notch_E_filter);
|
||||||
if (filter != nullptr && !filter->setup_notch_filter(*_error_notch, sample_rate)) {
|
if (filter != nullptr && !filter->setup_notch_filter(*_error_notch, sample_rate)) {
|
||||||
|
|
|
@ -70,8 +70,8 @@ void setup()
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
// setup (unfortunately must be done here as we cannot create a global AC_PID object)
|
// setup (unfortunately must be done here as we cannot create a global AC_PID object)
|
||||||
AC_PID *pid = new AC_PID(TEST_P, TEST_I, TEST_D, 0.0f, TEST_IMAX * 100.0f, 0.0f, 0.0f, TEST_FILTER);
|
AC_PID *pid = NEW_NOTHROW AC_PID(TEST_P, TEST_I, TEST_D, 0.0f, TEST_IMAX * 100.0f, 0.0f, 0.0f, TEST_FILTER);
|
||||||
// AC_HELI_PID *heli_pid= new AC_HELI_PID(TEST_P, TEST_I, TEST_D, TEST_INITIAL_FF, TEST_IMAX * 100, 0.0f, 0.0f, TEST_FILTER);
|
// AC_HELI_PID *heli_pid= NEW_NOTHROW AC_HELI_PID(TEST_P, TEST_I, TEST_D, TEST_INITIAL_FF, TEST_IMAX * 100, 0.0f, 0.0f, TEST_FILTER);
|
||||||
|
|
||||||
// display PID gains
|
// display PID gains
|
||||||
hal.console->printf("P %f I %f D %f imax %f\n", (double)pid->kP(), (double)pid->kI(), (double)pid->kD(), (double)pid->imax());
|
hal.console->printf("P %f I %f D %f imax %f\n", (double)pid->kP(), (double)pid->kI(), (double)pid->kD(), (double)pid->imax());
|
||||||
|
|
Loading…
Reference in New Issue