zmaxheap.c
Go to the documentation of this file.
1 /* Copyright (C) 2013-2016, The Regents of The University of Michigan.
2 All rights reserved.
3 This software was developed in the APRIL Robotics Lab under the
4 direction of Edwin Olson, ebolson@umich.edu. This software may be
5 available under alternative licensing terms; contact the address above.
6 Redistribution and use in source and binary forms, with or without
7 modification, are permitted provided that the following conditions are met:
8 1. Redistributions of source code must retain the above copyright notice, this
9  list of conditions and the following disclaimer.
10 2. Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
14 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
15 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
16 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR
17 ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
18 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
19 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
20 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
21 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
22 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
23 The views and conclusions contained in the software and documentation are those
24 of the authors and should not be interpreted as representing official policies,
25 either expressed or implied, of the Regents of The University of Michigan.
26 */
27 
28 #include <stdlib.h>
29 #include <stdio.h>
30 #include <string.h>
31 #include <math.h>
32 #include <assert.h>
33 #include <stdint.h>
34 
35 #include "zmaxheap.h"
36 #include "debug_print.h"
37 
38 #ifdef _WIN32
39 static inline long int random(void)
40 {
41  return rand();
42 }
43 #endif
44 
45 // 0
46 // 1 2
47 // 3 4 5 6
48 // 7 8 9 10 11 12 13 14
49 //
50 // Children of node i: 2*i+1, 2*i+2
51 // Parent of node i: (i-1) / 2
52 //
53 // Heap property: a parent is greater than (or equal to) its children.
54 
55 #define MIN_CAPACITY 16
56 
57 struct zmaxheap
58 {
59  size_t el_sz;
60 
61  int size;
62  int alloc;
63 
64  float *values;
65  char *data;
66 
67  void (*swap)(zmaxheap_t *heap, int a, int b);
68 };
69 
70 static inline void swap_default(zmaxheap_t *heap, int a, int b)
71 {
72  float t = heap->values[a];
73  heap->values[a] = heap->values[b];
74  heap->values[b] = t;
75 
76  char *tmp = malloc(sizeof(char)*heap->el_sz);
77  memcpy(tmp, &heap->data[a*heap->el_sz], heap->el_sz);
78  memcpy(&heap->data[a*heap->el_sz], &heap->data[b*heap->el_sz], heap->el_sz);
79  memcpy(&heap->data[b*heap->el_sz], tmp, heap->el_sz);
80  free(tmp);
81 }
82 
83 static inline void swap_pointer(zmaxheap_t *heap, int a, int b)
84 {
85  float t = heap->values[a];
86  heap->values[a] = heap->values[b];
87  heap->values[b] = t;
88 
89  void **pp = (void**) heap->data;
90  void *tmp = pp[a];
91  pp[a] = pp[b];
92  pp[b] = tmp;
93 }
94 
95 
97 {
98  zmaxheap_t *heap = calloc(1, sizeof(zmaxheap_t));
99  heap->el_sz = el_sz;
100 
101  heap->swap = swap_default;
102 
103  if (el_sz == sizeof(void*))
104  heap->swap = swap_pointer;
105 
106  return heap;
107 }
108 
110 {
111  free(heap->values);
112  free(heap->data);
113  memset(heap, 0, sizeof(zmaxheap_t));
114  free(heap);
115 }
116 
118 {
119  return heap->size;
120 }
121 
122 void zmaxheap_ensure_capacity(zmaxheap_t *heap, int capacity)
123 {
124  if (heap->alloc >= capacity)
125  return;
126 
127  int newcap = heap->alloc;
128 
129  while (newcap < capacity) {
130  if (newcap < MIN_CAPACITY) {
131  newcap = MIN_CAPACITY;
132  continue;
133  }
134 
135  newcap *= 2;
136  }
137 
138  heap->values = realloc(heap->values, newcap * sizeof(float));
139  heap->data = realloc(heap->data, newcap * heap->el_sz);
140  heap->alloc = newcap;
141 }
142 
143 void zmaxheap_add(zmaxheap_t *heap, void *p, float v)
144 {
145 
146  assert (isfinite(v) && "zmaxheap_add: Trying to add non-finite number to heap. NaN's prohibited, could allow INF with testing");
147  zmaxheap_ensure_capacity(heap, heap->size + 1);
148 
149  int idx = heap->size;
150 
151  heap->values[idx] = v;
152  memcpy(&heap->data[idx*heap->el_sz], p, heap->el_sz);
153 
154  heap->size++;
155 
156  while (idx > 0) {
157 
158  int parent = (idx - 1) / 2;
159 
160  // we're done!
161  if (heap->values[parent] >= v)
162  break;
163 
164  // else, swap and recurse upwards.
165  heap->swap(heap, idx, parent);
166  idx = parent;
167  }
168 }
169 
170 void zmaxheap_vmap(zmaxheap_t *heap, void (*f)())
171 {
172  assert(heap != NULL);
173  assert(f != NULL);
174  assert(heap->el_sz == sizeof(void*));
175 
176  for (int idx = 0; idx < heap->size; idx++) {
177  void *p = NULL;
178  memcpy(&p, &heap->data[idx*heap->el_sz], heap->el_sz);
179  if (p == NULL) {
180  debug_print("Warning: zmaxheap_vmap item %d is NULL\n", idx);
181  }
182  f(p);
183  }
184 }
185 
186 // Removes the item in the heap at the given index. Returns 1 if the
187 // item existed. 0 Indicates an invalid idx (heap is smaller than
188 // idx). This is mostly intended to be used by zmaxheap_remove_max.
189 int zmaxheap_remove_index(zmaxheap_t *heap, int idx, void *p, float *v)
190 {
191  if (idx >= heap->size)
192  return 0;
193 
194  // copy out the requested element from the heap.
195  if (v != NULL)
196  *v = heap->values[idx];
197  if (p != NULL)
198  memcpy(p, &heap->data[idx*heap->el_sz], heap->el_sz);
199 
200  heap->size--;
201 
202  // If this element is already the last one, then there's nothing
203  // for us to do.
204  if (idx == heap->size)
205  return 1;
206 
207  // copy last element to first element. (which probably upsets
208  // the heap property).
209  heap->values[idx] = heap->values[heap->size];
210  memcpy(&heap->data[idx*heap->el_sz], &heap->data[heap->el_sz * heap->size], heap->el_sz);
211 
212  // now fix the heap. Note, as we descend, we're "pushing down"
213  // the same node the entire time. Thus, while the index of the
214  // parent might change, the parent_score doesn't.
215  int parent = idx;
216  float parent_score = heap->values[idx];
217 
218  // descend, fixing the heap.
219  while (parent < heap->size) {
220 
221  int left = 2*parent + 1;
222  int right = left + 1;
223 
224 // assert(parent_score == heap->values[parent]);
225 
226  float left_score = (left < heap->size) ? heap->values[left] : -INFINITY;
227  float right_score = (right < heap->size) ? heap->values[right] : -INFINITY;
228 
229  // put the biggest of (parent, left, right) as the parent.
230 
231  // already okay?
232  if (parent_score >= left_score && parent_score >= right_score)
233  break;
234 
235  // if we got here, then one of the children is bigger than the parent.
236  if (left_score >= right_score) {
237  assert(left < heap->size);
238  heap->swap(heap, parent, left);
239  parent = left;
240  } else {
241  // right_score can't be less than left_score if right_score is -INFINITY.
242  assert(right < heap->size);
243  heap->swap(heap, parent, right);
244  parent = right;
245  }
246  }
247 
248  return 1;
249 }
250 
251 int zmaxheap_remove_max(zmaxheap_t *heap, void *p, float *v)
252 {
253  return zmaxheap_remove_index(heap, 0, p, v);
254 }
255 
257 {
258  memset(it, 0, sizeof(zmaxheap_iterator_t));
259  it->heap = heap;
260  it->in = 0;
261  it->out = 0;
262 }
263 
264 int zmaxheap_iterator_next(zmaxheap_iterator_t *it, void *p, float *v)
265 {
266  zmaxheap_t *heap = it->heap;
267 
268  if (it->in >= zmaxheap_size(heap))
269  return 0;
270 
271  *v = heap->values[it->in];
272  memcpy(p, &heap->data[it->in*heap->el_sz], heap->el_sz);
273 
274  if (it->in != it->out) {
275  heap->values[it->out] = heap->values[it->in];
276  memcpy(&heap->data[it->out*heap->el_sz], &heap->data[it->in*heap->el_sz], heap->el_sz);
277  }
278 
279  it->in++;
280  it->out++;
281  return 1;
282 }
283 
285 {
286  zmaxheap_t *heap = it->heap;
287 
288  if (it->in >= zmaxheap_size(heap))
289  return 0;
290 
291  *v = heap->values[it->in];
292  *((void**) p) = &heap->data[it->in*heap->el_sz];
293 
294  if (it->in != it->out) {
295  heap->values[it->out] = heap->values[it->in];
296  memcpy(&heap->data[it->out*heap->el_sz], &heap->data[it->in*heap->el_sz], heap->el_sz);
297  }
298 
299  it->in++;
300  it->out++;
301  return 1;
302 }
303 
305 {
306  it->out--;
307 }
308 
309 static void maxheapify(zmaxheap_t *heap, int parent)
310 {
311  int left = 2*parent + 1;
312  int right = 2*parent + 2;
313 
314  int betterchild = parent;
315 
316  if (left < heap->size && heap->values[left] > heap->values[betterchild])
317  betterchild = left;
318  if (right < heap->size && heap->values[right] > heap->values[betterchild])
319  betterchild = right;
320 
321  if (betterchild != parent) {
322  heap->swap(heap, parent, betterchild);
323  return maxheapify(heap, betterchild);
324  }
325 }
326 
327 #if 0 //won't compile if defined but not used
328 // test the heap property
329 static void validate(zmaxheap_t *heap)
330 {
331  for (int parent = 0; parent < heap->size; parent++) {
332  int left = 2*parent + 1;
333  int right = 2*parent + 2;
334 
335  if (left < heap->size) {
336  assert(heap->values[parent] > heap->values[left]);
337  }
338 
339  if (right < heap->size) {
340  assert(heap->values[parent] > heap->values[right]);
341  }
342  }
343 }
344 #endif
346 {
347  // if nothing was removed, no work to do.
348  if (it->in == it->out)
349  return;
350 
351  zmaxheap_t *heap = it->heap;
352 
353  heap->size = it->out;
354 
355  // restore heap property
356  for (int i = heap->size/2 - 1; i >= 0; i--)
357  maxheapify(heap, i);
358 }
359 
361 {
362  int cap = 10000;
363  int sz = 0;
364  int32_t *vals = calloc(sizeof(int32_t), cap);
365 
366  zmaxheap_t *heap = zmaxheap_create(sizeof(int32_t));
367 
368  int maxsz = 0;
369  int zcnt = 0;
370 
371  for (int iter = 0; iter < 5000000; iter++) {
372  assert(sz == heap->size);
373 
374  if ((random() & 1) == 0 && sz < cap) {
375  // add a value
376  int32_t v = (int32_t) (random() / 1000);
377  float fv = v;
378  assert(v == fv);
379 
380  vals[sz] = v;
381  zmaxheap_add(heap, &v, fv);
382  sz++;
383 
384 // printf("add %d %f\n", v, fv);
385  } else {
386  // remove a value
387  int maxv = -1, maxi = -1;
388 
389  for (int i = 0; i < sz; i++) {
390  if (vals[i] > maxv) {
391  maxv = vals[i];
392  maxi = i;
393  }
394  }
395 
396 
397  int32_t outv;
398  float outfv;
399  int res = zmaxheap_remove_max(heap, &outv, &outfv);
400  if (sz == 0) {
401  assert(res == 0);
402  } else {
403 // printf("%d %d %d %f\n", sz, maxv, outv, outfv);
404  assert(outv == outfv);
405  assert(maxv == outv);
406 
407  // shuffle erase the maximum from our list.
408  vals[maxi] = vals[sz - 1];
409  sz--;
410  }
411  }
412 
413  if (sz > maxsz)
414  maxsz = sz;
415 
416  if (maxsz > 0 && sz == 0)
417  zcnt++;
418  }
419 
420  printf("max size: %d, zcount %d\n", maxsz, zcnt);
421  free (vals);
422 }
float * values
Definition: zmaxheap.c:64
void zmaxheap_iterator_init(zmaxheap_t *heap, zmaxheap_iterator_t *it)
Definition: zmaxheap.c:256
void zmaxheap_iterator_remove(zmaxheap_iterator_t *it)
Definition: zmaxheap.c:304
void zmaxheap_destroy(zmaxheap_t *heap)
Definition: zmaxheap.c:109
#define debug_print(fmt,...)
Definition: debug_print.h:39
#define MIN_CAPACITY
Definition: zmaxheap.c:55
void zmaxheap_vmap(zmaxheap_t *heap, void(*f)())
Definition: zmaxheap.c:170
int zmaxheap_remove_index(zmaxheap_t *heap, int idx, void *p, float *v)
Definition: zmaxheap.c:189
void zmaxheap_test()
Definition: zmaxheap.c:360
int size
Definition: zmaxheap.c:61
void(* swap)(zmaxheap_t *heap, int a, int b)
Definition: zmaxheap.c:67
static void swap_default(zmaxheap_t *heap, int a, int b)
Definition: zmaxheap.c:70
int zmaxheap_size(zmaxheap_t *heap)
Definition: zmaxheap.c:117
zmaxheap_t * zmaxheap_create(size_t el_sz)
Definition: zmaxheap.c:96
static void swap_pointer(zmaxheap_t *heap, int a, int b)
Definition: zmaxheap.c:83
zmaxheap_t * heap
Definition: zmaxheap.h:36
void zmaxheap_iterator_finish(zmaxheap_iterator_t *it)
Definition: zmaxheap.c:345
int zmaxheap_iterator_next(zmaxheap_iterator_t *it, void *p, float *v)
Definition: zmaxheap.c:264
static void maxheapify(zmaxheap_t *heap, int parent)
Definition: zmaxheap.c:309
char * data
Definition: zmaxheap.c:65
void zmaxheap_add(zmaxheap_t *heap, void *p, float v)
Definition: zmaxheap.c:143
int zmaxheap_iterator_next_volatile(zmaxheap_iterator_t *it, void *p, float *v)
Definition: zmaxheap.c:284
void zmaxheap_ensure_capacity(zmaxheap_t *heap, int capacity)
Definition: zmaxheap.c:122
int zmaxheap_remove_max(zmaxheap_t *heap, void *p, float *v)
Definition: zmaxheap.c:251
int alloc
Definition: zmaxheap.c:62
size_t el_sz
Definition: zmaxheap.c:59


apriltag
Author(s): Edwin Olson , Max Krogius
autogenerated on Mon Jun 26 2023 02:26:35