mirror of https://github.com/ArduPilot/ardupilot
AP_ADC_ADS1115: Remove resource leak.
Constructor allocate '_samples' but there was no destructor to deallocate it. Also, initializes '_gain' to silence CID 9144 although '_gain' wasn't being used uninitialized because of ::init(). CID 91424
This commit is contained in:
parent
36bdd7f1f1
commit
fe48901db0
|
@ -110,11 +110,17 @@ static const uint16_t mux_table[ADS1115_CHANNELS_COUNT] = {
|
|||
|
||||
AP_ADC_ADS1115::AP_ADC_ADS1115()
|
||||
: _dev(hal.i2c_mgr->get_device(ADS1115_I2C_BUS, ADS1115_I2C_ADDR))
|
||||
, _gain(ADS1115_PGA_4P096)
|
||||
, _channel_to_read(0)
|
||||
{
|
||||
_samples = new adc_report_s[_channels_number];
|
||||
}
|
||||
|
||||
AP_ADC_ADS1115::~AP_ADC_ADS1115()
|
||||
{
|
||||
delete[] _samples;
|
||||
}
|
||||
|
||||
bool AP_ADC_ADS1115::init()
|
||||
{
|
||||
hal.scheduler->suspend_timer_procs();
|
||||
|
|
|
@ -17,6 +17,7 @@ class AP_ADC_ADS1115
|
|||
{
|
||||
public:
|
||||
AP_ADC_ADS1115();
|
||||
~AP_ADC_ADS1115();
|
||||
|
||||
bool init();
|
||||
size_t read(adc_report_s *report, size_t length) const;
|
||||
|
|
Loading…
Reference in New Issue