mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_TempCalibration: Remove pointer check before delete
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
12cd138030
commit
61bcbfea14
@ -93,9 +93,7 @@ void AP_TempCalibration::setup_learning(void)
|
|||||||
learn_temp_step = 0.25;
|
learn_temp_step = 0.25;
|
||||||
learn_count = 200;
|
learn_count = 200;
|
||||||
learn_i = 0;
|
learn_i = 0;
|
||||||
if (learn_values != nullptr) {
|
delete [] learn_values;
|
||||||
delete [] learn_values;
|
|
||||||
}
|
|
||||||
learn_values = new float[learn_count];
|
learn_values = new float[learn_count];
|
||||||
if (learn_values == nullptr) {
|
if (learn_values == nullptr) {
|
||||||
return;
|
return;
|
||||||
|
Loading…
Reference in New Issue
Block a user