15 #ifndef _LIBMETIS_PROTO_H_ 16 #define _LIBMETIS_PROTO_H_ 45 idx_t cnvtxs,
size_t nunmatched);
47 idx_t cnvtxs,
size_t *r_nunmatched,
size_t maxdegree);
49 idx_t cnvtxs,
size_t *r_nunmatched,
size_t maxdegree);
239 void genmmd(
idx_t,
idx_t *,
idx_t *,
idx_t *,
idx_t *,
idx_t ,
idx_t *,
idx_t *,
idx_t *,
idx_t *,
idx_t,
idx_t *);
240 void mmdelm(
idx_t,
idx_t *
xadj,
idx_t *,
idx_t *,
idx_t *,
idx_t *,
idx_t *,
idx_t *,
idx_t *,
idx_t,
idx_t);
243 void mmdupd(
idx_t,
idx_t,
idx_t *,
idx_t *,
idx_t,
idx_t *,
idx_t *,
idx_t *,
idx_t *,
idx_t *,
idx_t *,
idx_t *,
idx_t,
idx_t *tag);
void Greedy_KWayVolOptimize(ctrl_t *ctrl, graph_t *graph, idx_t niter, real_t ffactor, idx_t omode)
void ComputeSubDomainGraph(ctrl_t *ctrl, graph_t *graph)
real_t ComputeLoadImbalanceDiff(graph_t *graph, idx_t nparts, real_t *pijbm, real_t *ubvec)
idx_t idx_t idx_t idx_t * vwgt
int ivecaxpygez(idx_t n, idx_t a, idx_t *x, idx_t *y, idx_t *z)
void MlevelNodeBisectionMultiple(ctrl_t *ctrl, graph_t *graph)
void MlevelNestedDissectionCC(ctrl_t *ctrl, graph_t *graph, idx_t *order, idx_t lastvtx)
int BetterBalance2Way(idx_t n, real_t *x, real_t *y)
real_t rvecmaxdiff(idx_t n, real_t *x, real_t *y)
real_t ComputeLoadImbalance(graph_t *graph, idx_t nparts, real_t *pijbm)
idx_t CheckBnd2(graph_t *)
graph_t * FixGraph(graph_t *graph)
bool match(const T &xpr, std::string ref, std::string str_xpr="")
void CreateGraphNodal(idx_t ne, idx_t nn, idx_t *eptr, idx_t *eind, idx_t **r_xadj, idx_t **r_adjncy)
void RandomBisection(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts, idx_t niparts)
void ComputeBFSOrdering(ctrl_t *ctrl, graph_t *graph, idx_t *bfsperm)
int CheckGraph(graph_t *graph, int numflag, int verbose)
void Compute2WayNodePartitionParams(ctrl_t *ctrl, graph_t *graph)
void genmmd(idx_t, idx_t *, idx_t *, idx_t *, idx_t *, idx_t, idx_t *, idx_t *, idx_t *, idx_t *, idx_t, idx_t *)
void Greedy_McKWayVolOptimize(ctrl_t *ctrl, graph_t *graph, idx_t niter, real_t ffactor, idx_t omode)
idx_t Match_2Hop(ctrl_t *ctrl, graph_t *graph, idx_t *perm, idx_t *match, idx_t cnvtxs, size_t nunmatched)
real_t ComputeElementBalance(idx_t, idx_t, idx_t *)
void EliminateSubDomainEdges(ctrl_t *ctrl, graph_t *graph)
void Greedy_KWayCutOptimize(ctrl_t *ctrl, graph_t *graph, idx_t niter, real_t ffactor, idx_t omode)
idx_t idx_t idx_t idx_t * ncommon
idx_t cnbrpoolGetNext(ctrl_t *ctrl, idx_t nnbrs)
void Refine2WayNode(ctrl_t *ctrl, graph_t *orggraph, graph_t *graph)
void ComputePartitionInfoBipartite(graph_t *, idx_t, idx_t *)
idx_t idx_t idx_t idx_t idx_t idx_t idx_t real_t real_t idx_t idx_t idx_t * part
void General2WayBalance(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts)
void MlevelNodeBisectionL1(ctrl_t *ctrl, graph_t *graph, idx_t niparts)
void PrintCtrl(ctrl_t *ctrl)
idx_t Match_2HopAny(ctrl_t *ctrl, graph_t *graph, idx_t *perm, idx_t *match, idx_t cnvtxs, size_t *r_nunmatched, size_t maxdegree)
void FM_2WayNodeRefine2Sided(ctrl_t *ctrl, graph_t *graph, idx_t niter)
idx_t CheckRInfo(ctrl_t *ctrl, ckrinfo_t *rinfo)
idx_t Match_RM(ctrl_t *ctrl, graph_t *graph)
idx_t idx_t idx_t idx_t idx_t * hmarker
void MinCover(idx_t *, idx_t *, idx_t, idx_t, idx_t *, idx_t *)
mesh_t * CreateMesh(void)
void Print2WayRefineStats(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts, real_t deltabal, idx_t mincutorder)
int CheckInputGraphWeights(idx_t nvtxs, idx_t ncon, idx_t *xadj, idx_t *adjncy, idx_t *vwgt, idx_t *vsize, idx_t *adjwgt)
void FM_2WayNodeRefine1Sided(ctrl_t *ctrl, graph_t *graph, idx_t niter)
std::vector< Array2i > sizes
graph_t * SetupSplitGraph(graph_t *graph, idx_t snvtxs, idx_t snedges)
idx_t idx_t idx_t idx_t idx_t real_t ubfactor
void Compute2WayPartitionParams(ctrl_t *ctrl, graph_t *graph)
void CreateCoarseGraphPerm(ctrl_t *ctrl, graph_t *graph, idx_t cnvtxs, idx_t *match, idx_t *perm)
void Setup2WayBalMultipliers(ctrl_t *ctrl, graph_t *graph, real_t *tpwgts)
idx_t idx_t idx_t idx_t idx_t idx_t real_t idx_t idx_t idx_t * epart
void GrowBisection(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts, idx_t niparts)
void PrintTimers(ctrl_t *)
void FM_2WayCutRefine(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts, idx_t niter)
void FM_Mc2WayCutRefine(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts, idx_t niter)
graph_t * CreateGraph(void)
void FreeMesh(mesh_t **mesh)
graph_t * SetupCoarseGraph(graph_t *graph, idx_t cnvtxs, idx_t dovsize)
void ReAdjustMemory(ctrl_t *ctrl, graph_t *graph, graph_t *cgraph)
void BucketSortKeysInc(ctrl_t *ctrl, idx_t n, idx_t max, idx_t *keys, idx_t *tperm, idx_t *perm)
void MMDOrder(ctrl_t *ctrl, graph_t *graph, idx_t *order, idx_t lastvtx)
void Allocate2WayNodePartitionMemory(ctrl_t *ctrl, graph_t *graph)
idx_t idx_t idx_t idx_t idx_t idx_t idx_t * nparts
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
idx_t MlevelKWayPartitioning(ctrl_t *ctrl, graph_t *graph, idx_t *part)
idx_t MultilevelBisect(ctrl_t *ctrl, graph_t *graph, real_t *tpwgts)
int ivecaxpylez(idx_t n, idx_t a, idx_t *x, idx_t *y, idx_t *z)
void FM_2WayRefine(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts, idx_t niter)
idx_t idx_t idx_t idx_t idx_t idx_t * iperm
idx_t * iwspacemalloc(ctrl_t *, idx_t)
void * wspacemalloc(ctrl_t *ctrl, size_t nbytes)
void SelectQueue(graph_t *graph, real_t *pijbm, real_t *ubfactors, rpq_t **queues, idx_t *from, idx_t *cnum)
idx_t mmdint(idx_t, idx_t *xadj, idx_t *, idx_t *, idx_t *, idx_t *, idx_t *, idx_t *, idx_t *)
void InduceRowPartFromColumnPart(idx_t nrows, idx_t *rowptr, idx_t *rowind, idx_t *rpart, idx_t *cpart, idx_t nparts, real_t *tpwgts)
void SetupGraph_label(graph_t *graph)
int rvecsumle(idx_t n, real_t *x1, real_t *x2, real_t *y)
idx_t IsSeparable(graph_t *)
void CreateCoarseGraph(ctrl_t *ctrl, graph_t *graph, idx_t cnvtxs, idx_t *match)
NonlinearFactorGraph graph
graph_t * CompressGraph(ctrl_t *ctrl, idx_t nvtxs, idx_t *xadj, idx_t *adjncy, idx_t *vwgt, idx_t *cptr, idx_t *cind)
int BetterVBalance(idx_t ncon, real_t *itvwgt, idx_t *v_vwgt, idx_t *u1_vwgt, idx_t *u2_vwgt)
void MinCover_Decompose(idx_t *, idx_t *, idx_t, idx_t, idx_t *, idx_t *, idx_t *)
idx_t iargmax_strd(size_t, idx_t *, idx_t)
void FM_2WayNodeRefine2SidedP(ctrl_t *ctrl, graph_t *graph, idx_t *hmarker, real_t ubfactor, idx_t npasses)
void ChangeMesh2CNumbering(idx_t n, idx_t *ptr, idx_t *ind)
idx_t IsConnected(graph_t *graph, idx_t report)
void MoveGroupContigForCut(ctrl_t *ctrl, graph_t *graph, idx_t to, idx_t gid, idx_t *ptr, idx_t *ind)
idx_t Match_2HopAll(ctrl_t *ctrl, graph_t *graph, idx_t *perm, idx_t *match, idx_t cnvtxs, size_t *r_nunmatched, size_t maxdegree)
idx_t IsConnectedSubdomain(ctrl_t *, graph_t *, idx_t, idx_t)
void AllocateWorkSpace(ctrl_t *ctrl, graph_t *graph)
int metis_rcode(int sigrval)
idx_t idx_t idx_t idx_t idx_t * vsize
void MlevelNodeBisectionL2(ctrl_t *ctrl, graph_t *graph, idx_t niparts)
void Bnd2WayBalance(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts)
void ConstructMinCoverSeparator(ctrl_t *ctrl, graph_t *graph)
void MinCover_RowDFS(idx_t *, idx_t *, idx_t, idx_t *, idx_t *, idx_t)
void CheckKWayVolPartitionParams(ctrl_t *ctrl, graph_t *graph)
idx_t IsArticulationNode(idx_t i, idx_t *xadj, idx_t *adjncy, idx_t *where, idx_t *bfslvl, idx_t *bfsind, idx_t *bfsmrk)
void AllocateKWayPartitionMemory(ctrl_t *ctrl, graph_t *graph)
void GrowBisectionNode(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts, idx_t niparts)
void SetupKWayBalMultipliers(ctrl_t *ctrl, graph_t *graph)
void InitMesh(mesh_t *mesh)
idx_t ComputeVolume(graph_t *, idx_t *)
void AllocateRefinementWorkSpace(ctrl_t *ctrl, idx_t nbrpoolsize)
void PrintCGraphStats(ctrl_t *ctrl, graph_t *graph)
void wspacepop(ctrl_t *ctrl)
int IsBalanced(ctrl_t *ctrl, graph_t *graph, real_t ffactor)
idx_t ComputeCut(graph_t *graph, idx_t *where)
idx_t idx_t idx_t idx_t idx_t idx_t ** r_xadj
graph_t * PruneGraph(ctrl_t *ctrl, idx_t nvtxs, idx_t *xadj, idx_t *adjncy, idx_t *vwgt, idx_t *iperm, real_t factor)
ikv_t * ikvwspacemalloc(ctrl_t *, idx_t)
void Change2CNumbering(idx_t, idx_t *, idx_t *)
void FM_2WayNodeRefine1SidedP(ctrl_t *ctrl, graph_t *graph, idx_t *hmarker, real_t ubfactor, idx_t npasses)
void McGrowBisection(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts, idx_t niparts)
void mmdupd(idx_t, idx_t, idx_t *, idx_t *, idx_t, idx_t *, idx_t *, idx_t *, idx_t *, idx_t *, idx_t *, idx_t *, idx_t, idx_t *tag)
idx_t ComputeMaxCut(graph_t *graph, idx_t nparts, idx_t *where)
graph_t * CoarsenGraph(ctrl_t *ctrl, graph_t *graph)
idx_t idx_t idx_t idx_t idx_t idx_t real_t idx_t idx_t idx_t idx_t * npart
int BetterBalanceKWay(idx_t ncon, idx_t *vwgt, real_t *itvwgt, idx_t a1, idx_t *pt1, real_t *bm1, idx_t a2, idx_t *pt2, real_t *bm2)
Array< int, Dynamic, 1 > v
idx_t MlevelRecursiveBisection(ctrl_t *ctrl, graph_t *graph, idx_t nparts, idx_t *part, real_t *tpwgts, idx_t fpart)
void SplitGraphOrder(ctrl_t *ctrl, graph_t *graph, graph_t **r_lgraph, graph_t **r_rgraph)
void Change2FNumberingOrder(idx_t, idx_t *, idx_t *, idx_t *, idx_t *)
idx_t idx_t idx_t idx_t idx_t * perm
void Project2WayPartition(ctrl_t *ctrl, graph_t *graph)
idx_t idx_t idx_t idx_t idx_t idx_t idx_t real_t real_t * ubvec
graph_t * CoarsenGraphNlevels(ctrl_t *ctrl, graph_t *graph, idx_t nlevels)
ctrl_t * SetupCtrl(moptype_et optype, idx_t *options, idx_t ncon, idx_t nparts, real_t *tpwgts, real_t *ubvec)
void PrintSubDomainGraph(graph_t *graph, idx_t nparts, idx_t *where)
idx_t Match_SHEM(ctrl_t *ctrl, graph_t *graph)
void MoveGroupContigForVol(ctrl_t *ctrl, graph_t *graph, idx_t to, idx_t gid, idx_t *ptr, idx_t *ind, idx_t *vmarker, idx_t *pmarker, idx_t *modind)
void UpdateEdgeSubDomainGraph(ctrl_t *ctrl, idx_t u, idx_t v, idx_t ewgt, idx_t *r_maxndoms)
idx_t FindSepInducedComponents(ctrl_t *, graph_t *, idx_t *, idx_t *)
void MinCover_ColDFS(idx_t *, idx_t *, idx_t, idx_t *, idx_t *, idx_t)
idx_t idx_t idx_t idx_t idx_t * numflag
void InitGraph(graph_t *graph)
real_t ComputeLoadImbalanceDiffVec(graph_t *graph, idx_t nparts, real_t *pijbm, real_t *ubfactors, real_t *diffvec)
idx_t idx_t idx_t idx_t idx_t idx_t idx_t real_t * tpwgts
void Init2WayPartition(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts, idx_t niparts)
void McRandomBisection(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts, idx_t niparts)
idx_t idx_t idx_t idx_t idx_t idx_t idx_t ** r_adjncy
void FreeGraph(graph_t **graph)
void cnbrpoolReset(ctrl_t *ctrl)
void ComputeKWayVolGains(ctrl_t *ctrl, graph_t *graph)
void McGeneral2WayBalance(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts)
void SetupGraph_tvwgt(graph_t *graph)
graph_t ** SplitGraphOrderCC(ctrl_t *ctrl, graph_t *graph, idx_t ncmps, idx_t *cptr, idx_t *cind)
void ComputePartitionBalance(graph_t *, idx_t, idx_t *, real_t *)
idx_t idx_t idx_t idx_t idx_t idx_t * adjwgt
void MlevelNestedDissection(ctrl_t *ctrl, graph_t *graph, idx_t *order, idx_t lastvtx)
idx_t FindCommonElements(idx_t qid, idx_t elen, idx_t *eind, idx_t *nptr, idx_t *nind, idx_t *eptr, idx_t ncommon, idx_t *marker, idx_t *nbrs)
idx_t CheckNodeBnd(graph_t *, idx_t)
idx_t idx_t idx_t idx_t * where
void Greedy_McKWayCutOptimize(ctrl_t *ctrl, graph_t *graph, idx_t niter, real_t ffactor, idx_t omode)
idx_t CheckBnd(graph_t *)
void mmdelm(idx_t, idx_t *xadj, idx_t *, idx_t *, idx_t *, idx_t *, idx_t *, idx_t *, idx_t *, idx_t, idx_t)
idx_t FindPartitionInducedComponents(graph_t *graph, idx_t *where, idx_t *cptr, idx_t *cind)
idx_t vnbrpoolGetNext(ctrl_t *ctrl, idx_t nnbrs)
void Balance2Way(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts)
graph_t * SetupGraph(ctrl_t *ctrl, idx_t nvtxs, idx_t ncon, idx_t *xadj, idx_t *adjncy, idx_t *vwgt, idx_t *vsize, idx_t *adjwgt)
idx_t idx_t idx_t * adjncy
void ConstructSeparator(ctrl_t *ctrl, graph_t *graph)
void CreateCoarseGraphNoMask(ctrl_t *ctrl, graph_t *graph, idx_t cnvtxs, idx_t *match)
void GrowBisectionNode2(ctrl_t *ctrl, graph_t *graph, real_t *ntpwgts, idx_t niparts)
void Change2FNumbering2(idx_t, idx_t *, idx_t *)
void KWayVolUpdate(ctrl_t *ctrl, graph_t *graph, idx_t v, idx_t from, idx_t to, ipq_t *queue, idx_t *vstatus, idx_t *r_nupd, idx_t *updptr, idx_t *updind, idx_t bndtype, idx_t *vmarker, idx_t *pmarker, idx_t *modind)
void Project2WayNodePartition(ctrl_t *ctrl, graph_t *graph)
idx_t iargmax_nrm(size_t n, idx_t *x, real_t *y)
void vnbrpoolReset(ctrl_t *ctrl)
int rvecle(idx_t n, real_t *x, real_t *y)
void Allocate2WayPartitionMemory(ctrl_t *ctrl, graph_t *graph)
void Greedy_KWayOptimize(ctrl_t *ctrl, graph_t *graph, idx_t niter, real_t ffactor, idx_t omode)
void MoveGroupMinConnForVol(ctrl_t *ctrl, graph_t *graph, idx_t to, idx_t nind, idx_t *ind, idx_t *vmarker, idx_t *pmarker, idx_t *modind)
void mmdnum(idx_t, idx_t *, idx_t *, idx_t *)
void ComputeKWayBoundary(ctrl_t *ctrl, graph_t *graph, idx_t bndtype)
void ChangeMesh2FNumbering2(idx_t ne, idx_t nn, idx_t *ptr, idx_t *ind, idx_t *epart, idx_t *npart)
void MlevelNestedDissectionP(ctrl_t *ctrl, graph_t *graph, idx_t *order, idx_t lastvtx, idx_t npes, idx_t cpos, idx_t *sizes)
void FreeWorkSpace(ctrl_t *ctrl)
idx_t MinCover_Augment(idx_t *, idx_t *, idx_t, idx_t *, idx_t *, idx_t *, idx_t)
void RefineKWay(ctrl_t *ctrl, graph_t *orggraph, graph_t *graph)
void ComputeLoadImbalanceVec(graph_t *graph, idx_t nparts, real_t *pijbm, real_t *lbvec)
idx_t idx_t idx_t idx_t npes
void Refine2Way(ctrl_t *ctrl, graph_t *orggraph, graph_t *graph, real_t *rtpwgts)
void FreeRData(graph_t *graph)
void ComputeKWayPartitionParams(ctrl_t *ctrl, graph_t *graph)
idx_t CheckNodePartitionParams(graph_t *)
void EliminateComponents(ctrl_t *ctrl, graph_t *graph)
int ivecle(idx_t n, idx_t *x, idx_t *z)
idx_t iargmax2_nrm(size_t n, idx_t *x, real_t *y)
void InitKWayPartitioning(ctrl_t *ctrl, graph_t *graph)
idx_t FindCommonNodes(idx_t qid, idx_t nelmnts, idx_t *elmntids, idx_t *eptr, idx_t *eind, idx_t *marker, idx_t *nbrs)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
void FM_2WayNodeBalance(ctrl_t *ctrl, graph_t *graph)
int ivecge(idx_t n, idx_t *x, idx_t *z)
idx_t rargmax2(size_t, real_t *)
void InitSeparator(ctrl_t *ctrl, graph_t *graph, idx_t niparts)
real_t * rwspacemalloc(ctrl_t *, idx_t)
int CheckParams(ctrl_t *ctrl)
void InitTimers(ctrl_t *)
void wspacepush(ctrl_t *ctrl)
void CreateGraphDual(idx_t ne, idx_t nn, idx_t *eptr, idx_t *eind, idx_t ncommon, idx_t **r_xadj, idx_t **r_adjncy)
void MoveGroupMinConnForCut(ctrl_t *ctrl, graph_t *graph, idx_t to, idx_t nind, idx_t *ind)
void Change2FNumbering(idx_t, idx_t *, idx_t *, idx_t *)
void ChangeMesh2FNumbering(idx_t n, idx_t *ptr, idx_t *ind, idx_t nvtxs, idx_t *xadj, idx_t *adjncy)
void ProjectKWayPartition(ctrl_t *ctrl, graph_t *graph)
void FreeCtrl(ctrl_t **r_ctrl)
void SplitGraphPart(ctrl_t *ctrl, graph_t *graph, graph_t **r_lgraph, graph_t **r_rgraph)
int rvecge(idx_t n, real_t *x, real_t *y)