34 size= numpoints * dimension * (int)
sizeof(
coordT);
36 qh_fprintf(qh, qh->
ferr, 6004,
"qhull error: insufficient memory to copy %d points\n",
40 memcpy((
char *)newpoints, (
char *)points, (
size_t)size);
58 vecC[0]=
det2_(vecA[1], vecA[2],
60 vecC[1]= -
det2_(vecA[0], vecA[2],
62 vecC[2]=
det2_(vecA[0], vecA[1],
90 qh_fprintf(qh, qh->
ferr, 6005,
"qhull internal error (qh_determinate): only implemented for dimension >= 2\n");
93 det=
det2_(rows[0][0], rows[0][1],
94 rows[1][0], rows[1][1]);
98 det=
det3_(rows[0][0], rows[0][1], rows[0][2],
99 rows[1][0], rows[1][1], rows[1][2],
100 rows[2][0], rows[2][1], rows[2][2]);
131 realT abscoord, distround, joggle, maxcoord, mincoord;
132 pointT *point, *pointtemp;
138 for (k=0; k < dimension; k++) {
141 else if (qh->
DELAUNAY && k == dimension-1)
142 abscoord= 2 * maxabs * maxabs;
151 abscoord=
fmax_(maxcoord, -mincoord);
159 trace2((qh, qh->
ferr, 2001,
"qh_detjoggle: joggle=%2.2g maxwidth=%2.2g\n", joggle, maxwidth));
226 realT maxangle= 1.0, maxrho;
232 sqrt(1.0 - maxangle * maxangle) + qh->
DISTround;
251 qh_fprintf(qh, qh->
ferr, 6006,
"qhull error: the joggle for 'QJn', %.2g, is below roundoff for distance computations, %.2g\n",
282 qh_fprintf(qh, qh->
ferr, 7001,
"qhull input warning: minimum visibility V%.2g is greater than \nminimum outside W%.2g. Flipped facets are likely.\n",
306 pointT *coorda, *coordp, *gmcoord, *point, **pointp;
321 *(gmcoord++)= *coordp++ - *coorda++;
324 qh_fprintf(qh, qh->
ferr, 6007,
"qhull internal error (qh_detsimplex): #points %d < dimension %d\n",
329 trace2((qh, qh->
ferr, 2002,
"qh_detsimplex: det=%2.2g for point p%d, dim %d, nearzero? %d\n",
350 coordT *normalp= normal, *coordp= point;
356 dist += *(coordp++) * *(normalp++);
378 realT maxdistsum, maxround;
380 maxdistsum= sqrt((
realT)dimension) * maxabs;
382 maxround=
REALepsilon * (dimension * maxdistsum * 1.01 + maxabs);
384 trace4((qh, qh->
ferr, 4008,
"qh_distround: %2.2g maxabs %2.2g maxsumabs %2.2g maxdistsum %2.2g\n",
385 maxround, maxabs, maxsumabs, maxdistsum));
411 realT temp, numerx, denomx;
414 if (numer < mindenom1 && numer > -mindenom1) {
415 numerx=
fabs_(numer);
416 denomx=
fabs_(denom);
417 if (numerx < denomx) {
426 if (temp > mindenom1 || temp < -mindenom1) {
481 trace4((qh, qh->
ferr, 4009,
"qh_facetarea: f%d area %2.2g\n", facet->
id, area));
520 pointT *coorda, *coordp, *gmcoord;
530 if (vertex == notvertex)
534 coordp= vertex->
point;
538 *(gmcoord++)= *coordp++ - *coorda++;
542 dist += *coordp++ * *normalp++;
543 if (dist < -qh->WIDEfacet) {
547 coordp= vertex->
point;
550 *(gmcoord++)= (*coordp++ - dist * *normalp++) - *coorda++;
554 qh_fprintf(qh, qh->
ferr, 6008,
"qhull internal error (qh_facetarea_simplex): #points %d != dim %d -1\n",
560 for (i=0; i < dim-1; i++)
564 rows[dim-1][dim-1]= -1.0;
568 *(gmcoord++)= *normalp++;
575 trace4((qh, qh->
ferr, 4010,
"qh_facetarea_simplex: area=%2.2g for point p%d, toporient %d, nearzero? %d\n",
576 area,
qh_pointid(qh, apex), toporient, nearzero));
634 facetT *neighbor, **neighborp, *bestfacet=NULL, *facet;
652 if (goodseen && !neighbor->
good)
659 if (neighbor->
good) {
661 if (dist > bestdist) {
671 trace2((qh, qh->
ferr, 2003,
"qh_findgooddist: p%d is %2.2g above good facet f%d\n",
675 trace4((qh, qh->
ferr, 4011,
"qh_findgooddist: no good facet for p%d above f%d\n",
711 qh_fprintf(qh, qh->
ferr, 8020,
"computing area of each facet and volume of the convex hull\n");
713 trace1((qh, qh->
ferr, 1001,
"qh_getarea: computing volume and area for each facet\n"));
765 realT *rowi, *rowj, norm;
768 for (i=0; i < dim; i++) {
770 for (norm= 0.0, k= dim; k--; rowi++)
771 norm += *rowi * *rowi;
778 for (j=i+1; j < dim; j++) {
780 for (norm= 0.0, k=dim; k--; )
781 norm += *rowi++ * *rowj++;
783 *(--rowj) -= *(--rowi) * norm;
822 if (normal[k] < threshold)
825 threshold -= normal[k];
826 *angle +=
fabs_(threshold);
831 if (normal[k] > threshold)
834 threshold -= normal[k];
835 *angle +=
fabs_(threshold);
878 realT randr, randa, randb;
885 qh_fprintf(qh, qh->
ferr, 6009,
"qhull error: insufficient memory to joggle %d points\n",
907 qh_fprintf(qh, qh->
ferr, 6010,
"qhull error: the current joggle for 'QJn', %.2g, is too large for the width\nof the input. If possible, recompile Qhull with higher-precision reals.\n",
913 qh_option(qh,
"_joggle-seed", &seed, NULL);
914 trace0((qh, qh->
ferr, 6,
"qh_joggleinput: joggle input by %2.2g with seed %d\n",
921 for (i=size; i--; ) {
923 *(coordp++)= *(inputp++) + (randr * randa + randb);
940 realT *maxp= NULL, *colp, absval;
943 for (k=dim, colp= normal; k--; colp++) {
944 absval=
fabs_(*colp);
945 if (absval > maxval) {
982 realT maxcoord, temp;
983 pointT *minimum, *maximum, *point, *pointtemp;
998 qh_fprintf(qh, qh->
ferr, 6011,
"qhull error: floating point constants in user.h are wrong\n\ 999 REALepsilon %g REALmin %g REALmax %g -REALmax %g\n",
1004 for (k=0; k < dimension; k++) {
1006 minimum= maximum= points + dimension;
1008 minimum= maximum= points;
1012 if (maximum[k] < point[k])
1014 else if (minimum[k] > point[k])
1017 if (k == dimension-1) {
1024 maxcoord=
fmax_(maximum[k], -minimum[k]);
1029 temp= maximum[k] - minimum[k];
1043 qh_printpoints(qh, qh->
ferr,
"qh_maxmin: found the max and min points(by dim):",
set);
1072 trace4((qh, qh->
ferr, 4012,
"qh_maxouter: max distance from facet to outer plane is %2.2g max_outside is %2.2g\n", dist, qh->
max_outside));
1100 pointT *point, **pointp, *pointtemp, *maxpoint, *minx=NULL, *maxx=NULL;
1109 if (maxcoord < point[0]) {
1113 if (mincoord > point[0]) {
1122 if (maxcoord < point[0]) {
1126 if (mincoord > point[0]) {
1139 qh_fprintf(qh, qh->
ferr, 6012,
"qhull precision error (qh_maxsimplex for voronoi_center):\n%d points with the same x coordinate.\n",
1143 qh_fprintf(qh, qh->
ferr, 6013,
"qhull input error: input is less than %d-dimensional since it has the same x coordinate\n", qh->
hull_dim);
1148 for (k=sizinit; k < dim+1; k++) {
1154 if ((det=
fabs_(det)) > maxdet) {
1157 maxnearzero= nearzero;
1161 if (!maxpoint || maxnearzero) {
1164 trace0((qh, qh->
ferr, 7,
"qh_maxsimplex: searching all points for %d-th initial vertex.\n", k+1));
1166 trace0((qh, qh->
ferr, 8,
"qh_maxsimplex: searching all points for %d-th initial vertex, better than p%d det %2.2g\n",
1174 if ((det=
fabs_(det)) > maxdet) {
1177 maxnearzero= nearzero;
1183 qh_fprintf(qh, qh->
ferr, 6014,
"qhull internal error (qh_maxsimplex): not enough points available\n");
1187 trace1((qh, qh->
ferr, 1002,
"qh_maxsimplex: selected point p%d for %d`th initial vertex, det=%2.2g\n",
1204 for (k=dim, colp=normal; k--; colp++) {
1208 return fmax_(maxval, -minval);
1220 realT *vecAp= vecA, *vecBp= vecB;
1223 for (k=0; k < dim; k++) {
1224 diff= *vecAp++ - *vecBp++;
1226 if (diff < mindiff) {
1281 realT dist, mindist;
1326 for (k= (dim > 0 ? dim : -dim); k--; ) {
1327 diff= *point1++ - *point2++;
1328 dist += diff * diff;
1353 for (i=0; i < numrow; i++) {
1355 for (k=0; k < numcol; k++) {
1429 signed char *project;
1430 int projectsize= (qh->
input_dim+1)*
sizeof(*project);
1431 pointT *newpoints, *coord, *infinity;
1432 realT paraboloid, maxboloid= 0;
1434 project= (
signed char*)
qh_memalloc(qh, projectsize);
1435 memset((
char*)project, 0, (
size_t)projectsize);
1450 qh_fprintf(qh, qh->
ferr, 6015,
"qhull internal error (qh_projectinput): dimension after projection %d != hull_dim %d\n", newdim, qh->
hull_dim);
1455 qh_fprintf(qh, qh->
ferr, 6016,
"qhull error: insufficient memory to project %d points\n",
1462 trace1((qh, qh->
ferr, 1003,
"qh_projectinput: updating lower and upper_bound\n"));
1470 qh_fprintf(qh, qh->
ferr, 6017,
"qhull internal error (qh_projectinput): HALFspace defined without qh.feasible_point\n");
1489 for (k=0; k < qh->
hull_dim-1; k++) {
1490 paraboloid += *coord * *coord;
1491 infinity[k] += *coord;
1494 *(coord++)= paraboloid;
1500 *(coord++)= maxboloid * 1.1;
1502 trace0((qh, qh->
ferr, 9,
"qh_projectinput: projected points to paraboloid for Delaunay\n"));
1534 int numpoints,
int dim,
realT *newpoints,
int newdim) {
1535 int testdim= dim, oldk=0, newk=0, i,j=0,k;
1538 for (k=0; k < n; k++)
1539 testdim += project[k];
1540 if (testdim != newdim) {
1541 qh_fprintf(qh, qh->
ferr, 6018,
"qhull internal error (qh_projectpoints): newdim %d should be %d after projection\n",
1545 for (j=0; j<n; j++) {
1546 if (project[j] == -1)
1549 newp= newpoints+newk++;
1550 if (project[j] == +1) {
1555 oldp= points+oldk++;
1556 for (i=numpoints; i--; ) {
1565 trace1((qh, qh->
ferr, 1004,
"qh_projectpoints: projected %d points from dim %d to dim %d\n",
1566 numpoints, dim, newdim));
1613 realT *point, *rowi, *coord= NULL, sum, *newval;
1618 for (point= points, j= numpoints; j--; point += dim) {
1620 for (i=0; i < dim; i++) {
1623 for (sum= 0.0, k= dim; k--; )
1624 sum += *rowi++ * *coord++;
1628 *(--coord)= *(--newval);
1684 trace4((qh, qh->
ferr, 4013,
"qh_scalelast: scale last coordinate from [%2.2g, %2.2g] to [0,%2.2g]\n",
1685 low, high, newhigh));
1693 qh_fprintf(qh, qh->
ferr, 6019,
"qhull input error: can not scale last coordinate. Input is cocircular\n or cospherical. Use option 'Qz' to add a point at infinity.\n");
1695 qh_fprintf(qh, qh->
ferr, 6020,
"qhull input error: can not scale last coordinate. New bounds [0, %2.2g] are too wide for\nexisting bounds [%2.2g, %2.2g] (width %2.2g)\n",
1696 newhigh, low, high, high-low);
1699 shift= - low * newhigh / (high-low);
1700 coord= points + dim - 1;
1701 for (i=numpoints; i--; coord += dim)
1702 *coord= *coord * scale + shift;
1726 realT shift, scale, *coord, low, high, newlow, newhigh, mincoord, maxcoord;
1729 for (k=0; k < dim; k++) {
1730 newhigh= newhighs[k];
1736 for (i=numpoints, coord=points+k; i--; coord += dim) {
1744 if (qh->
DELAUNAY && k == dim-1 && newhigh < newlow) {
1745 qh_fprintf(qh, qh->
ferr, 6021,
"qhull input error: 'Qb%d' or 'QB%d' inverts paraboloid since high bound %.2g < low bound %.2g\n",
1746 k, k, newhigh, newlow);
1749 scale=
qh_divzero(newhigh - newlow, high - low,
1752 qh_fprintf(qh, qh->
ferr, 6022,
"qhull input error: %d'th dimension's new bounds [%2.2g, %2.2g] too wide for\nexisting bounds [%2.2g, %2.2g]\n",
1753 k, newlow, newhigh, low, high);
1756 shift= (newlow * high - low * newhigh)/(high-low);
1758 for (i=numpoints; i--; coord += dim)
1759 *coord= *coord * scale + shift;
1761 if (newlow < newhigh) {
1768 for (i=numpoints; i--; coord += dim) {
1772 trace0((qh, qh->
ferr, 10,
"qh_scalepoints: scaled %d'th coordinate [%2.2g, %2.2g] to [%.2g, %.2g] for %d points by %2.2g and shifted %2.2g\n",
1773 k, low, high, newlow, newhigh, numpoints, scale, shift));
1813 trace0((qh, qh->
ferr, 11,
"qh_setdelaunay: project %d points to paraboloid for Delaunay triangulation\n", count));
1815 for (i=0; i < count; i++) {
1817 paraboloid= coord*coord;
1818 for (k=dim-2; k--; ) {
1820 paraboloid += coord*coord;
1822 *coordp++ = paraboloid;
1848 coordT *normp= normal, *feasiblep= feasible, *coordp= coords;
1856 dist += *(normp++) * *(feasiblep++);
1858 goto LABELerroroutside;
1860 if (dist < -qh->MINdenom) {
1862 *(coordp++)= *(normp++) / -dist;
1864 for (k=dim; k--; ) {
1867 goto LABELerroroutside;
1872 qh_fprintf(qh, qh->
ferr, 8021,
"qh_sethalfspace: halfspace at offset %6.2g to point: ", *offset);
1873 for (k=dim, coordp=coords; k--; ) {
1881 feasiblep= feasible;
1883 qh_fprintf(qh, qh->
ferr, 6023,
"qhull input error: feasible point is not clearly inside halfspace\nfeasible point: ");
1923 coordT *coordp, *normalp, *offsetp;
1925 trace0((qh, qh->
ferr, 12,
"qh_sethalfspace_all: compute dual for halfspace intersection\n"));
1928 qh_fprintf(qh, qh->
ferr, 6024,
"qhull error: insufficient memory to compute dual of %d halfspaces\n",
1933 normalp= halfspaces;
1934 for (i=0; i < count; i++) {
1935 offsetp= normalp + newdim;
1936 if (!
qh_sethalfspace(qh, newdim, coordp, &coordp, normalp, offsetp, feasible)) {
1938 qh_fprintf(qh, qh->
ferr, 8032,
"The halfspace was at index %d\n", i);
1941 normalp= offsetp + 1;
1972 quadrant[ k]= (facet->
normal[ k] > 0);
1975 if (quadrant[ k] != (facet->
normal[ k] > 0)) {
1985 trace3((qh, qh->
ferr, 3001,
"qh_sharpnewfacets: %d\n", issharp));
2015 pointT *point, **pointp, *point0;
2020 realT *diffp, sum2, *sum2row, *sum2p, det, factor;
2021 boolT nearzero, infinite;
2025 else if (size < dim+1) {
2027 qh_fprintf(qh, qh->
ferr, 6025,
"qhull internal error (qh_voronoi_center):\n need at least %d points to construct a Voronoi center\n",
2037 for (k=0; k < dim; k++) {
2040 if (point != point0)
2041 *(gmcoord++)= point[k] - point0[k];
2045 for (i=0; i < dim; i++) {
2047 for (k=0; k < dim; k++) {
2048 diffp= qh->
gm_row[k] + i;
2049 sum2 += *diffp * *diffp;
2061 for (i=0; i < dim; i++) {
2064 for (k=0; k < dim; k++) {
2068 *(gmcoord++)= *sum2p++;
2071 if (point != point0)
2072 *(gmcoord++)= point[k] - point0[k];
2080 qh_fprintf(qh, qh->
ferr, 8033,
"qh_voronoi_center: det %2.2g factor %2.2g ", det, factor);
2092 if (simplex != points)
boolT qh_gram_schmidt(qhT *qh, int dim, realT **row)
void qh_rotateinput(qhT *qh, realT **rows)
void seed(unsigned int seed_value)
void * qh_malloc(size_t size)
#define FOREACHvertex_(vertices)
void qh_removefacet(facetT *facet)
void qh_projectpoints(qhT *qh, signed char *project, int n, realT *points, int numpoints, int dim, realT *newpoints, int newdim)
#define SETfirstt_(set, type)
pointT * qh_facetcenter(qhT *qh, setT *vertices)
void qh_fprintf(FILE *fp, int msgcode, const char *fmt,...)
void qh_precision(const char *reason)
void qh_setdelaunay(qhT *qh, int dim, int count, pointT *points)
realT qh_divzero(realT numer, realT denom, realT mindenom1, boolT *zerodiv)
void qh_scalelast(qhT *qh, coordT *points, int numpoints, int dim, coordT low, coordT high, coordT newhigh)
#define FORALLfacet_(facetlist)
void qh_scalepoints(qhT *qh, pointT *points, int numpoints, int dim, realT *newlows, realT *newhighs)
coordT * qh_copypoints(qhT *qh, coordT *points, int numpoints, int dimension)
coordT qh_pointdist(pointT *point1, pointT *point2, int dim)
void qh_rotatepoints(qhT *qh, realT *points, int numpoints, int dim, realT **row)
int qh_pointid(pointT *point)
realT qh_maxouter(qhT *qh)
void qh_appendfacet(facetT *facet)
int qh_setin(setT *set, void *setelem)
void qh_getarea(qhT *qh, facetT *facetlist)
void qh_outerinner(qhT *qh, facetT *facet, realT *outerplane, realT *innerplane)
void qh_crossproduct(int dim, realT vecA[3], realT vecB[3], realT vecC[3])
#define det2_(a1, a2, b1, b2)
boolT qh_inthresholds(qhT *qh, coordT *normal, realT *angle)
void qh_printmatrix(qhT *qh, FILE *fp, const char *string, realT **rows, int numrow, int numcol)
void qh_gausselim(realT **rows, int numrow, int numcol, boolT *sign, boolT *nearzero)
void qh_settempfree(setT **set)
#define FOREACHridge_(ridges)
realT * qh_maxabsval(realT *normal, int dim)
coordT * qh_sethalfspace_all(qhT *qh, int dim, int count, coordT *halfspaces, pointT *feasible)
pointT * qh_getcentrum(facetT *facet)
pointT * qh_voronoi_center(qhT *qh, int dim, setT *points)
#define maximize_(maxval, val)
realT qh_minabsval(realT *normal, int dim)
void qh_option(const char *option, int *i, realT *r)
realT qh_detjoggle(qhT *qh, pointT *points, int numpoints, int dimension)
realT qh_facetarea(qhT *qh, facetT *facet)
#define det3_(a1, a2, a3, b1, b2, b3, c1, c2, c3)
realT qh_facetarea_simplex(qhT *qh, int dim, coordT *apex, setT *vertices, vertexT *notvertex, boolT toporient, coordT *normal, realT *offset)
realT qh_distnorm(int dim, pointT *point, pointT *normal, realT *offsetp)
#define FOREACHneighbor_(facet)
boolT qh_sethalfspace(qhT *qh, int dim, coordT *coords, coordT **nextp, coordT *normal, coordT *offset, coordT *feasible)
setT * qh_maxmin(qhT *qh, pointT *points, int numpoints, int dimension)
boolT qh_orientoutside(qhT *qh, facetT *facet)
void qh_projectinput(qhT *qh)
void qh_setappend(setT **setp, void *newelem)
#define qh_JOGGLEincrease
void qh_memfree(void *object, int insize)
#define FORALLpoint_(points, num)
#define qh_JOGGLEmaxincrease
realT qh_detsimplex(qhT *qh, pointT *apex, setT *points, int dim, boolT *nearzero)
#define qh_RATIOnearinside
int qh_mindiff(realT *vecA, realT *vecB, int dim)
int qh_setunique(setT **set, void *elem)
void qh_maxsimplex(qhT *qh, int dim, setT *maxpoints, pointT *points, int numpoints, setT **simplex)
void qh_errexit(int exitcode, facetT *facet, ridgeT *ridge)
realT qh_distround(qhT *qh, int dimension, realT maxabs, realT maxsumabs)
setT * qh_settemp(int setsize)
boolT qh_sharpnewfacets(qhT *qh)
facetT * qh_findgooddist(qhT *qh, pointT *point, facetT *facetA, realT *distp, facetT **facetlist)
realT qh_determinant(qhT *qh, realT **rows, int dim, boolT *nearzero)
void qh_printpoints(qhT *qh, FILE *fp, const char *string, setT *points)
void qh_scaleinput(qhT *qh)
void * qh_memalloc(int insize)
void qh_distplane(pointT *point, facetT *facet, realT *dist)
int qh_setsize(setT *set)
void qh_detroundoff(qhT *qh)
#define FOREACHpoint_(points)
void qh_joggleinput(qhT *qh)
#define minimize_(minval, val)