image_u8.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 <assert.h>
29 #include <stdio.h>
30 #include <stdlib.h>
31 #include <string.h>
32 #include <math.h>
33 
34 #include "common/image_u8.h"
35 #include "common/pnm.h"
36 #include "common/math_util.h"
37 
38 // least common multiple of 64 (sandy bridge cache line) and 24 (stride
39 // needed for RGB in 8-wide vector processing)
40 #define DEFAULT_ALIGNMENT_U8 96
41 
42 image_u8_t *image_u8_create_stride(unsigned int width, unsigned int height, unsigned int stride)
43 {
44  uint8_t *buf = calloc(height*stride, sizeof(uint8_t));
45 
46  // const initializer
47  image_u8_t tmp = { .width = width, .height = height, .stride = stride, .buf = buf };
48 
49  image_u8_t *im = calloc(1, sizeof(image_u8_t));
50  memcpy(im, &tmp, sizeof(image_u8_t));
51  return im;
52 }
53 
54 image_u8_t *image_u8_create(unsigned int width, unsigned int height)
55 {
56  return image_u8_create_alignment(width, height, DEFAULT_ALIGNMENT_U8);
57 }
58 
59 image_u8_t *image_u8_create_alignment(unsigned int width, unsigned int height, unsigned int alignment)
60 {
61  int stride = width;
62 
63  if ((stride % alignment) != 0)
64  stride += alignment - (stride % alignment);
65 
66  return image_u8_create_stride(width, height, stride);
67 }
68 
70 {
71  uint8_t *buf = malloc(in->height*in->stride*sizeof(uint8_t));
72  memcpy(buf, in->buf, in->height*in->stride*sizeof(uint8_t));
73 
74  // const initializer
75  image_u8_t tmp = { .width = in->width, .height = in->height, .stride = in->stride, .buf = buf };
76 
77  image_u8_t *copy = calloc(1, sizeof(image_u8_t));
78  memcpy(copy, &tmp, sizeof(image_u8_t));
79  return copy;
80 }
81 
83 {
84  if (!im)
85  return;
86 
87  free(im->buf);
88  free(im);
89 }
90 
92 // PNM file i/o
94 {
96 }
97 
98 image_u8_t *image_u8_create_from_pnm_alignment(const char *path, int alignment)
99 {
100  pnm_t *pnm = pnm_create_from_file(path);
101  if (pnm == NULL)
102  return NULL;
103 
104  image_u8_t *im = NULL;
105 
106  switch (pnm->format) {
107  case PNM_FORMAT_GRAY: {
108  im = image_u8_create_alignment(pnm->width, pnm->height, alignment);
109 
110  if (pnm->max == 255) {
111  for (int y = 0; y < im->height; y++)
112  memcpy(&im->buf[y*im->stride], &pnm->buf[y*im->width], im->width);
113  } else if (pnm->max == 65535) {
114  for (int y = 0; y < im->height; y++)
115  for (int x = 0; x < im->width; x++)
116  im->buf[y*im->stride + x] = pnm->buf[2*(y*im->width + x)];
117  } else {
118  assert(0);
119  }
120 
121  break;
122  }
123 
124  case PNM_FORMAT_RGB: {
125  im = image_u8_create_alignment(pnm->width, pnm->height, alignment);
126 
127  if (pnm->max == 255) {
128  // Gray conversion for RGB is gray = (r + g + g + b)/4
129  for (int y = 0; y < im->height; y++) {
130  for (int x = 0; x < im->width; x++) {
131  uint8_t gray = (pnm->buf[y*im->width*3 + 3*x+0] + // r
132  pnm->buf[y*im->width*3 + 3*x+1] + // g
133  pnm->buf[y*im->width*3 + 3*x+1] + // g
134  pnm->buf[y*im->width*3 + 3*x+2]) // b
135  / 4;
136 
137  im->buf[y*im->stride + x] = gray;
138  }
139  }
140  } else if (pnm->max == 65535) {
141  for (int y = 0; y < im->height; y++) {
142  for (int x = 0; x < im->width; x++) {
143  int r = pnm->buf[6*(y*im->width + x) + 0];
144  int g = pnm->buf[6*(y*im->width + x) + 2];
145  int b = pnm->buf[6*(y*im->width + x) + 4];
146 
147  im->buf[y*im->stride + x] = (r + g + g + b) / 4;
148  }
149  }
150  } else {
151  assert(0);
152  }
153 
154  break;
155  }
156 
157  case PNM_FORMAT_BINARY: {
158  im = image_u8_create_alignment(pnm->width, pnm->height, alignment);
159 
160  // image is padded to be whole bytes on each row.
161 
162  // how many bytes per row on the input?
163  int pbmstride = (im->width + 7) / 8;
164 
165  for (int y = 0; y < im->height; y++) {
166  for (int x = 0; x < im->width; x++) {
167  int byteidx = y * pbmstride + x / 8;
168  int bitidx = 7 - (x & 7);
169 
170  // ack, black is one according to pbm docs!
171  if ((pnm->buf[byteidx] >> bitidx) & 1)
172  im->buf[y*im->stride + x] = 0;
173  else
174  im->buf[y*im->stride + x] = 255;
175  }
176  }
177  break;
178  }
179  }
180 
181  pnm_destroy(pnm);
182  return im;
183 }
184 
186 {
187  image_u8_t *im = image_u8_create(fim->width, fim->height);
188 
189  for (int y = 0; y < fim->height; y++) {
190  for (int x = 0; x < fim->width; x++) {
191  float v = fim->buf[y*fim->stride + x];
192  im->buf[y*im->stride + x] = (int) (255 * v);
193  }
194  }
195 
196  return im;
197 }
198 
199 
200 int image_u8_write_pnm(const image_u8_t *im, const char *path)
201 {
202  FILE *f = fopen(path, "wb");
203  int res = 0;
204 
205  if (f == NULL) {
206  res = -1;
207  goto finish;
208  }
209 
210  // Only outputs to grayscale
211  fprintf(f, "P5\n%d %d\n255\n", im->width, im->height);
212 
213  for (int y = 0; y < im->height; y++) {
214  if (im->width != (int32_t)fwrite(&im->buf[y*im->stride], 1, im->width, f)) {
215  res = -2;
216  goto finish;
217  }
218  }
219 
220  finish:
221  if (f != NULL)
222  fclose(f);
223 
224  return res;
225 }
226 
227 void image_u8_draw_circle(image_u8_t *im, float x0, float y0, float r, int v)
228 {
229  r = r*r;
230 
231  for (int y = y0-r; y <= y0+r; y++) {
232  for (int x = x0-r; x <= x0+r; x++) {
233  float d = (x-x0)*(x-x0) + (y-y0)*(y-y0);
234  if (d > r)
235  continue;
236 
237  if (x >= 0 && x < im->width && y >= 0 && y < im->height) {
238  int idx = y*im->stride + x;
239  im->buf[idx] = v;
240  }
241  }
242  }
243 }
244 
245 void image_u8_draw_annulus(image_u8_t *im, float x0, float y0, float r0, float r1, int v)
246 {
247  r0 = r0*r0;
248  r1 = r1*r1;
249 
250  assert(r0 < r1);
251 
252  for (int y = y0-r1; y <= y0+r1; y++) {
253  for (int x = x0-r1; x <= x0+r1; x++) {
254  float d = (x-x0)*(x-x0) + (y-y0)*(y-y0);
255  if (d < r0 || d > r1)
256  continue;
257 
258  int idx = y*im->stride + x;
259  im->buf[idx] = v;
260  }
261  }
262 }
263 
264 // only widths 1 and 3 supported (and 3 only badly)
265 void image_u8_draw_line(image_u8_t *im, float x0, float y0, float x1, float y1, int v, int width)
266 {
267  double dist = sqrtf((y1-y0)*(y1-y0) + (x1-x0)*(x1-x0));
268  if (dist == 0) {
269  return;
270  }
271  double delta = 0.5 / dist;
272 
273  // terrible line drawing code
274  for (float f = 0; f <= 1; f += delta) {
275  int x = ((int) (x1 + (x0 - x1) * f));
276  int y = ((int) (y1 + (y0 - y1) * f));
277 
278  if (x < 0 || y < 0 || x >= im->width || y >= im->height)
279  continue;
280 
281  int idx = y*im->stride + x;
282  im->buf[idx] = v;
283  if (width > 1) {
284  im->buf[idx+1] = v;
285  im->buf[idx+im->stride] = v;
286  im->buf[idx+1+im->stride] = v;
287  }
288  }
289 }
290 
292 {
293  for (int y = 0; y < im->height; y++) {
294  for (int x = 0; x < im->width; x++) {
295  im->buf[im->stride*y+x] /= 2;
296  }
297  }
298 }
299 
300 static void convolve(const uint8_t *x, uint8_t *y, int sz, const uint8_t *k, int ksz)
301 {
302  assert((ksz&1)==1);
303 
304  for (int i = 0; i < ksz/2 && i < sz; i++)
305  y[i] = x[i];
306 
307  for (int i = 0; i < sz - ksz; i++) {
308  uint32_t acc = 0;
309 
310  for (int j = 0; j < ksz; j++)
311  acc += k[j]*x[i+j];
312 
313  y[ksz/2 + i] = acc >> 8;
314  }
315 
316  for (int i = sz - ksz + ksz/2; i < sz; i++)
317  y[i] = x[i];
318 }
319 
320 void image_u8_convolve_2D(image_u8_t *im, const uint8_t *k, int ksz)
321 {
322  assert((ksz & 1) == 1); // ksz must be odd.
323 
324  for (int y = 0; y < im->height; y++) {
325 
326  uint8_t *x = malloc(sizeof(uint8_t)*im->stride);
327  memcpy(x, &im->buf[y*im->stride], im->stride);
328 
329  convolve(x, &im->buf[y*im->stride], im->width, k, ksz);
330  free(x);
331  }
332 
333  for (int x = 0; x < im->width; x++) {
334  uint8_t *xb = malloc(sizeof(uint8_t)*im->height);
335  uint8_t *yb = malloc(sizeof(uint8_t)*im->height);
336 
337  for (int y = 0; y < im->height; y++)
338  xb[y] = im->buf[y*im->stride + x];
339 
340  convolve(xb, yb, im->height, k, ksz);
341  free(xb);
342 
343  for (int y = 0; y < im->height; y++)
344  im->buf[y*im->stride + x] = yb[y];
345  free(yb);
346  }
347 }
348 
349 void image_u8_gaussian_blur(image_u8_t *im, double sigma, int ksz)
350 {
351  if (sigma == 0)
352  return;
353 
354  assert((ksz & 1) == 1); // ksz must be odd.
355 
356  // build the kernel.
357  double *dk = malloc(sizeof(double)*ksz);
358 
359  // for kernel of length 5:
360  // dk[0] = f(-2), dk[1] = f(-1), dk[2] = f(0), dk[3] = f(1), dk[4] = f(2)
361  for (int i = 0; i < ksz; i++) {
362  int x = -ksz/2 + i;
363  double v = exp(-.5*sq(x / sigma));
364  dk[i] = v;
365  }
366 
367  // normalize
368  double acc = 0;
369  for (int i = 0; i < ksz; i++)
370  acc += dk[i];
371 
372  for (int i = 0; i < ksz; i++)
373  dk[i] /= acc;
374 
375  uint8_t *k = malloc(sizeof(uint8_t)*ksz);
376  for (int i = 0; i < ksz; i++)
377  k[i] = dk[i]*255;
378 
379  if (0) {
380  for (int i = 0; i < ksz; i++)
381  printf("%d %15f %5d\n", i, dk[i], k[i]);
382  }
383  free(dk);
384 
385  image_u8_convolve_2D(im, k, ksz);
386  free(k);
387 }
388 
389 image_u8_t *image_u8_rotate(const image_u8_t *in, double rad, uint8_t pad)
390 {
391  int iwidth = in->width, iheight = in->height;
392  rad = -rad; // interpret y as being "down"
393 
394  float c = cos(rad), s = sin(rad);
395 
396  float p[][2] = { { 0, 0}, { iwidth, 0 }, { iwidth, iheight }, { 0, iheight} };
397 
398  float xmin = HUGE_VALF, xmax = -HUGE_VALF, ymin = HUGE_VALF, ymax = -HUGE_VALF;
399  float icx = iwidth / 2.0, icy = iheight / 2.0;
400 
401  for (int i = 0; i < 4; i++) {
402  float px = p[i][0] - icx;
403  float py = p[i][1] - icy;
404 
405  float nx = px*c - py*s;
406  float ny = px*s + py*c;
407 
408  xmin = fmin(xmin, nx);
409  xmax = fmax(xmax, nx);
410  ymin = fmin(ymin, ny);
411  ymax = fmax(ymax, ny);
412  }
413 
414  int owidth = ceil(xmax-xmin), oheight = ceil(ymax - ymin);
415  image_u8_t *out = image_u8_create(owidth, oheight);
416 
417  // iterate over output pixels.
418  for (int oy = 0; oy < oheight; oy++) {
419  for (int ox = 0; ox < owidth; ox++) {
420  // work backwards from destination coordinates...
421  // sample pixel centers.
422  float sx = ox - owidth / 2.0 + .5;
423  float sy = oy - oheight / 2.0 + .5;
424 
425  // project into input-image space
426  int ix = floor(sx*c + sy*s + icx);
427  int iy = floor(-sx*s + sy*c + icy);
428 
429  if (ix >= 0 && iy >= 0 && ix < iwidth && iy < iheight)
430  out->buf[oy*out->stride+ox] = in->buf[iy*in->stride + ix];
431  else
432  out->buf[oy*out->stride+ox] = pad;
433  }
434  }
435 
436  return out;
437 }
438 
440 {
441  int width = im->width, height = im->height;
442 
443  if (ffactor == 1.5) {
444  int swidth = width / 3 * 2, sheight = height / 3 * 2;
445 
446  image_u8_t *decim = image_u8_create(swidth, sheight);
447 
448  int y = 0, sy = 0;
449  while (sy < sheight) {
450  int x = 0, sx = 0;
451  while (sx < swidth) {
452 
453  // a b c
454  // d e f
455  // g h i
456  uint8_t a = im->buf[(y+0)*im->stride + (x+0)];
457  uint8_t b = im->buf[(y+0)*im->stride + (x+1)];
458  uint8_t c = im->buf[(y+0)*im->stride + (x+2)];
459 
460  uint8_t d = im->buf[(y+1)*im->stride + (x+0)];
461  uint8_t e = im->buf[(y+1)*im->stride + (x+1)];
462  uint8_t f = im->buf[(y+1)*im->stride + (x+2)];
463 
464  uint8_t g = im->buf[(y+2)*im->stride + (x+0)];
465  uint8_t h = im->buf[(y+2)*im->stride + (x+1)];
466  uint8_t i = im->buf[(y+2)*im->stride + (x+2)];
467 
468  decim->buf[(sy+0)*decim->stride + (sx + 0)] =
469  (4*a+2*b+2*d+e)/9;
470  decim->buf[(sy+0)*decim->stride + (sx + 1)] =
471  (4*c+2*b+2*f+e)/9;
472 
473  decim->buf[(sy+1)*decim->stride + (sx + 0)] =
474  (4*g+2*d+2*h+e)/9;
475  decim->buf[(sy+1)*decim->stride + (sx + 1)] =
476  (4*i+2*f+2*h+e)/9;
477 
478  x += 3;
479  sx += 2;
480  }
481 
482  y += 3;
483  sy += 2;
484  }
485 
486  return decim;
487  }
488 
489  int factor = (int) ffactor;
490 
491  int swidth = 1 + (width - 1)/factor;
492  int sheight = 1 + (height - 1)/factor;
493  image_u8_t *decim = image_u8_create(swidth, sheight);
494  int sy = 0;
495  for (int y = 0; y < height; y += factor) {
496  int sx = 0;
497  for (int x = 0; x < width; x += factor) {
498  decim->buf[sy*decim->stride + sx] = im->buf[y*im->stride + x];
499  sx++;
500  }
501  sy++;
502  }
503  return decim;
504 }
505 
506 void image_u8_fill_line_max(image_u8_t *im, const image_u8_lut_t *lut, const float *xy0, const float *xy1)
507 {
508  // what is the maximum distance that will result in drawing into our LUT?
509  float max_dist2 = (lut->nvalues-1)/lut->scale;
510  float max_dist = sqrt(max_dist2);
511 
512  // the orientation of the line
513  double theta = atan2(xy1[1]-xy0[1], xy1[0]-xy0[0]);
514  double v = sin(theta), u = cos(theta);
515 
516  int ix0 = iclamp(fmin(xy0[0], xy1[0]) - max_dist, 0, im->width-1);
517  int ix1 = iclamp(fmax(xy0[0], xy1[0]) + max_dist, 0, im->width-1);
518 
519  int iy0 = iclamp(fmin(xy0[1], xy1[1]) - max_dist, 0, im->height-1);
520  int iy1 = iclamp(fmax(xy0[1], xy1[1]) + max_dist, 0, im->height-1);
521 
522  // the line segment xy0---xy1 can be parameterized in terms of line coordinates.
523  // We fix xy0 to be at line coordinate 0.
524  float xy1_line_coord = (xy1[0]-xy0[0])*u + (xy1[1]-xy0[1])*v;
525 
526  float min_line_coord = fmin(0, xy1_line_coord);
527  float max_line_coord = fmax(0, xy1_line_coord);
528 
529  for (int iy = iy0; iy <= iy1; iy++) {
530  float y = iy+.5;
531 
532  for (int ix = ix0; ix <= ix1; ix++) {
533  float x = ix+.5;
534 
535  // compute line coordinate of this pixel.
536  float line_coord = (x - xy0[0])*u + (y - xy0[1])*v;
537 
538  // find point on line segment closest to our current pixel.
539  if (line_coord < min_line_coord)
540  line_coord = min_line_coord;
541  else if (line_coord > max_line_coord)
542  line_coord = max_line_coord;
543 
544  float px = xy0[0] + line_coord*u;
545  float py = xy0[1] + line_coord*v;
546 
547  double dist2 = (x-px)*(x-px) + (y-py)*(y-py);
548 
549  // not in our LUT?
550  int idx = dist2 * lut->scale;
551  if (idx >= lut->nvalues)
552  continue;
553 
554  uint8_t lut_value = lut->values[idx];
555  uint8_t old_value = im->buf[iy*im->stride + ix];
556  if (lut_value > old_value)
557  im->buf[iy*im->stride + ix] = lut_value;
558  }
559  }
560 }
image_u8_lut::nvalues
int nvalues
Definition: image_u8.h:46
image_u8_create_from_f32
image_u8_t * image_u8_create_from_f32(image_f32_t *fim)
Definition: image_u8.c:185
image_u8_destroy
void image_u8_destroy(image_u8_t *im)
Definition: image_u8.c:82
PNM_FORMAT_RGB
#define PNM_FORMAT_RGB
Definition: pnm.h:38
image_u8_darken
void image_u8_darken(image_u8_t *im)
Definition: image_u8.c:291
pnm::height
int height
Definition: pnm.h:45
image_u8::stride
const int32_t stride
Definition: image_types.h:41
image_u8_lut
Definition: image_u8.h:38
PNM_FORMAT_BINARY
#define PNM_FORMAT_BINARY
Definition: pnm.h:36
pnm::width
int width
Definition: pnm.h:45
pnm::format
int format
Definition: pnm.h:46
DEFAULT_ALIGNMENT_U8
#define DEFAULT_ALIGNMENT_U8
Definition: image_u8.c:40
image_u8_create_alignment
image_u8_t * image_u8_create_alignment(unsigned int width, unsigned int height, unsigned int alignment)
Definition: image_u8.c:59
image_u8_decimate
image_u8_t * image_u8_decimate(image_u8_t *im, float ffactor)
Definition: image_u8.c:439
image_f32::height
const int32_t height
Definition: image_types.h:70
pnm::max
int max
Definition: pnm.h:47
image_u8_create
image_u8_t * image_u8_create(unsigned int width, unsigned int height)
Definition: image_u8.c:54
iclamp
static int iclamp(int v, int minv, int maxv)
Definition: math_util.h:166
image_u8_convolve_2D
void image_u8_convolve_2D(image_u8_t *im, const uint8_t *k, int ksz)
Definition: image_u8.c:320
image_u8::height
const int32_t height
Definition: image_types.h:40
image_u8::width
const int32_t width
Definition: image_types.h:39
image_u8
Definition: image_types.h:37
image_u8_draw_annulus
void image_u8_draw_annulus(image_u8_t *im, float x0, float y0, float r0, float r1, int v)
Definition: image_u8.c:245
convolve
static void convolve(const uint8_t *x, uint8_t *y, int sz, const uint8_t *k, int ksz)
Definition: image_u8.c:300
pnm::buf
uint8_t * buf
Definition: pnm.h:50
image_u8_create_from_pnm_alignment
image_u8_t * image_u8_create_from_pnm_alignment(const char *path, int alignment)
Definition: image_u8.c:98
image_u8_write_pnm
int image_u8_write_pnm(const image_u8_t *im, const char *path)
Definition: image_u8.c:200
image_u8_draw_line
void image_u8_draw_line(image_u8_t *im, float x0, float y0, float x1, float y1, int v, int width)
Definition: image_u8.c:265
sq
static double sq(double v)
Definition: math_util.h:66
pnm.h
image_f32
Definition: image_types.h:67
image_u8_gaussian_blur
void image_u8_gaussian_blur(image_u8_t *im, double sigma, int ksz)
Definition: image_u8.c:349
pnm_create_from_file
pnm_t * pnm_create_from_file(const char *path)
Definition: pnm.c:34
PNM_FORMAT_GRAY
#define PNM_FORMAT_GRAY
Definition: pnm.h:37
pnm
Definition: pnm.h:43
image_u8_lut::scale
float scale
Definition: image_u8.h:44
image_f32::buf
float * buf
Definition: image_types.h:73
image_u8_rotate
image_u8_t * image_u8_rotate(const image_u8_t *in, double rad, uint8_t pad)
Definition: image_u8.c:389
pnm_destroy
void pnm_destroy(pnm_t *pnm)
Definition: pnm.c:147
math_util.h
image_u8.h
image_f32::stride
const int32_t stride
Definition: image_types.h:71
image_u8_lut::values
uint8_t * values
Definition: image_u8.h:47
image_u8_create_stride
image_u8_t * image_u8_create_stride(unsigned int width, unsigned int height, unsigned int stride)
Definition: image_u8.c:42
image_u8_fill_line_max
void image_u8_fill_line_max(image_u8_t *im, const image_u8_lut_t *lut, const float *xy0, const float *xy1)
Definition: image_u8.c:506
image_f32::width
const int32_t width
Definition: image_types.h:69
image_u8::buf
uint8_t * buf
Definition: image_types.h:43
image_u8_copy
image_u8_t * image_u8_copy(const image_u8_t *in)
Definition: image_u8.c:69
image_u8_create_from_pnm
image_u8_t * image_u8_create_from_pnm(const char *path)
Definition: image_u8.c:93
image_u8_draw_circle
void image_u8_draw_circle(image_u8_t *im, float x0, float y0, float r, int v)
Definition: image_u8.c:227


apriltag
Author(s): Edwin Olson , Max Krogius
autogenerated on Sun Apr 20 2025 02:08:19