AP_ExpandingArray.cpp 2.6 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include "AP_ExpandingArray.h"
  14. #include <AP_HAL/AP_HAL.h>
  15. extern const AP_HAL::HAL& hal;
  16. AP_ExpandingArrayGeneric::~AP_ExpandingArrayGeneric(void)
  17. {
  18. // free chunks
  19. for (uint16_t i=0; i<chunk_count; i++) {
  20. free(chunk_ptrs[i]);
  21. }
  22. // free chunks_ptrs array
  23. free(chunk_ptrs);
  24. }
  25. // expand the array by specified number of chunks, returns true on success
  26. bool AP_ExpandingArrayGeneric::expand(uint16_t num_chunks)
  27. {
  28. // expand chunk_ptrs array if necessary
  29. if (chunk_count + num_chunks >= chunk_count_max) {
  30. uint16_t chunk_ptr_size = chunk_count + num_chunks + chunk_ptr_increment;
  31. if (hal.util->available_memory() < 100U + (chunk_ptr_size * sizeof(chunk_ptr_t))) {
  32. // fail if reallocating would leave less than 100 bytes of memory free
  33. return false;
  34. }
  35. chunk_ptr_t *chunk_ptrs_new = (chunk_ptr_t*)realloc(chunk_ptrs, chunk_ptr_size * sizeof(chunk_ptr_t));
  36. if (chunk_ptrs_new == nullptr) {
  37. return false;
  38. }
  39. // use new pointers array
  40. chunk_ptrs = chunk_ptrs_new;
  41. chunk_count_max = chunk_ptr_size;
  42. }
  43. // allocate new chunks
  44. for (uint16_t i = 0; i < num_chunks; i++) {
  45. if (hal.util->available_memory() < 100U + (chunk_size * elem_size)) {
  46. // fail if reallocating would leave less than 100 bytes of memory free
  47. return false;
  48. }
  49. uint8_t *new_chunk = (uint8_t *)calloc(chunk_size, elem_size);
  50. if (new_chunk == nullptr) {
  51. // failed to allocate new chunk
  52. return false;
  53. }
  54. chunk_ptrs[chunk_count] = new_chunk;
  55. chunk_count++;
  56. }
  57. return true;
  58. }
  59. // expand to hold at least num_items
  60. bool AP_ExpandingArrayGeneric::expand_to_hold(uint16_t num_items)
  61. {
  62. // check if already big enough
  63. if (num_items <= max_items()) {
  64. return true;
  65. }
  66. uint16_t chunks_required = ((num_items - max_items()) / chunk_size) + 1;
  67. return expand(chunks_required);
  68. }