NDDEM
Parameters.h
Go to the documentation of this file.
1 #ifndef PARAMETERS
2 #define PARAMETERS
3 
7 #include <cstdlib>
8 #include <cmath>
9 #include <cstdio>
10 #include <vector>
11 #include <iostream>
12 #include <fstream>
13 #include <map>
14 //#include <boost/variant.hpp>
15 #include <variant>
16 #if !__EMSCRIPTEN__ && __GNUC__ < 8
17  #include <experimental/filesystem>
18  namespace fs = std::experimental::filesystem ;
19 #else
20  #include <filesystem>
21  namespace fs = std::filesystem ;
22 #endif
23 
24 #include "Typedefs.h"
25 #include "Tools.h"
26 #include "Xml.h"
27 #include "Vtk.h"
28 #include "RigidBody.h"
29 #include "Mesh.h"
30 #include "Boundaries.h"
31 #include "json_parser.h"
32 //#include "json.hpp"
33 //
34 #include <boost/random.hpp>
35 
36 #ifdef EMSCRIPTEN
37  #define STR_PROTECT(s) static_cast<const char*>(s "\0")
38 #else
39  #define STR_PROTECT(s) s
40 #endif
41 
42 //using json = nlohmann::json;
43 using json = nddem::json ;
44 using namespace std ;
45 enum class ExportType {NONE=0, CSV=1, VTK=2, NETCDFF=4, XML=8, XMLbase64=16, CSVA=32, CSVCONTACT=64} ;
46 enum class ExportData {NONE=0, POSITION=0x1, VELOCITY=0x2, OMEGA=0x4, OMEGAMAG=0x8, ORIENTATION=0x10, COORDINATION=0x20, RADIUS=0x40, IDS=0x80, FN=0x100, FT=0x200, TORQUE=0x400, GHOSTMASK=0x800, GHOSTDIR=0x1000, BRANCHVECTOR=0x2000, FN_EL=0x4000, FN_VISC=0x8000, FT_EL=0x10000, FT_VISC=0x20000, FT_FRIC=0x40000, FT_FRICTYPE=0x80000, CONTACTPOSITION=0x100000, MASS=0x200000} ;
47 inline ExportType & operator|=(ExportType & a, const ExportType b) {a= static_cast<ExportType>(static_cast<int>(a) | static_cast<int>(b)); return a ; }
48 inline ExportData & operator|=(ExportData & a, const ExportData b) {a= static_cast<ExportData>(static_cast<int>(a) | static_cast<int>(b)); return a ; }
49 inline ExportData operator| (ExportData a, ExportData b) {auto c= static_cast<ExportData>(static_cast<int>(a) | static_cast<int>(b)); return c ; }
50 inline ExportData operator~ (ExportData a) {auto c= static_cast<ExportData>(~static_cast<int>(a)); return c ; }
51 inline ExportData & operator&=(ExportData & a, const ExportData b) {a= static_cast<ExportData>(static_cast<int>(a) & static_cast<int>(b)); return a ; }
52 inline ExportData & operator>>= (ExportData& w, int u) {w=static_cast<ExportData>(static_cast<int>(w)>>u) ; return w ; }
53 inline ExportData & operator<<= (ExportData& w, int u) {w=static_cast<ExportData>(static_cast<int>(w)<<u) ; return w ; }
54 inline bool operator& (ExportType & a, ExportType b) {return (static_cast<int>(a) & static_cast<int>(b)) ; }
55 inline bool operator& (ExportData & a, ExportData b) {return (static_cast<int>(a) & static_cast<int>(b)) ; }
56 
57 template <int d>
58 class Multiproc ;
59 
61 template <typename T>
62 class number_gen {
63 public:
64  void parse (std::string s)
65  {
66  auto res = s.find(':') ; double val ;
67  if (res==std::string::npos)
68  {
69  val=stod(s) ; first=static_cast<T>(val) ;
70  isconst=true ; delta=0 ;
72  }
73  else
74  {
75  isconst=false ;
76  val=stod(s) ; first=static_cast<T>(val) ;
77  s=s.substr(res+1) ; res = s.find(':') ;
78  if (res==std::string::npos)
79  {
80  val=stod(s) ; last=static_cast<T>(val) ;
81  delta=1 ;
82  }
83  else
84  {
85  val=stod(s) ; delta=static_cast<T>(val) ;
86  s=s.substr(res+1) ;
87  val=stod(s) ; last=static_cast<T>(val) ;
88  }
89  }
90  iter=0 ;
91  }
92 
93  void reset () {iter = 0 ; }
94  int niter() { return isconst?1:(floor((last-first)/delta)+1) ; }
95  T cur() {return first+delta*iter ; }
96  std::optional<T> operator() (bool allow=false)
97  {
98  if (isconst)
99  {
100  if (iter>0 && !allow) return {} ;
101  else
102  {
103  iter ++ ;
104  return first ;
105  }
106  }
107  else
108  {
109  T res = first+delta*iter ;
110  if (res>last && !allow)
111  return {} ;
112  iter++ ;
113  return res ;
114  }
115  }
116 private:
117  int iter=0 ;
118  bool isconst = true ;
119  T first, last, delta=1 ;
120 };
121 template <typename T>
122 std::istream & operator>> (std::istream & in, number_gen<T> & n) {std::string s; in >>s ; n.parse(s) ; return in ; }
123 
127 template <int d>
128 class Parameters {
129 public :
131  Parameters (int NN):
132  N(5), //number of particles
133  tdump(100000000), //dump data every these timesteps
134  tinfo(100),
135  T(5000), //number of timesteps
136  dt(0.0001), //timestep
137  rho(1), //density (unit [M.L^(-d)]) WARNING UNUSED
138  Kn(0.0001) , //Hooke stiffness
139  Kt(0.00001) , //Tangential stiffness
140  Gamman(0.0001), //Normal damping
141  Gammat(0), //Tangential damping
142  Mu(0.5), // Friction coefficient
143  Mu_wall(0.5), // Wall friction coefficient
144  damping(0.0),
145  forceinsphere(false),
146  cellsize(-1),
147  contact_strategy(ContactStrategies::NAIVE),
148  //dumpkind(ExportType::NONE), //How to dump: 0=nothing, 1=csv, 2=vtk
149  //dumplist(ExportData::POSITION),
150  Directory ("Output"),
151  orientationtracking(true),
152  wallforcecompute(false),
153  wallforcerequested(false),
154  wallforcecomputed(false),
155  graddesc_gamma(0.1),
156  graddesc_tol(1e-5)
157  {
158  reset_ND(NN) ;
159  }
160 
161  void reset_ND (int NN)
162  {
163  N=NN ; r.resize(N,0.5) ; //particle size
164  m.resize(N, 1e-2); // Set the masses directly
165  I.resize(N,1) ; //Momentum of inertia (particles are sphere)
166  g.resize(d,0) ; // Initialise gravity
167  Frozen.resize(N,false) ;
168 
169  Boundaries.resize(d) ; // Boundary type in [:,3]: 0=regular pbc, 1=wall}
170  }
171 
172  int N;
173  int tdump ;
174  int tinfo ;
175  double T ;
176  double dt ;
177  double rho;
178  double Kn ;
179  double Kt ;
180  double Gamman;
181  double Gammat ;
182  double Mu ;
183  double Mu_wall; //< Wall friction
184  double damping; //< Artificial rolling damping
185  bool forceinsphere; //< Artificial rolling damping
186  double cellsize ;
187  ContactModels ContactModel=HOOKE ;
188  ContactStrategies contact_strategy = NAIVE ;
189  vector <std::pair<ExportType,ExportData>> dumps ;
190  XMLWriter * xmlout = nullptr ;
191  bool xmlstarted=false ;
192  mutable size_t xml_location ;
193 
194  vector <double> r ;
195  vector <double> m ;
196  vector <double> I ;
197  vector <double> g ;
198  vector <bool> Frozen ;
199  vector < Boundary<d> > Boundaries ;
200  string Directory ;
205  double graddesc_gamma ;
206  double graddesc_tol ;
208  unsigned long int seed = 5489UL ;
209  double gravityrotateangle = 0.0;
211  vector <Mesh<d>> Meshes ;
212  int n_restart=-1 ;
213  std::string restart_filename="" ;
214  unsigned char restart_flag ;
215 
216  multimap<float, string> events ;
217 
218  template <class Archive>
219  void save(Archive &ar) const {
220  if (xmlout != nullptr)
221  xml_location = xmlout->get_file_location() ;
222 
223  ar(N, tdump, tinfo, T, dt, rho, Kn, Kt, Gamman, Gammat, Mu, Mu_wall, damping, forceinsphere, cellsize, ContactModel, contact_strategy,
224  dumps, xmlstarted, xml_location, r, m, I, g, Frozen, Boundaries, Directory, orientationtracking, wallforcecompute, wallforcerequested, wallforcecomputed,
225  graddesc_gamma, graddesc_tol, contactforcedump, seed, gravityrotateangle, RigidBodies, Meshes, events,
226  n_restart, restart_filename, restart_flag
227  ) ;
228 
229  if (xmlout != nullptr)
230  xmlout->save(ar) ;
231  }
232  template <class Archive>
233  void load(Archive &ar) {
234  ar(N, tdump, tinfo, T, dt, rho, Kn, Kt, Gamman, Gammat, Mu, Mu_wall, damping, forceinsphere, cellsize, ContactModel, contact_strategy,
235  dumps, xmlstarted, xml_location, r, m, I, g, Frozen, Boundaries, Directory, orientationtracking, wallforcecompute, wallforcerequested, wallforcecomputed,
236  graddesc_gamma, graddesc_tol, contactforcedump, seed, gravityrotateangle, RigidBodies, Meshes, events,
237  n_restart, restart_filename, restart_flag
238  ) ;
239  // Handling potential XML restart
240  for (auto v : dumps)
241  if (v.first==ExportType::XML || v.first==ExportType::XMLbase64)
242  {
243  xmlout= new XMLWriter(Directory+"/dump.xml", xml_location) ;
244  xmlout->load(ar) ;
245  }
246 
247  }
248 
249 // Useful functions
250  int set_boundaries() ;
251  //int init_particles(v2d & X, v2d & A) ;
252  void perform_PBC(v1d & X, uint32_t & PBCFlags) ;
253  void perform_PBCLE_move() ;
254  void perform_PBCLE (v1d & X, v1d & V, uint32_t & PBCFlag) ;
255  bool perform_forceinsphere(v1d & X) ;
256 
257  void perform_MOVINGWALL() ;
258  int init_mass() ;
259  int init_inertia() ;
260 
261  void do_nothing (double time __attribute__((unused))) {return;}
262  double grav_intensity = 10, grav_omega=1 ; int grav_rotdim[2]={0,1} ;
263  void do_gravityrotate (double deltatime) {gravityrotateangle += deltatime*grav_omega; g[grav_rotdim[0]]=grav_intensity*cos(gravityrotateangle); g[grav_rotdim[1]]=grav_intensity*sin(gravityrotateangle); return;}
264  void (Parameters::*update_gravity) (double time) = &Parameters::do_nothing ;
265 
266  void load_datafile (char path[], v2d & X, v2d & V, v2d & Omega) ;
267  void check_events(float time, v2d & X, v2d & V, v2d & Omega) ;
268  void interpret_command (istream & in, v2d & X, v2d & V, v2d & Omega) ;
269  void interpret_command (string & in, v2d & X, v2d & V, v2d & Omega) ;
270 
271  void remove_particle (int idx, v2d & X, v2d & V, v2d & A, v2d & Omega, v2d & F, v2d & FOld, v2d & Torque, v2d & TorqueOld) ;
272  void add_particle (/*v2d & X, v2d & V, v2d & A, v2d & Omega, v2d & F, v2d & FOld, v2d & Torque, v2d & TorqueOld*/) ;
273  void init_locations (char *line, v2d & X, char *extras) ;
274  void init_radii (char line[], v1d & r) ;
275 
276  void display_info(int tint, v2d& V, v2d& Omega, v2d& F, v2d& Torque, int, int) ;
277  void quit_cleanly() ;
278  void finalise();
279  void xml_header () ;
280  int dumphandling (int ti, double t, v2d &X, v2d &V, v1d &Vmag, v2d &A, v2d &Omega, v1d &OmegaMag, vector<uint32_t> &PBCFlags, v1d & Z, Multiproc<d> & MP) ;
281  int savecsvcontact (FILE * out, ExportData outflags, Multiproc<d> & MP, cv2d & X) ;
282 } ;
285 /*****************************************************************************************************
286  * *
287  * *
288  * *
289  * IMPLEMENTATIONS *
290  * *
291  * *
292  * *
293  * ***************************************************************************************************/
294 double nan_or_double (istream & in)
295 {
296  char c; std::string word ;
297  if (!in.good()) return std::numeric_limits<double>::quiet_NaN();
298  while (isspace(c = in.peek())) in.get();
299  if ( !isdigit(c) && c!='-' && c!='.') { in >> word ; return std::numeric_limits<double>::quiet_NaN(); }
300  double x ;
301  in >> x;
302  return x ;
303 }
304 
305 
307 template <int d>
309 {
310  for (int i=0 ; i<d ; i++)
311  {
312  Boundaries[i].xmin= 0 ;
313  Boundaries[i].xmax= 1 ;
314  Boundaries[i].delta=1 ; //Precomputed to increase speed
315  Boundaries[i].Type = WallType::PBC ; // PBC by default
316  }
317  //np.savetxt('Boundaries.csv', Boundaries , delimiter=',', fmt='%.6g', header='Low,High,Size,Type', comments='')
318  return 0 ;
319 }
320 //----------------------------------------------------
321 template <int d>
323 {
324  for (size_t j=0 ; j<Boundaries.size() ; j++)
325  {
326  if (Boundaries[j].Type== WallType::PBC) //PBC
327  {
328  if (X[j]<Boundaries[j].xmin) {X[j] += Boundaries[j].delta ; PBCFlag |= (1<<j) ;}
329  else if (X[j]>Boundaries[j].xmax) {X[j] -= Boundaries[j].delta ; PBCFlag |= (1<<j) ;}
330  }
331  }
332 }
333 //----------------------------------------------------
334 template <int d>
335 void Parameters<d>::perform_PBCLE (v1d & X, v1d & V, uint32_t & PBCFlag)
336 {
337  if (Boundaries[0].Type == WallType::PBC_LE)
338  {
339  if (X[0]<Boundaries[0].xmin)
340  {
341  X[0] += Boundaries[0].delta ; PBCFlag |= 1 ;
342  X[1] += Boundaries[0].displacement ;
343  V[1] += Boundaries[0].delta*Boundaries[0].vel ; ;
344  }
345  else if (X[0]>Boundaries[0].xmax)
346  {
347  X[0] -= Boundaries[0].delta ; PBCFlag |= 1 ;
348  X[1] -= Boundaries[0].displacement ;
349  V[1] -= Boundaries[0].delta*Boundaries[0].vel ; ;
350  }
351 
352  if ( X[1]<Boundaries[1].xmin) {X[1]+=Boundaries[1].delta ; PBCFlag |= 2 ; }
353  if ( X[1]>Boundaries[1].xmax) {X[1]-=Boundaries[1].delta ; PBCFlag |= 2 ; }
354  }
355 }
356 //----------------------------------------------------
357 template <int d>
359 {
361  {
362  Boundaries[0].displacement += dt*Boundaries[0].vel*Boundaries[0].delta ;
363  if (Boundaries[0].displacement>Boundaries[1].xmax)
364  Boundaries[0].displacement -= Boundaries[1].delta ;
365  }
366 }
367 //----------------------------------------------------
368 template <int d>
370 {
371  for (size_t j=0 ; j<Boundaries.size() ; j++)
372  {
374  {
375  Boundaries[j].xmin += Boundaries[j].velmin * dt ;
376  Boundaries[j].xmax += Boundaries[j].velmax * dt ;
377  }
378  }
379 }
380 //----------------------------------------------------
381 template <int d>
383 {
384  bool res = false ;
385  if (! Boundaries[0].is_sphere())
386  { printf("ERR: forceinsphere expect the sphere to be the first wall.") ; return false ; }
387 
388  double dst = 0 ;
389  for (int dd=0 ; dd<d ; dd++) dst += (X[dd]-Boundaries[0].center[dd])*(X[dd]-Boundaries[0].center[dd]) ;
390  if (dst > Boundaries[0].radius*Boundaries[0].radius || std::isnan(dst))
391  {
392  printf("%g ", dst) ; fflush(stdout) ;
393  boost::random::mt19937 rng(++seed);
394  boost::random::uniform_01<boost::mt19937> rand(rng) ;
395  do {
396  dst=0 ;
397  for(int dd=0 ; dd < d ; dd++)
398  {
399  X[dd] = (rand()*Boundaries[0].radius*2-Boundaries[0].radius) + Boundaries[0].center[dd] ;
400  dst += (Boundaries[0].center[dd]-X[dd])*(Boundaries[0].center[dd]-X[dd]) ;
401  }
402  } while ( dst > Boundaries[0].radius * Boundaries[0].radius) ;
403  res = true ;
404  printf("[INFO] Bringing back in sphere forcibly. \n"); fflush(stdout) ;
405  }
406  return res ;
407 }
408 
409 //-----------------------------------------------------
410 /*int Parameters::init_particles(v2d & X, v2d & A)
411 {
412  boost::random::mt19937 rng;
413  boost::random::uniform_01<boost::mt19937> rand(rng) ;
414  for (int i=0 ; i<N ; i++)
415  for (int dd=0 ; dd<d ; dd++)
416  {
417  X[i][dd]=rand()*(Boundaries[dd][2]-Boundaries[dd][3]*2*r[i])+(Boundaries[dd][0]+Boundaries[dd][3]*r[i]);//avoid too much overlap with walls
418  //m[i]=volume(r[i])*rho ;
419 
420  }
421  //X[0][5]=0.14 ;
422  //V[0][:]=np.zeros((1,d))+0.0001*unitvec(0) ;
423  //X[1][:]=np.ones((1,d))*0.7 ; X[1,5]=0.2 ; X[1,4]=0.71 ;
424  //X[1][:]=np.array([0.21,0.21,0.9,0.2]) ;
425  return 0 ;
426 }*/
427 template <int d>
429 {
430  for (int i=0 ; i<N ; i++)
431  m[i]=rho*Tools<d>::Volume(r[i]) ;
432 return 0 ;
433 }
434 
435 template <int d>
437 {
438  for (int i=0; i<N ; i++)
439  {
440  I[i]=Tools<d>::InertiaMomentum (r[i], rho) ;
441  }
442  return 0 ;
443 }
444 //---------------------------------------------------
445 template <int d>
446 void Parameters<d>::load_datafile (char path[], v2d & X, v2d & V, v2d & Omega)
447 {
448  ifstream in ;
449 
450  in.open(path) ;
451  if (!in.is_open()) { printf("[Input] file cannot be open\n"); return ;}
452 
453  while (! in.eof())
454  {
455  interpret_command(in, X, V, Omega) ;
456  }
457 
458  in.close() ;
459  // Self copy :)
460  fs::path p (path) ;
461  fs::path pcp (Directory+"/in") ;// pcp/= p.filename() ;
462  copy_file(p,pcp, fs::copy_options::overwrite_existing);
463 }
464 //-------------------------------------------------
465 template <int d>
466 void Parameters<d>::check_events(float time, v2d & X, v2d & V, v2d & Omega)
467 {
468  while (events.size()>0 && events.begin()->first < time)
469  {
470  stringstream command ; command.str(events.begin()->second) ;
471  printf("\nThe following event is implemented now: %s\n", events.begin()->second.c_str()) ;
472  interpret_command(command, X,V,Omega) ;
473  events.erase(events.begin()) ;
474  }
475 
476 }
477 //------------------------------------------------------
478 std::istream& operator>>(std::istream& in, std::variant<int*,double*,bool*> v)
479 {
480  printf("SETTING variable %ld\n", v.index());
481  switch(v.index())
482  {
483  case 0: in >> *(std::get<int*>(v)) ; break ;
484  case 1: in >> *(std::get<double*>(v)); break ;
485  case 2: in >> *(std::get<bool*>(v)); break ;
486  }
487  return(in) ;}
488 //------------------------------------------------------
489 template <int d>
490 void Parameters<d>::interpret_command (string &in, v2d & X, v2d & V, v2d & Omega)
491 {
492  stringstream B(in) ;
493  return (interpret_command(B, X, V, Omega)) ;
494 }
495 template <int d>
496 void Parameters<d>::interpret_command (istream & in, v2d & X, v2d & V, v2d & Omega)
497 {
498  map <string, std::variant<int*,double*,bool*>> SetValueMap = {
499  {"Kn",&Kn},
500  {"Kt",&Kt},
501  {"GammaN",&Gamman},
502  {"GammaT",&Gammat},
503  {"rho",&rho},
504  {"Mu",&Mu},
505  {"Mu_wall",&Mu_wall},
506  {"damping",&damping},
507  {"T",&T},
508  {"tdump",&tdump},
509  {"orientationtracking",&orientationtracking},
510  {"tinfo",&tinfo},
511  {"dt",&dt},
512  //{"skin", &skin},
513  {"gradientdescent_gamma", &graddesc_gamma},
514  {"gradientdescent_tol", &graddesc_tol},
515  {"cell_size", &cellsize},
516  {"forceinsphere", &forceinsphere}
517  } ;
518 
519 // Lambda definitions
520  auto discard_line = [&](){char line [5000] ; in.getline(line, 5000) ; } ;
521  auto read_event = [&](){float time ; char line [5000] ; in >> time ; in.getline (line, 5000) ; events.insert(make_pair(time,line)) ; printf("[INFO] Registering an event: %g -> %s\n", time, line) ;} ;
522  auto doauto = [&]() { char line [5000] ; in>>line ;
523  if (!strcmp(line, "mass")) init_mass() ;
524  else if (!strcmp(line, "rho"))
525  {
526  rho= m[0]/Tools<d>::Volume(r[0]) ;
527  printf("[INFO] Using first particle mass to set rho: %g [M].[L]^-%d\n", rho, d) ;
528  }
529  else if (!strcmp(line, "inertia")) init_inertia() ;
530  else if (!strcmp(line, "location"))
531  {
532  in >> line ;
533  char extras[5000]; in.getline(extras, 5000) ;
534  init_locations(line, X, extras) ;
535  printf("[INFO] Set all particle locations\n") ;
536  }
537  else if (!strcmp(line, "radius"))
538  {
539  in.getline(line, 5000) ;
540  init_radii(line, r) ;
541  printf("[INFO] Set all particle radii\n") ;
542  }
543  else printf("[WARN] Unknown auto command in input script\n") ;
544  printf("[INFO] Doing an auto \n") ;
545  } ;
546  auto setvalue = [&]() { char line[5000] ; in >> line ;
547  try {
548  in >> SetValueMap.at(line) ;
549  }
550  catch (const std::out_of_range & e) {
551  if (!strcmp(line, "dumps"))
552  {
553  string word ;
554  in>>word ;
555  ExportType dumpkind=ExportType::NONE ;
556  if (word=="CSV") dumpkind = ExportType::CSV ;
557  else if (word=="VTK") dumpkind = ExportType::VTK ;
558  else if (word=="NETCDFF") dumpkind = ExportType::NETCDFF ;
559  else if (word=="XML") dumpkind = ExportType::XML ;
560  else if (word=="XMLbase64") dumpkind = ExportType::XMLbase64 ;
561  else if (word=="CSVA") dumpkind = ExportType::CSVA ;
562  else if (word=="CONTACTFORCES") {dumpkind = ExportType::CSVCONTACT ; contactforcedump = true ; }
563  else if (word=="WALLFORCE") {wallforcecompute = true ; goto LABEL_leave ;} //Jumps at the end of the section
564  else {printf("Unknown dump type\n") ; }
565 
566  { // New section so g++ doesn't complains about the goto ...
567  in>>word ;
568  if (word != "with") printf("ERR: expecting keyword 'with'\n") ;
569  int nbparam ;
570  ExportData dumplist = ExportData::NONE ;
571  in>>nbparam ;
572  for (int i=0 ; i<nbparam ; i++)
573  {
574  in>>word ;
575  if (word=="Position") dumplist |= ExportData::POSITION ;
576  else if (word =="Velocity") dumplist |= ExportData::VELOCITY ;
577  else if (word =="Omega") dumplist |= ExportData::OMEGA ;
578  else if (word =="OmegaMag") dumplist |= ExportData::OMEGAMAG ;
579  else if (word =="Orientation")
580  {
581  orientationtracking=true ;
582  dumplist |= ExportData::ORIENTATION ;
583  }
584  else if (word =="Coordination") dumplist |= ExportData::COORDINATION ;
585  else if (word =="Radius") dumplist |= ExportData::RADIUS ;
586  else if (word =="Mass") dumplist |= ExportData::MASS ;
587 
588  else if (word =="Ids") dumplist |= ExportData::IDS ; // Contact properties
589  else if (word =="Fn") dumplist |= ExportData::FN ;
590  else if (word =="Ft") dumplist |= ExportData::FT ;
591  else if (word =="Torque") dumplist |= ExportData::TORQUE ;
592  else if (word =="Branch") dumplist |= ExportData::BRANCHVECTOR ;
593  else if (word =="Fn_el") dumplist |= ExportData::FN_EL ;
594  else if (word =="Fn_visc") dumplist |= ExportData::FN_VISC ;
595  else if (word =="Ft_el") dumplist |= ExportData::FT_EL ;
596  else if (word =="Ft_visc") dumplist |= ExportData::FT_VISC ;
597  else if (word =="Ft_fric") dumplist |= ExportData::FT_FRIC ;
598  else if (word =="Ft_frictype") dumplist |= ExportData::FT_FRICTYPE ;
599  else if (word =="Ghost_mask") dumplist |= ExportData::GHOSTMASK ;
600  else if (word =="Ghost_direction") dumplist |= ExportData::GHOSTDIR;
601 
602  else printf("Unknown asked data %s\n", word.c_str()) ;
603  }
604 
606  /*if constexpr (!SAVE_FORCE_COMPONENTS)
607  {
608  if (dumplist & (ExportData::FN_EL | ExportData::FN_VISC | ExportData::FT_EL | ExportData::FT_VISC | ExportData::FT_FRIC | ExportData::FT_FRICTYPE))
609  {
610  printf("WARN: NDDEM was compiled without support for force subcomponents exporting. Removing from the dump output.") ;
611  dumplist &= ~(ExportData::FN_EL | ExportData::FN_VISC | ExportData::FT_EL | ExportData::FT_VISC | ExportData::FT_FRIC | ExportData::FT_FRICTYPE) ;
612  }
613  }*/
614 
615  dumps.push_back(make_pair(dumpkind,dumplist)) ;
616  }
617  LABEL_leave: ; // Goto label (I know, not beautiful, but makes sense here really)
618  }
619  else
620  printf("[ERROR] Unknown parameter to set\n") ;
621  }
622  } ; // END of the setvalue lambda
623 
624 // Function mapping
625  map<string, function<void()>> Lvl0 ;
626  Lvl0["event"] = read_event ;
627  Lvl0["CG"] = discard_line ; // Discard CoarseGraining functions in DEM
628  Lvl0["set"] = setvalue ;
629  Lvl0["auto"] = doauto ;
630 
631  Lvl0["directory"] = [&](){in>>Directory ; if (! fs::exists(Directory)) fs::create_directory(Directory); };
632  Lvl0["dimensions"] = [&](){int nn; int dd ; in>>dd>>nn ; if (N!=nn || d!=dd) {printf("[ERROR] Dimension of number of particles not matching the input file requirements d=%d N=%d\n", d, N) ; std::exit(2) ; }} ;
633  Lvl0["location"] = [&]()
634  {
635  number_gen<int> ids ; number_gen<double> locs[d] ;
636  in >> ids ; for (int i=0 ; i<d ; i++) in >> locs[i] ;
637 
638  auto id=ids() ;
639  while (id.has_value())
640  {
641  for (int i=0 ; id.has_value() && i<d ; i++)
642  X[id.value()][i]= locs[i](true).value() ;
643  id = ids() ;
644  }
645  //try { while (1) for (int i=0, id=ids() ; i<d; i++) X[id][i]= locs[i](true) ; } catch(...) {}
646  //int id ; in>>id ; for (int i=0 ; i<d ; i++) {in >> X[id][i] ;}
647  //for (int i=0, id=ids(); i<d ; i++) { X[id][i]= locs[i]() ;}
648  printf("[INFO] Changing particle location.\n") ;
649 
650  } ;
651  Lvl0["velocity"] = [&](){int id ; in>>id ; for (int i=0 ; i<d ; i++) {in >> V[id][i] ;} printf("[INFO] Changing particle velocity.\n") ; } ;
652  Lvl0["omega"] = [&](){int id ; in>>id ; for (int i=0 ; i<d*(d-1)/2 ; i++) {in >> Omega[id][i] ;} printf("[INFO] Changing particle angular velocity.\n") ; } ;
653  Lvl0["freeze"] = [&](){int id ; in>>id ; Frozen[id]=true ; printf("[INFO] Freezing particle.\n") ;} ;
654  Lvl0["radius"] = [&](){int id ; double radius ; in>>id>>radius ; if(id==-1) r = v1d(N,radius) ; else r[id]=radius ; printf("[INFO] Set radius of particle.\n") ;} ;
655  Lvl0["mass"] = [&](){int id ; double mass ; in>>id>>mass ; if(id==-1) m = v1d(N,mass ) ; else r[id]=mass ; printf("[INFO] Set mass of particle.\n") ;} ;
656  Lvl0["gravity"] = [&](){for (int i=0 ; i<d ; i++) {in >> g[i] ;} printf("[INFO] Changing gravity.\n") ; } ;
657  Lvl0["ContactModel"] = [&](){ std::string s ; in >> s ; if (s=="Hertz") {ContactModel=ContactModels::HERTZ ;printf("[INFO] Using Hertz model\n") ;} else ContactModel=ContactModels::HOOKE ; } ;
658  Lvl0["ContactStrategy"] = [&](){ std::string s ; in >> s ; if (s=="naive") {contact_strategy = ContactStrategies::NAIVE ; }
659  else if (s=="cells") {contact_strategy = ContactStrategies::CELLS ; }
660  else if (s=="octree") {contact_strategy = ContactStrategies::OCTREE ; }
661  else {printf("[WARN] Unknown contact strategy\n") ; }} ;
662  Lvl0["gravityangle"] = [&](){ double intensity, angle ; in >> intensity >> angle ;
663  Tools<d>::setzero(g) ;
664  g[0] = -intensity * cos(angle / 180. * M_PI) ;
665  g[1] = intensity * sin(angle / 180. * M_PI) ;
666  printf("[INFO] Changing gravity angle in degree between x0 and x1.\n") ;
667  } ;
668  Lvl0["gravityrotate"] = [&] () {
669  update_gravity =&Parameters::do_gravityrotate;
670  Tools<d>::setzero(g) ;
671  in >> grav_intensity >> grav_omega >> grav_rotdim[0] >> grav_rotdim[1] ;
672  printf("[INFO] Setting up a rotating gravity\n") ;
673  } ;
674  Lvl0["boundary"] = [&](){size_t id ; in>>id ;
675  if (id>=Boundaries.size()) {Boundaries.resize(id+1) ;}
676  char line [5000] ; in>>line ;
677  if (!strcmp(line, "PBC"))
679  else if (!strcmp(line, "WALL"))
681  else if (!strcmp(line, "MOVINGWALL"))
683  else if (!strcmp(line, "SPHERE"))
685  else if (!strcmp(line, "HEMISPHERE"))
687  else if (!strcmp(line, "AXIALCYLINDER"))
689  else if (!strcmp(line, "ROTATINGSPHERE"))
691  else if (!strcmp(line, "PBCLE"))
692  {
693  assert((id==0)) ;
694  Boundaries[id].Type=WallType::PBC_LE ;
695  }
696  else if (!strcmp(line, "ELLIPSE"))
697  Boundaries[id].Type=WallType::ELLIPSE ;
698  else if (!strcmp(line, "REMOVE"))
699  { Boundaries.erase(Boundaries.begin() + id); return ; }
700  else printf("[WARN] Unknown boundary condition, unchanged.\n") ;
701 
702  Boundaries[id].read_line(in) ;
703 
704  printf("[INFO] Changing BC.\n") ;
705  };
706  Lvl0["rigid"] = [&] ()
707  {
708  size_t id, npart ; in >> id ;
709  if (RigidBodies.RB.size()<id+1) RigidBodies.RB.resize(id+1) ;
710  string s ; in>>s ;
711 
712  if (s=="set")
713  {
714  in >> npart ;
715  std::vector<int> ids ; int tmp ;
716  for (size_t i=0 ; i<npart ; i++)
717  {
718  in >> tmp ;
719  ids.push_back(tmp) ;
720  }
721  RigidBodies.RB[id].setparticles(ids, X, m) ;
722  }
723  else if (s=="gravity")
724  {
725  in >> s ;
726  if (s=="on") RigidBodies.RB[id].cancelgravity = false ;
727  else if (s=="off") RigidBodies.RB[id].cancelgravity = true ;
728  }
729  else if (s=="addforce")
730  {
731  for (int dd=0 ; dd<d ; dd++)
732  in >> RigidBodies.RB[id].addforce[dd] ; //= nan_or_double(in) ;
733  }
734  else if (s=="velocity")
735  {
736  for (int dd=0 ; dd<d ; dd++)
737  RigidBodies.RB[id].setvel[dd] = nan_or_double(in) ;
738  printf("%g %g\n", RigidBodies.RB[0].setvel[0], RigidBodies.RB[0].setvel[1]) ;
739  }
740 
741  printf("[INFO] Defining a rigid body.\n") ;
742  };
743  Lvl0["mesh"] = [&] ()
744  {
745  string s ; in>>s ;
746  json j;
747  if (s=="file" || s=="string")
748  {
749  if (s=="file")
750  {
751  in >> s ;
752  std::ifstream i(s.c_str());
753  if (i.is_open()==false) {printf("Cannot find the json file provided as argument\n") ; return ; }
754  i >> j;
755  }
756  else
757  {
758  std::getline(in, s) ;
759  j=json::parse(s) ;
760  }
761  //try
762  {
763  if (j["dimension"].get<int>()!=d) {printf("Incorrect dimension in the json Mesh file: %d, expecting %d.\n", j["dimension"].get<int>(),d) ; return ;}
764  for (auto & v: j["objects"])
765  {
766  Meshes.push_back({v[STR_PROTECT("dimensionality")].get<int>(), v["vertices"].get<std::vector<std::vector<double>>>()}) ;
767 
768  printf("[INFO] Mesh object added.\n") ;
769  }
770  }
771  }
772  else if (s=="translate")
773  {
774  std::vector<double> t(d,0) ;
775  for (int i=0 ; i<d ; i++) in>>t[i] ;
776  for (auto &v: Meshes) v.translate(t) ;
777  }
778  else if (s=="rotate")
779  {
780  std::vector<double> r(d*d, 0) ;
781  for (int i=0 ; i<d*d ; i++) in >> r[i] ;
782  for (auto &v: Meshes) v.rotate(r) ;
783  }
784  else if (s=="remove")
785  {
786  int id ;
787  in >> id ;
788  Meshes.erase(Meshes.begin()+id) ;
789  }
790  else if (s=="export")
791  {
792  in >> s ;
793  FILE * out = fopen(s.c_str(), "w") ;
794  if (out==NULL) printf("[WARN] Cannot open file to export mesh") ;
795  else
796  {
797  fprintf(out, "{\n \"dimension\": %d, \n \"objects\":[\n", d) ;
798  for (size_t i=0 ; i<Meshes.size() ; i++)
799  {
800  auto res = Meshes[i].export_json() ;
801  fprintf(out, "%s", res.c_str()) ;
802  if (i<Meshes.size()-1) fprintf(out, ",\n") ;
803  }
804  fprintf(out, "\n]}") ;
805  fclose(out) ;
806  }
807  //for (auto & v: Meshes) v.disp() ;
808  }
809  else
810  printf("[WARN] Unknown mesh subcommand\n") ;
811 
812  };
813  Lvl0["restart"] = [&] () {
814  restart_flag=0 ;
815  std::string s ; in >> s ;
816  if (s=="ignore")
817  restart_flag |= (1<<1) ;
818  else if (s=="force")
819  restart_flag |= (2<<1) ;
820 
821  in >> s ;
822  if (s=="keepall")
823  restart_flag |= 1 ;
824 
825  in >> n_restart ;
826  in >> restart_filename ;
827  } ;
828 
829 
830 // Processing
831  string line ;
832  in>>line;
833  if (line[0]=='#') {discard_line() ; return ;}
834  try {Lvl0.at(line)() ; }
835  catch (const std::out_of_range & e) { printf("LVL0 command unknown: %s\n", line.c_str()) ; discard_line() ; }
836 
837 }
838 //================================================================================================================================================
839 
840 //=====================================
841 template <int d>
842 void Parameters<d>::remove_particle (int idx, v2d & X, v2d & V, v2d & A, v2d & Omega, v2d & F, v2d & FOld, v2d & Torque, v2d & TorqueOld)
843 {
844  printf("WARN: it is probably a bad idea to use remove particle which hasn't been tested ... \n") ;
845  X.erase (X.begin()+idx) ; V.erase (V.begin()+idx) ;
846  A.erase (A.begin()+idx) ; Omega.erase (Omega.begin()+idx) ;
847  F.erase (F.begin()+idx) ; FOld.erase (FOld.begin()+idx) ;
848  Torque.erase (Torque.begin()+idx) ; TorqueOld.erase (TorqueOld.begin()+idx) ;
849  I.erase(I.begin()+idx) ; m.erase(m.begin()+idx) ; r.erase(r.begin()+idx) ;
850  Frozen.erase(Frozen.begin()+idx) ;
851  N-- ;
852 }
853 //--------------------
854 template <int d>
855 void Parameters<d>::add_particle (/*v2d & X, v2d & V, v2d & A, v2d & Omega, v2d & F, v2d & FOld, v2d & Torque, v2d & TorqueOld*/)
856 {
857  printf("add_particle NOT IMPLEMENTED YET\n") ;
858 }
859 //----------------
860 template <int d>
861 void Parameters<d>::init_locations (char *line, v2d & X, char *extras)
862 {
863  boost::random::mt19937 rng(seed);
864  boost::random::uniform_01<boost::mt19937> rand(rng) ;
865  if (!strcmp(line, "square"))
866  {
867  auto m = *(std::max_element(r.begin(), r.end())) ;
868  printf("%g\n", m) ;
869  int dd ;
870  for (dd=0 ; dd<d ; dd++) X[0][dd]=Boundaries[dd].xmin+m ;
871  for (int i=1 ; i<N ; i++)
872  {
873  X[i]=X[i-1] ;
874  for (dd=0 ; dd<d ; dd++)
875  {
876  X[i][dd] += 2*m ;
877  if (X[i][dd] > Boundaries[dd].xmax-m)
878  X[i][dd] = Boundaries[dd].xmin+m ;
879  else
880  break ;
881  }
882  if (dd==d) {printf("WARN: cannot affect all particles on the square lattice, not enough space in the simulation box\n") ; break ; }
883  }
884  }
885  else if (!strcmp(line, "randomsquare"))
886  {
887  auto m = *(std::max_element(r.begin(), r.end())) ;
888  printf("%g\n", m) ;
889  int dd ;
890  for (dd=0 ; dd<d ; dd++) X[0][dd]=Boundaries[dd].xmin+m ;
891  for (int i=1 ; i<N ; i++)
892  {
893  X[i]=X[i-1] ;
894  for (dd=0 ; dd<d ; dd++)
895  {
896  X[i][dd] += 2*m ;
897  if (X[i][dd] > Boundaries[dd].xmax-m)
898  X[i][dd] = Boundaries[dd].xmin+m + 0.1*m*(rand()-0.5) ;
899  else
900  break ;
901  }
902  if (dd==d) {printf("WARN: cannot affect all particles on the square lattice, not enough space in the simulation box\n") ; break ; }
903  }
904  }
905  else if (!strcmp(line, "randomdrop"))
906  {
907 
908  for (int i=0 ; i<N ; i++)
909  {
910  for(int dd=0 ; dd < d ; dd++)
911  {
912  if (Boundaries[dd].Type==WallType::PBC)
913  X[i][dd] = rand()*Boundaries[dd].delta + Boundaries[dd].xmin ;
914  else
915  X[i][dd] = rand()*(Boundaries[dd].delta-2*r[i]) + Boundaries[dd].xmin + r[i] ;
916  }
917  }
918  }
919  else if (!strcmp(line, "insphere"))
920  {
921  //printf("Location::insphere assumes that wall #d is a sphere") ; fflush(stdout) ;
922  auto w = std::find_if(Boundaries.begin(), Boundaries.end(), [](auto u){return (u.Type==WallType::SPHERE || u.Type==WallType::ROTATINGSPHERE) ; }) ;
923  if ( w == Boundaries.end()) {printf("ERR: the spherical wall cannot be found\n") ; fflush(stdout) ; }
924  int id = w-Boundaries.begin() ;
925 
926  for (int i=0 ; i<N ; i++)
927  {
928  double dst=0 ;
929  printf(".") ; fflush(stdout);
930  do {
931  dst=0 ;
932  for(int dd=0 ; dd < d ; dd++)
933  {
934  X[i][dd] = (rand()*Boundaries[id].radius*2-Boundaries[id].radius) + Boundaries[id].center[dd] ;
935  dst += (Boundaries[id].center[dd]-X[i][dd])*(Boundaries[id].center[dd]-X[i][dd]) ;
936  }
937  } while ( sqrt(dst) > (Boundaries[id].radius-2*r[i])) ;
938  }
939  }
940  else if (!strcmp(line, "incylinder"))
941  {
942  //printf("Location::insphere assumes that wall #d is a sphere") ; fflush(stdout) ;
943  auto w = std::find_if(Boundaries.begin(), Boundaries.end(), [](auto u){return (u.Type==WallType::AXIALCYLINDER) ; }) ;
944  if ( w== Boundaries.end()) {printf("ERR: the cylinder wall cannot be found\n") ; fflush(stdout) ; }
945  int id = w-Boundaries.begin() ;
946 
947  for (int i=0 ; i<N ; i++)
948  {
949  double dst=0 ;
950  printf(".") ; fflush(stdout);
951  do {
952  dst=0 ;
953  for(int dd=0 ; dd < d ; dd++)
954  {
955  if (dd == Boundaries[id].axis)
956  {
957  X[i][dd] = rand() * (Boundaries[Boundaries[id].axis].delta-2*r[i]) + Boundaries[Boundaries[id].axis].xmin + r[i] ;
958  }
959  else
960  {
961  X[i][dd] = (rand()*Boundaries[id].radius*2-Boundaries[id].radius) ;
962  dst += X[i][dd]*X[i][dd] ;
963  }
964  }
965  } while ( sqrt(dst) > (Boundaries[id].radius-2*r[i])) ;
966  }
967  }
968  else if (!strcmp(line, "roughinclineplane"))
969  {
970  printf("Location::roughinclineplane assumes a plane of normal [1,0,0...] at location 0 along the 1st dimension.") ; fflush(stdout) ;
971  auto m = *(std::max_element(r.begin(), r.end())) ; // Max radius
972  double delta=0.1*m ;
973  for (int dd=0 ; dd<d ; dd++) X[0][dd]=Boundaries[dd].xmin+m+delta ;
974  Frozen[0]=true ;
975  for (int i=1 ; i<N ; i++)
976  {
977  X[i]=X[i-1] ;
978  for (int dd=d-1 ; dd>=0 ; dd--)
979  {
980  X[i][dd] += 2*m+2*delta ;
981  if (X[i][dd]>Boundaries[dd].xmax-m-delta)
982  X[i][dd] = Boundaries[dd].xmin+m+delta ;
983  else
984  break ;
985  }
986  if (X[i][0]==Boundaries[0].xmin+m+delta) Frozen[i]=true ;
987  // randomize the previous grain
988  for (int dd=0 ; dd<d ; dd++)
989  X[i-1][dd] += (rand()-0.5)*2*delta ;
990  }
991  }
992  else if (!strcmp(line, "smallroughinclineplane"))
993  {
994  printf("Location::smallroughinclineplane assumes a plane of normal [1,0,0...] at location 0 along the 1st dimension. The frozen particles are forced to be the smallest particle radius\n") ; fflush(stdout) ;
995  auto r_max = *(std::max_element(r.begin(), r.end())) ; // Max radius
996  auto r_min = *(std::min_element(r.begin(), r.end())) ; // Max radius
997  double m = r_max;
998  double delta=0.1*r_max ;
999  int i_bottom_layer = 1;
1000  for (int dd=1 ; dd<d ; dd++)
1001  i_bottom_layer *= floor(Boundaries[dd].delta/(2*r_min+0.2*r_min)) ;
1002  printf("BOTTOM LAYER NUMBER: %d\n", i_bottom_layer);
1003  // for (int dd=1 ; dd<d ; dd++) X[0][dd]=Boundaries[dd].xmin+r_max+delta ; // skip first dimension
1004  Frozen[0]=true ;
1005  r[0] = r_min;
1006  for (int i=1 ; i<N ; i++)
1007  {
1008  X[i]=X[i-1] ;
1009  if (i < i_bottom_layer ) {
1010  Frozen[i]=true ;
1011  r[i] = r_min;
1012  m = r_min;
1013  delta = 0.1*r_min;
1014  } else {
1015  m = r_max;
1016  delta = 0.1*r_max;
1017  }
1018  for (int dd=d-1 ; dd>=0 ; dd--)
1019  {
1020  X[i][dd] += 2*m+2*delta ;
1021  if (X[i][dd]>Boundaries[dd].xmax-m-delta)
1022  if (i < i_bottom_layer ) {
1023  X[i][dd] = 0 ;
1024  } else {
1025  X[i][dd] = Boundaries[dd].xmin+m+delta ;
1026  }
1027  else
1028  break ;
1029  }
1030  // randomize this grain EXCEPT if it is a boundary particle
1031  for (int dd=0 ; dd<d ; dd++) {
1032  if (i >= i_bottom_layer) {
1033  X[i][dd] += (rand()-0.5)*2*delta ;
1034  }
1035  }
1036  }
1037  // add some randomness to boundary particles in first dimension only
1038  for (int i=1 ; i<i_bottom_layer ; i++)
1039  {
1040  X[i][0] += rand()*2*delta;
1041  }
1042  }
1043  else if (!strcmp(line, "roughinclineplane2"))
1044  {
1045  printf("Location::roughinclineplane assumes a plane of normal [1,0,0...] at location 0 along the 1st dimension.") ; fflush(stdout) ;
1046  auto m = *(std::max_element(r.begin(), r.end())) ; // Max radius
1047  double delta=0.1*m ; int ddd ;
1048  for (int dd=0 ; dd<d ; dd++) X[0][dd]=Boundaries[dd].xmin+m ;
1049  Frozen[0]=true ; bool bottomlayer=true ;
1050  for (int i=1 ; i<N ; i++)
1051  {
1052  X[i]=X[i-1] ;
1053  for (ddd=d-1 ; ddd>=0 ; ddd--)
1054  {
1055  if (bottomlayer)
1056  {
1057  X[i][ddd]+= 2*m ;
1058  if (X[i][ddd]>Boundaries[ddd].xmax-m)
1059  X[i][ddd] = Boundaries[ddd].xmin+m ;
1060  else
1061  break ;
1062  }
1063  else
1064  {
1065  X[i][ddd] += 2*m+2*delta ;
1066  if (X[i][ddd]>Boundaries[ddd].xmax-m-delta)
1067  X[i][ddd] = Boundaries[ddd].xmin+m+delta ;
1068  else
1069  break ;
1070  }
1071  }
1072  if (ddd==0) bottomlayer=false ;
1073  if (bottomlayer)
1074  {
1075  Frozen[i-1]=true ;
1076  X[i-1][0] += rand()*delta ; // Randomness only on x0, and only >r (above the bottom wall)
1077  }
1078  else
1079  {
1080  for (int dd=0 ; dd<d ; dd++)
1081  X[i-1][dd] += (rand()-0.5)*2*delta ;
1082  }
1083  }
1084  }
1085  else if (!strcmp(line, "quasicrystal"))
1086  {
1087  auto m = *(std::max_element(r.begin(), r.end())) ; // largest radius
1088  printf("%g\n", m) ;
1089  int dd ;
1090  // X is an array of particle locations
1091  for (dd=0 ; dd<d ; dd++) { X[0][dd]=Boundaries[dd].xmin+m ; } // d is number of dimensions, dd is its index
1092  for (int i=1 ; i<N ; i++) // number of particles
1093  {
1094  X[i]=X[i-1] ; // get previous particle location
1095  for (dd=0 ; dd<d ; dd++) // iterate over dimensions
1096  {
1097  X[i][dd] += 2*m ; // add a diameter
1098  if (X[i][dd]>Boundaries[dd].xmax-m) // if too close to 'right'
1099  X[i][dd] = Boundaries[dd].xmin+m ; // bring back to 'left'
1100  else
1101  break ;
1102  }
1103  if (dd==d) {printf("WARN: cannot affect all particles on the square lattice, not enough space in the simulation box\n") ; break ; }
1104  }
1105  }
1106  else if (!strcmp(line, "fromfile"))
1107  {
1108  while (*extras == ' ') extras++ ;
1109  std::ifstream in(extras); // Open the file
1110 
1111  if (!in) { std::cerr << "Failed to open the file." << std::endl; return;}
1112  while (!in.eof())
1113  {
1114  int idx ;
1115  in >> idx ;
1116  for (int dd=0 ; dd<d ; dd++)
1117  in >> X[idx][dd] ;
1118  in >> r[idx] ;
1119  }
1120  }
1121  else
1122  printf("ERR: undefined initial location function.\n") ;
1123 }
1124 //-----------------------------
1125 template <int d>
1126 void Parameters<d>::init_radii (char line[], v1d & r)
1127 {
1128  std::istringstream s(line) ;
1129  std::string word ;
1130  double minr, maxr, fraction, fuzz ;
1131  boost::random::mt19937 rng(seed);
1132  boost::random::uniform_01<boost::mt19937> rand(rng) ;
1133 
1134  s >> word ;
1135  printf("[%s]\n", word.c_str()) ;
1136  if (word == "uniform")
1137  {
1138  s >> minr ; s >> maxr ;
1139  for (auto & v : r) v = rand()*(maxr-minr)+minr ;
1140  }
1141  else if (word == "bidisperse")
1142  {
1143  s >> minr ; s >> maxr ;
1144  s >> fraction ;
1145 
1146  double Vs=Tools<d>::Volume(minr) ;
1147  double Vl=Tools<d>::Volume(maxr) ;
1148  double f = fraction*Vs/((1-fraction)*Vl+fraction*Vs) ;
1149 
1150  for (auto & v : r) v = (rand()<f?maxr:minr) ;
1151 
1152  }
1153  else if (word == "bidisperse_fuzzy")
1154  {
1155  s >> minr ; s >> maxr ;
1156  s >> fraction ;
1157  s >> fuzz ;
1158 
1159  double Vs=Tools<d>::Volume(minr) ;
1160  double Vl=Tools<d>::Volume(maxr) ;
1161  double f = fraction*Vs/((1-fraction)*Vl+fraction*Vs) ;
1162 
1163  for (auto & v : r)
1164  {
1165  v = (rand()<f?maxr:minr) ;
1166  v = v + (rand()*2-1)*(fuzz*v) ;
1167  }
1168  }
1169  else
1170  printf("WARN: unknown radius distribution automatic creation. Nothing done ...\n") ;
1171 }
1172 
1173 
1174 //======================================
1175 template <int d>
1176 void Parameters<d>::display_info(int tint, v2d& V, v2d& Omega, v2d& F, v2d& Torque, int nct, int ngst)
1177 {
1178 static bool first=true ;
1179 static double Rmax, mmax ;
1180 if (first)
1181 {
1182  Rmax=*max_element(r.begin(), r.end()) ;
1183  mmax=*max_element(m.begin(), m.end()) ;
1184  //printf("\e[10S\e[9A") ;
1185 }
1186 
1187 //printf("\e[s%c\n", letters[tint%4]) ;
1188 //printf("\033%c %c\n", 0x37, letters[tint%4]) ;
1189 if (tint%tinfo==0)
1190 {
1191  //for (int i=0 ; i<(tint*100)/int(T/dt) ; i++) printf("#") ;
1192  //printf("%d %d %d ",tint, T, (tint*100)/T) ;
1193  if (!first) printf("\e[8A") ;
1194  printf("\e[80G") ;
1195  printf("\n\e[80G NContacts: %d | Nghosts: %d \n", nct, ngst) ;
1196 
1197  double Vmax=Tools<d>::norm(*max_element(V.begin(), V.end(), [](cv1d &a, cv1d &b) {return (Tools<d>::normsq(a)<Tools<d>::normsq(b)) ;})) ;
1198  double Omegamax=Tools<d>::skewnorm(*max_element(Omega.begin(), Omega.end(), [](cv1d &a, cv1d &b) {return (Tools<d>::skewnormsq(a)<Tools<d>::skewnormsq(b)) ;})) ;
1199  double Torquemax=Tools<d>::skewnorm(*max_element(Torque.begin(), Torque.end(), [](cv1d &a, cv1d &b) {return (Tools<d>::skewnormsq(a)<Tools<d>::skewnormsq(b)) ;})) ;
1200  double Fmax=Tools<d>::norm(*max_element(F.begin(), F.end(), [](cv1d &a, cv1d &b) {return (Tools<d>::normsq(a)<Tools<d>::normsq(b)) ;})) ;
1201 
1202  printf("\n") ;
1203  printf("\e[80G Max V: %15g | V dt / R = %15g \n", Vmax, Vmax*dt/Rmax) ;
1204  printf("\e[80G Max O: %15g | Omega dt = %15g \n", Omegamax, Omegamax*dt) ;
1205  printf("\e[80G Max F: %15g | F dt dt / m r = %15g \n", Fmax, Fmax*dt*dt/(mmax*Rmax)) ;
1206  printf("\e[80G Max M: %15g | M dt / m R R = %15g \n", Torquemax, Torquemax*dt/(mmax*Rmax*Rmax)) ;
1207  printf("\e[80G | g dt dt / R = %15g \n", Tools<d>::norm(g)*dt*dt/Rmax) ;
1208 
1209 //printf("\e[u") ;
1210 //printf("\\033%c", 0x38) ;
1211 printf("\e[0G") ;
1212 fflush(stdout) ;
1213 }
1214 if (first) first=false ;
1215 }
1216 //------------------------------------------
1217 template <int d>
1219 {
1220  xmlout->openbranch("boundaries", {make_pair("length", to_string(d*2))}) ;
1222  for (int i=0 ; i<d ; i++) xmlout->fic << Boundaries[0].center[d]-Boundaries[0].radius << " " << Boundaries[0].center[d]+Boundaries[0].radius << " " ;
1223  else
1224  for (int i=0 ; i<d ; i++) xmlout->fic << Boundaries[i].xmin << " " << Boundaries[i].xmax << " " ;
1225  xmlout->closebranch() ;
1226 
1227  xmlout->openbranch("radius", {make_pair("length", to_string(N))}) ;
1228  for (auto v: r) xmlout->fic << v << " " ;
1229  xmlout->closebranch() ;
1230 }
1231 
1232 //-----------------------------------------
1233 template <int d>
1235 {
1236  for (auto v : dumps)
1237  if ((v.first == ExportType::XML) || (v.first == ExportType::XMLbase64))
1238  xmlout->emergencyclose() ;
1239 }
1240 template <int d>
1242 {
1243  for (auto v : dumps)
1244  if ((v.first == ExportType::XML) || (v.first == ExportType::XMLbase64))
1245  xmlout->close() ;
1246 }
1247 
1248 
1249 //========================================
1250 template <int d>
1251 int Parameters<d>::dumphandling (int ti, double t, v2d &X, v2d &V, v1d &Vmag, v2d &A, v2d &Omega, v1d &OmegaMag, vector<uint32_t> &PBCFlags, v1d & Z, Multiproc<d> & MP)
1252 {
1253  for (auto v : dumps)
1254  {
1255  if (v.first==ExportType::CSV)
1256  {
1257  char path[500] ; sprintf(path, "%s/dump-%05d.csv", Directory.c_str(), ti) ;
1258  Tools<d>::norm(Vmag, V) ; Tools<d>::norm(OmegaMag, Omega) ;
1259  if ( v.second & ExportData::VELOCITY)
1260  {
1261  Tools<d>::savecsv(path, X, V, r, PBCFlags, Vmag, OmegaMag, Z) ; //These are always written for CSV, independent of the dumplist
1262  }
1263  else
1264  {
1265  Tools<d>::savecsv(path, X, r, PBCFlags, Vmag, OmegaMag, Z) ; //These are always written for CSV, independent of the dumplist
1266  }
1267  if (v.second & ExportData::ORIENTATION)
1268  {
1269  char path[500] ; sprintf(path, "%s/dumpA-%05d.csv", Directory.c_str(), ti) ;
1270  Tools<d>::savecsv(path, A) ;
1271  }
1272  }
1273 
1274 
1275  if (v.first == ExportType::CSVCONTACT)
1276  {
1277  char path[500] ; sprintf(path, "%s/dumpcontactforce-%05d.csv", Directory.c_str(), ti) ;
1278  FILE * out = fopen(path, "w") ;
1279  if (out == NULL) {printf("[ERR] Cannot open file for contact force writing.\n") ; fflush(stdout) ; return 1 ; }
1280  savecsvcontact(out, v.second, MP, X) ;
1281  fclose(out) ;
1282  }
1283 
1284  if (v.first == ExportType::VTK)
1285  {
1286  v2d tmp ;
1287  char path[500] ; sprintf(path, "%s/dump-%05d.vtk", Directory.c_str(), ti) ;
1288 
1289  FILE * out = vtkwriter::open (path, d) ;
1290  vtkwriter::write_points(out, X, d) ;
1291 
1292  vector<std::pair<ExportData, int>> mapping ;
1293  vector<vector<double>> contactdata ;
1295  {
1296  std::tie(mapping, contactdata) = MP.contacts2array(v.second, X, *this) ;
1297  if (mapping[0].first != ExportData::IDS) printf("ERR: something went wrong in writing contact data in the vtk file %X\n", static_cast<unsigned int>(mapping[0].first)) ;
1298  vtkwriter::write_contactlines (out, contactdata) ;
1299  }
1300 
1301  vtkwriter::start_pointdata(out, X) ;
1303 
1304  vector <TensorInfos> val;
1305  if (v.second & ExportData::VELOCITY) vtkwriter::write_data(out, {"Velocity", TensorType::VECTOR, &V}, d) ;
1306  if (v.second & ExportData::OMEGA) vtkwriter::write_data(out, {"Omega", TensorType::SKEWTENSOR, &Omega}, d) ;
1307  if (v.second & ExportData::OMEGAMAG) {tmp.push_back(OmegaMag) ; vtkwriter::write_data(out, {"OmegaMag", TensorType::SCALAR, &tmp}, d) ;}
1308  if (v.second & ExportData::ORIENTATION) vtkwriter::write_data(out, {"ORIENTATION", TensorType::TENSOR, &A}, d) ;
1309  if (v.second & ExportData::RADIUS) {tmp.push_back(r) ; vtkwriter::write_data(out, {"RADIUS", TensorType::SCALAR, &tmp}, d) ;}
1310  if (v.second & ExportData::MASS) {tmp.push_back(m) ; vtkwriter::write_data(out, {"MASS", TensorType::SCALAR, &tmp}, d) ;}
1311  if (v.second & ExportData::COORDINATION) {tmp.push_back(Z) ; vtkwriter::write_data(out, {"Coordination", TensorType::SCALAR, &tmp}, d) ; }
1312  if (v.second & ExportData::IDS) {
1313  vector<double> tmpid (N, 0) ;
1314  for (int i=0 ; i<N ; i++)
1315  tmpid[i]=i ;
1316  tmp.push_back(tmpid) ; vtkwriter::write_data(out, {"Id", TensorType::SCALAR, &tmp}, d) ;
1317  }
1318 
1319  if (mapping.size()>1)
1320  {
1321  vtkwriter::start_celldata(out, X.size(), contactdata.size());
1322 
1323  for (auto & v:mapping)
1324  {
1325  switch(v.first){
1326  case ExportData::CONTACTPOSITION : vtkwriter::write_celldata (out, "Locations", contactdata, TensorType::VECTOR, v.second, N, d) ; break ;
1327  case ExportData::FN : vtkwriter::write_celldata (out, "NormalForce", contactdata, TensorType::VECTOR, v.second, N, d) ; break ;
1328  case ExportData::FT : vtkwriter::write_celldata (out, "TangentialForce", contactdata, TensorType::VECTOR, v.second, N, d) ; break ;
1329  case ExportData::BRANCHVECTOR : vtkwriter::write_celldata (out, "BranchVector", contactdata, TensorType::VECTOR, v.second, N, d) ; break ;
1330  case ExportData::FN_EL : vtkwriter::write_celldata (out, "ElasticNormalForce", contactdata, TensorType::VECTOR, v.second, N, d) ; break ;
1331  case ExportData::FN_VISC : vtkwriter::write_celldata (out, "ViscousNormalForce", contactdata, TensorType::VECTOR, v.second, N, d) ; break ;
1332  case ExportData::FT_EL : vtkwriter::write_celldata (out, "ElasticTangentialForce", contactdata, TensorType::VECTOR, v.second, N, d) ; break ;
1333  case ExportData::FT_VISC : vtkwriter::write_celldata (out, "VisousTangentialForce", contactdata, TensorType::VECTOR, v.second, N, d) ; break ;
1334  case ExportData::FT_FRIC : vtkwriter::write_celldata (out, "FrictionForce", contactdata, TensorType::VECTOR, v.second, N, d) ; break ;
1335  case ExportData::FT_FRICTYPE : vtkwriter::write_celldata (out, "FrictionActivated", contactdata, TensorType::VECTOR, v.second, N, d) ; break ;
1336  case ExportData::GHOSTMASK : vtkwriter::write_celldata (out, "GhostMask", contactdata, TensorType::SCALARMASK, v.second, N, d) ; break ;
1337  case ExportData::GHOSTDIR : vtkwriter::write_celldata (out, "GhostDirection", contactdata, TensorType::SCALARMASK, v.second, N, d) ; break ;
1338  default: break ;
1339  }
1340  }
1341  }
1342 
1343  vtkwriter::close(out) ;
1344  //Tools<d>::savevtk(path, N, Boundaries, X, r, {}) ;
1345  }
1346 
1347  if (v.first == ExportType::NETCDFF)
1348  printf("WARN: netcdf writing hasn't been tested and therefore is not plugged in\n") ;
1349 
1350  if (v.first == ExportType::XML)
1351  {
1352  if (xmlstarted==false)
1353  {
1354  char path[500] ; sprintf(path, "%s/dump.xml", Directory.c_str()) ;
1355  xmlout->header(d, path) ;
1356  xml_header() ;
1357  xmlstarted=true ;
1358  }
1359  xmlout->startTS(t);
1362  if (v.second & ExportData::OMEGA) xmlout->writeArray("Omega", &Omega, ArrayType::particles, EncodingType::ascii);
1363  if (v.second & ExportData::OMEGAMAG)
1364  printf("Omega Mag not implemented yet\n");
1367 
1369  {
1370  auto [mapping, tmp] = MP.contacts2array(v.second, X, *this) ;
1371  for (auto & v:mapping)
1372  {
1373  switch(v.first){
1374  case ExportData::IDS: xmlout->writeArray("Ids", &tmp, v.second, 2, ArrayType::contacts, EncodingType::ascii) ; break ;
1375  case ExportData::CONTACTPOSITION : xmlout->writeArray("Locations", &tmp, v.second, d, ArrayType::contacts, EncodingType::ascii) ; break ;
1376  case ExportData::FN : xmlout->writeArray("Normal force", &tmp, v.second, d, ArrayType::contacts, EncodingType::ascii) ; break ;
1377  case ExportData::FT : xmlout->writeArray("Tangential force", &tmp, v.second, d, ArrayType::contacts, EncodingType::ascii) ; break ;
1378  case ExportData::BRANCHVECTOR : xmlout->writeArray("Branch vector", &tmp, v.second, d, ArrayType::contacts, EncodingType::ascii) ; break ;
1379  case ExportData::FN_EL : xmlout->writeArray("Elastic normal force", &tmp, v.second, d, ArrayType::contacts, EncodingType::ascii) ; break ;
1380  case ExportData::FN_VISC : xmlout->writeArray("Viscous normal force", &tmp, v.second, d, ArrayType::contacts, EncodingType::ascii) ; break ;
1381  case ExportData::FT_EL : xmlout->writeArray("Elastic tangential force", &tmp, v.second, d, ArrayType::contacts, EncodingType::ascii) ; break ;
1382  case ExportData::FT_VISC : xmlout->writeArray("Visous tangential force", &tmp, v.second, d, ArrayType::contacts, EncodingType::ascii) ; break ;
1383  case ExportData::FT_FRIC : xmlout->writeArray("Friction force", &tmp, v.second, d, ArrayType::contacts, EncodingType::ascii) ; break ;
1384  case ExportData::FT_FRICTYPE : xmlout->writeArray("Friction activated", &tmp, v.second, 1, ArrayType::contacts, EncodingType::ascii) ; break ;
1385  case ExportData::GHOSTMASK : xmlout->writeArray("Ghost mask", &tmp, v.second, 1, ArrayType::contacts, EncodingType::ascii) ; break ;
1386  case ExportData::GHOSTDIR : xmlout->writeArray("Ghost direction", &tmp, v.second, 1, ArrayType::contacts, EncodingType::ascii) ; break ;
1387  default: break ;
1388  }
1389  }
1390  }
1391 
1392 // case ExportData::POSITION: res.push_back(loc) ; break ;
1393 // case ExportData::FN: res.push_back(contact.infos->Fn) ; break ;
1394 // case ExportData::FT: res.push_back(contact.infos->Ft) ; break ;
1395 // case ExportData::GHOSTMASK: res.push_back(contact.infos->ghost) ; break ;
1396 // case ExportData::GHOSTDIR : res.push_back(contact.infos->ghostdir) ; break ;
1397 // case ExportData::BRANCHVECTOR: res.push_back(branch) ; break ;
1398  xmlout->stopTS();
1399  }
1400 
1401  if (v.first == ExportType::XMLbase64)
1402  {
1403  if (xmlstarted==false)
1404  {
1405  char path[500] ; sprintf(path, "%s/dump.xml", Directory.c_str()) ;
1406  xmlout->header(d, path) ;
1407  xml_header() ;
1408  xmlstarted=true ;
1409  }
1410  xmlout->startTS(t);
1413  if (v.second & ExportData::OMEGA) xmlout->writeArray("Omega", &Omega, ArrayType::particles, EncodingType::base64);
1414  if (v.second & ExportData::OMEGAMAG)
1415  printf("Omega Mag not implemented yet\n");
1418  xmlout->stopTS();
1419  }
1420 
1421  }
1422 return 0 ;
1423 }
1424 
1425 //------------------------------------------------------------------------------
1426 template <int d>
1427 int Parameters<d>::savecsvcontact (FILE * out, ExportData outflags, Multiproc<d> & MP, cv2d & X)
1428 {
1429  if (outflags & ExportData::IDS) fprintf(out, "id_i, id_j, ") ;
1430  if (outflags & ExportData::CONTACTPOSITION || outflags & ExportData::POSITION)
1431  {
1432  for (int dd = 0 ; dd<d ; dd++)
1433  fprintf(out, "x%d_i, ", dd) ;
1434  for (int dd = 0 ; dd<d ; dd++)
1435  fprintf(out, "x%d_j, ", dd) ;
1436  }
1437  if (outflags & ExportData::FN)
1438  for (int dd = 0 ; dd<d ; dd++)
1439  fprintf(out, "Fn%d_i, ", dd) ;
1440  if (outflags & ExportData::FT)
1441  for (int dd = 0 ; dd<d ; dd++)
1442  fprintf(out, "Ft%d_i, ", dd) ;
1443  if (outflags & ExportData::TORQUE)
1444  {
1445  for (int dd = 0 ; dd<d*(d-1)/2 ; dd++)
1446  {
1447  auto val = Tools<d>::MASIndex[dd] ;
1448  fprintf(out, "Torque%d:%d_i, ", val.first, val.second) ;
1449  }
1450  for (int dd = 0 ; dd<d*(d-1)/2 ; dd++)
1451  {
1452  auto val = Tools<d>::MASIndex[dd] ;
1453  fprintf(out, "Torque%d:%d_j, ", val.first, val.second) ;
1454  }
1455  }
1456  if (outflags & ExportData::GHOSTMASK)
1457  fprintf(out, "GhostMask, ") ;
1458  if (outflags & ExportData::GHOSTDIR)
1459  fprintf(out, "GhostDir, ") ;
1460  if (outflags & ExportData::BRANCHVECTOR)
1461  {
1462  for (int dd = 0 ; dd<d ; dd++)
1463  fprintf(out, "lij%d, ", dd) ;
1464  }
1465 
1466  fseek (out, -2, SEEK_CUR) ;
1467  fprintf(out, "\n") ;
1468 
1469  for (auto & CLp : MP.CLp)
1470  {
1471  for (auto & contact: CLp.v)
1472  {
1473  if (outflags & ExportData::IDS)
1474  fprintf(out, "%d %d ", contact.i, contact.j) ;
1475  if (outflags & ExportData::CONTACTPOSITION || outflags & ExportData::POSITION)
1476  {
1477  for (auto dd : X[contact.i])
1478  fprintf(out, "%g ", dd) ;
1479  for (auto dd : X[contact.j])
1480  fprintf(out, "%g ", dd) ;
1481  }
1482  if (outflags & ExportData::FN)
1483  for (auto dd : contact.infos->Fn)
1484  fprintf(out, "%g ", dd) ;
1485  if (outflags & ExportData::FT)
1486  for (auto dd : contact.infos->Ft)
1487  fprintf(out, "%g ", dd) ;
1488 
1489  if (outflags & ExportData::TORQUE)
1490  {
1491  for (auto dd : contact.infos->Torquei)
1492  fprintf(out, "%g ", dd) ;
1493  for (auto dd : contact.infos->Torquej)
1494  fprintf(out, "%g ", dd) ;
1495  }
1496 
1497  if (outflags & ExportData::GHOSTMASK)
1498  fprintf(out, "%d ", contact.ghost) ;
1499  if (outflags & ExportData::GHOSTDIR)
1500  fprintf(out, "%d ", contact.ghostdir) ;
1501 
1502  if (outflags & ExportData::BRANCHVECTOR)
1503  {
1504  auto [loc,branch] = contact.compute_branchvector(X, *this) ;
1505 
1506  for (int dd = 0 ; dd<d ; dd++) fprintf(out, "%g ", branch[dd]) ;
1507  }
1508  fprintf(out, "\n") ;
1509  }
1510  }
1511  return 0 ;
1512 }
1513 
1514 #endif
EIGEN_DEVICE_FUNC const FloorReturnType floor() const
Definition: ArrayCwiseUnaryOps.h:481
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Definition: ArrayCwiseUnaryOps.h:187
EIGEN_DEVICE_FUNC const CosReturnType cos() const
Definition: ArrayCwiseUnaryOps.h:237
EIGEN_DEVICE_FUNC const SinReturnType sin() const
Definition: ArrayCwiseUnaryOps.h:255
double nan_or_double(istream &in)
Definition: Parameters.h:294
NLOHMANN_BASIC_JSON_TPL_DECLARATION std::string to_string(const NLOHMANN_BASIC_JSON_TPL &j)
user-defined to_string function for JSON values
Definition: json.hpp:25318
internal::enable_if< internal::valid_indexed_view_overload< RowIndices, ColIndices >::value &&internal::traits< typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::ReturnAsIndexedView, typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::type operator()(const RowIndices &rowIndices, const ColIndices &colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST
Definition: IndexedViewMethods.h:73
boost::random::mt19937 rng(static_cast< unsigned int >(std::time(nullptr)))
Manual multiprocessor handling for OpenMP, for max efficiency & avoiding bugs & race conditions,...
Definition: Multiproc.h:60
vector< ContactList< d > > CLp
ContactList particle-particle for each processor.
Definition: Multiproc.h:271
Generic class to handle the simulation set up.
Definition: Parameters.h:128
vector< double > g
Gravity vector.
Definition: Parameters.h:197
void do_nothing(double time __attribute__((unused)))
Definition: Parameters.h:261
bool contactforcedump
Extract the forces between grains as well?
Definition: Parameters.h:207
bool orientationtracking
Track orientation?
Definition: Parameters.h:201
void load_datafile(char path[], v2d &X, v2d &V, v2d &Omega)
Load and parse input script.
Definition: Parameters.h:446
void remove_particle(int idx, v2d &X, v2d &V, v2d &A, v2d &Omega, v2d &F, v2d &FOld, v2d &Torque, v2d &TorqueOld)
Not tested.
Definition: Parameters.h:842
bool perform_forceinsphere(v1d &X)
Definition: Parameters.h:382
void perform_PBCLE_move()
Definition: Parameters.h:358
void do_gravityrotate(double deltatime)
Definition: Parameters.h:263
double T
Run until this time (note it is a floating point).
Definition: Parameters.h:175
void quit_cleanly()
Close opened dump files in the event of an emergency quit (usually a SIGINT signal to the process)
Definition: Parameters.h:1234
void init_radii(char line[], v1d &r)
Set particle radii.
Definition: Parameters.h:1126
bool forceinsphere
Definition: Parameters.h:185
void xml_header()
Write the Xml header (should go into a file dedicated to the writing though ...)
Definition: Parameters.h:1218
bool wallforcecompute
Compute for on the wall?
Definition: Parameters.h:202
void save(Archive &ar) const
Definition: Parameters.h:219
vector< double > r
Particle radii.
Definition: Parameters.h:194
int N
Number of particles.
Definition: Parameters.h:172
void display_info(int tint, v2d &V, v2d &Omega, v2d &F, v2d &Torque, int, int)
On screen information display.
Definition: Parameters.h:1176
RigidBodies_< d > RigidBodies
Handle all the rigid bodies.
Definition: Parameters.h:210
void perform_PBCLE(v1d &X, v1d &V, uint32_t &PBCFlag)
Definition: Parameters.h:335
size_t xml_location
Temporary stores the already written locations in the xml, so that upon restart we can resume at the ...
Definition: Parameters.h:192
int tinfo
Show detail information on scren every this many timesteps.
Definition: Parameters.h:174
double Kt
Tangential spring constant.
Definition: Parameters.h:179
double Gamman
Normal dissipation.
Definition: Parameters.h:180
bool wallforcerequested
Compute for on the wall?
Definition: Parameters.h:203
double graddesc_gamma
Decay rate parameters for the gradient descent algorithm.
Definition: Parameters.h:205
void finalise()
Close opened dump files.
Definition: Parameters.h:1241
Parameters()
Definition: Parameters.h:130
string Directory
Saving directory.
Definition: Parameters.h:200
int savecsvcontact(FILE *out, ExportData outflags, Multiproc< d > &MP, cv2d &X)
Definition: Parameters.h:1427
double Kn
Normal spring constant.
Definition: Parameters.h:178
void load(Archive &ar)
Definition: Parameters.h:233
int dumphandling(int ti, double t, v2d &X, v2d &V, v1d &Vmag, v2d &A, v2d &Omega, v1d &OmegaMag, vector< uint32_t > &PBCFlags, v1d &Z, Multiproc< d > &MP)
Dump writing functions.
Definition: Parameters.h:1251
int set_boundaries()
Set default boundaries.
Definition: Parameters.h:308
double damping
Definition: Parameters.h:184
vector< bool > Frozen
Frozen atom if true.
Definition: Parameters.h:198
double dt
timestep
Definition: Parameters.h:176
void perform_PBC(v1d &X, uint32_t &PBCFlags)
Bring particle back in the simulation box if the grains cross the boundaries.
Definition: Parameters.h:322
vector< Mesh< d > > Meshes
Handle all meshes.
Definition: Parameters.h:211
multimap< float, string > events
For storing events. first is the time at which the event triggers, second is the event command string...
Definition: Parameters.h:216
Parameters(int NN)
Set the default values for all parameters. Calls to setup parameter function should be provided after...
Definition: Parameters.h:131
vector< double > m
Particle mass.
Definition: Parameters.h:195
double cellsize
Size of cells for contact detection.
Definition: Parameters.h:186
void reset_ND(int NN)
reset the full simulation.
Definition: Parameters.h:161
vector< Boundary< d > > Boundaries
List of boundaries. Second dimension is {min, max, length, type}.
Definition: Parameters.h:199
double Mu
Fricton.
Definition: Parameters.h:182
int init_inertia()
Initialise particle moment of inertia.
Definition: Parameters.h:436
void check_events(float time, v2d &X, v2d &V, v2d &Omega)
Verify if an event triggers at the current time time.
Definition: Parameters.h:466
double rho
density
Definition: Parameters.h:177
void add_particle()
Not implemented.
Definition: Parameters.h:855
bool wallforcecomputed
Compute for on the wall?
Definition: Parameters.h:204
void interpret_command(istream &in, v2d &X, v2d &V, v2d &Omega)
Parse input script commands.
Definition: Parameters.h:496
double graddesc_tol
Tolerance for the gradient descent algorithm.
Definition: Parameters.h:206
int init_mass()
Initialise particle mass.
Definition: Parameters.h:428
vector< double > I
Particule moment of inertia.
Definition: Parameters.h:196
vector< std::pair< ExportType, ExportData > > dumps
Vector linking dump file and data dumped.
Definition: Parameters.h:189
void init_locations(char *line, v2d &X, char *extras)
Set particle locations.
Definition: Parameters.h:861
void perform_MOVINGWALL()
Move the boundary wall if moving.
Definition: Parameters.h:369
int tdump
Write dump file every this many timesteps.
Definition: Parameters.h:173
double Gammat
Tangential dissipation.
Definition: Parameters.h:181
double Mu_wall
Definition: Parameters.h:183
unsigned char restart_flag
Definition: Parameters.h:214
Definition: RigidBody.h:48
std::vector< RigidBody< d > > RB
Definition: RigidBody.h:51
Static class to handle multi-dimensional mathematics, and more. It gets specialised for speed with te...
Definition: Tools.h:101
Definition: Xml.h:29
void emergencyclose()
Definition: Xml.cpp:183
void header(int dimension, string input)
Definition: Xml.cpp:38
void startTS(double ts)
Definition: Xml.cpp:56
streamoff get_file_location()
Definition: Xml.h:52
void writeArray(string name, vector< vector< double >> *x, int beg, int length, ArrayType t, EncodingType te=EncodingType::ascii)
Definition: Xml.cpp:68
void stopTS()
Definition: Xml.cpp:62
bool closebranch()
Definition: Xml.cpp:15
void save(Archive &ar) const
Definition: Xml.h:63
void openbranch(string name, vector< pair< string, string >> attributes)
Definition: Xml.cpp:4
void load(Archive &ar)
Definition: Xml.h:67
void close()
Definition: Xml.cpp:165
ofstream fic
Definition: Xml.h:60
namespace for Niels Lohmann
Definition: json.hpp:20203
Small class to handle number generator (ie. first:step:last syntax)
Definition: Parameters.h:62
int niter()
Definition: Parameters.h:94
void reset()
Definition: Parameters.h:93
void parse(std::string s)
Definition: Parameters.h:64
T cur()
Definition: Parameters.h:95
@ NONE
Definition: Coarsing.h:58
vector< vector< double > > v2d
Definition: Typedefs.h:10
static void savecsv(char path[], cv2d &X, cv1d &r, const vector< uint32_t > &PBCFlags, cv1d &Vmag, cv1d &OmegaMag, [[maybe_unused]] cv1d &Z)
Save the location and a few more informations in a CSV file.
Definition: Tools.h:380
ExportData & operator>>=(ExportData &w, int u)
Definition: Parameters.h:52
ExportData operator|(ExportData a, ExportData b)
Definition: Parameters.h:49
static void setzero(v2d &a)
Set a matrix to zero in-place.
Definition: Tools.h:117
ExportType & operator|=(ExportType &a, const ExportType b)
Definition: Parameters.h:47
ContactStrategies
Definition: Typedefs.h:22
ExportData operator~(ExportData a)
Definition: Parameters.h:50
static double skewnorm(cv1d &a)
Norm of a skew-symetric matrix.
Definition: Tools.h:125
ExportData
Definition: Parameters.h:46
static double InertiaMomentum(double R, double rho)
Compute the hypersphere moment of inertia.
Definition: Tools.h:865
@ radius
Definition: Typedefs.h:19
@ mass
Definition: Typedefs.h:19
ExportType
Definition: Parameters.h:45
#define STR_PROTECT(s)
Definition: Parameters.h:39
ContactModels
Definition: Typedefs.h:21
bool operator&(ExportType &a, ExportType b)
Definition: Parameters.h:54
auto contacts2array(ExportData exp, cv2d &X, Parameters< d > &P)
pack the contact data in a 2d array
Definition: Multiproc.h:568
const vector< double > cv1d
Definition: Typedefs.h:13
const vector< vector< double > > cv2d
Definition: Typedefs.h:14
ExportData & operator<<=(ExportData &w, int u)
Definition: Parameters.h:53
XMLWriter * xmlout
Definition: DEMND.cpp:22
ExportData & operator&=(ExportData &a, const ExportData b)
Definition: Parameters.h:51
vector< double > v1d
Definition: Typedefs.h:9
static double norm(const vector< double > &a)
Norm of a vector.
Definition: Tools.h:119
static double Volume(double R)
Compute the hypersphere volume.
Definition: Tools.h:853
std::istream & operator>>(std::istream &in, number_gen< T > &n)
Definition: Parameters.h:122
@ CELLS
Definition: Typedefs.h:22
@ OCTREE
Definition: Typedefs.h:22
@ NAIVE
Definition: Typedefs.h:22
@ HERTZ
Definition: Typedefs.h:21
@ HOOKE
Definition: Typedefs.h:21
@ ROTATINGSPHERE
uint d
int N
v2d Boundaries
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bfloat16() max(const bfloat16 &a, const bfloat16 &b)
Definition: BFloat16.h:576
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC bool() isnan(const bfloat16 &a)
Definition: BFloat16.h:480
EIGEN_CONSTEXPR Index first(const T &x) EIGEN_NOEXCEPT
Definition: IndexedViewHelper.h:81
svint32_t PacketXi __attribute__((arm_sve_vector_bits(EIGEN_ARM64_SVE_VL)))
Definition: PacketMath.h:33
static const symbolic::SymbolExpr< internal::symbolic_last_tag > last
Definition: IndexedViewHelper.h:38
auto get(const nlohmann::detail::iteration_proxy_value< IteratorType > &i) -> decltype(i.key())
Definition: json.hpp:5657
struct JsonValue json
Definition: json_parser.h:15
Definition: json.hpp:5678
int write_data(FILE *out, TensorInfos v, int d)
Definition: Vtk.h:73
FILE * open(char path[], int d)
Definition: Vtk.h:4
int write_points(FILE *out, cv2d &X, int d)
Definition: Vtk.h:16
int write_contactlines(FILE *out, cv2d &ids)
Definition: Vtk.h:25
int write_celldata(FILE *out, std::string name, cv2d &v, TensorType order, int idx, int N, int d)
Definition: Vtk.h:103
int write_dimension_data(FILE *out, cv2d &X, cv1d &r, int d, vector< Boundary< dd > > boundaries)
Definition: Vtk.h:47
void close(FILE *out)
Definition: Vtk.h:123
int start_celldata(FILE *out, int N, int Ncf)
Definition: Vtk.h:40
int start_pointdata(FILE *out, cv2d &X)
Definition: Vtk.h:34
const GenericPointer< typename T::ValueType > T2 value
Definition: pointer.h:1282
const GenericPointer< typename T::ValueType > T2 T::AllocatorType & a
Definition: pointer.h:1181
PUGI_IMPL_FN I min_element(I begin, I end, const Pred &pred)
Definition: pugixml.cpp:7604
Type
Type of JSON value.
Definition: rapidjson.h:644
unsigned int uint32_t
Definition: stdint.h:126
#define SEEK_CUR
Definition: zconf.h:512