3 #include "chrono/physics/ChSystemSMC.h"
4 #include "chrono/physics/ChSystem.h"
5 #include "chrono/timestepper/ChTimestepper.h"
6 #include "chrono/solver/ChSolverPMINRES.h"
7 #include "chrono/core/ChTransform.h"
8 #include "chrono/physics/ChLinkSpring.h"
9 #include "chrono/geometry/ChTriangleMeshConnected.h"
14 using namespace chrono::collision;
24 void step(
double proteus_dt,
int n_substeps);
25 void setDirectory(std::string dir);
26 void setTimestepperType(std::string tstype,
bool verbose);
27 void setCollisionEnvelopeMargin(
double envelope,
double margin);
28 void addMesh(std::shared_ptr<ChMesh> mesh);
65 std::shared_ptr<ChLinkSpring>
spring;
68 shared_ptr<ChTriangleMeshConnected>
trimesh;
70 std::shared_ptr<ChBody>
body;
73 ChVector<double> hxyz(
double* x,
double t);
74 double hx(
double* x,
double t);
75 double hy(
double* x,
double t);
76 double hz(
double* x,
double t);
77 void calculate_init();
78 void prestep(
double* force,
double* torque);
80 void setConstraints(
double* free_x,
double* free_y);
81 void addSpring(
double stiffness,
86 void addPrismaticLinksWithSpring(
double* pris1,
91 void addPrismaticLinkX(
double* pris1);
92 void setName(std::string name);
93 void setPrescribedMotionPoly(
double coeff1);
94 void setPrescribedMotionSine(
double a,
double f);
95 void setPrescribedMotionCustom(std::vector<double> t, std::vector<double> x,
96 std::vector<double> y, std::vector<double>
z,
97 std::vector<double> ang, std::vector<double> ang2,
98 std::vector<double> ang3,
double t_max);
99 void getTriangleMeshSDF(ChVector<> pos_node,
101 void getTriangleMeshVel(
double *x,
104 void updateTriangleMeshVisualisationPos();
112 chrono_dt = 0.000001;
134 if (tstype ==
"HHT") {
135 system->SetTimestepperType(ChTimestepper::Type::HHT);
136 auto mystepper = std::dynamic_pointer_cast<ChTimestepperHHT>(system->GetTimestepper());
137 mystepper->SetAlpha(-0.2);
138 mystepper->SetMaxiters(10);
139 mystepper->SetAbsTolerances(1e-6);
140 mystepper->SetMode(ChTimestepperHHT::POSITION);
141 mystepper->SetScaling(
false);
142 mystepper->SetVerbose(verbose);
143 mystepper->SetModifiedNewton(
false);
145 else if (tstype ==
"Euler") {
146 system->SetTimestepperType(ChTimestepper::Type::EULER_IMPLICIT_LINEARIZED);
148 else if (tstype ==
"Trapezoidal") {
149 system->SetTimestepperType(ChTimestepper::Type::TRAPEZOIDAL);
155 double dt2 = proteus_dt/(double)n_substeps;
156 for (
int i = 0; i < n_substeps; ++i) {
157 system->DoStepDynamics(dt2);
169 body = chrono_types::make_shared<ChBody>();
178 free_x = ChVector<>(1., 1., 1.);
179 free_r = ChVector<>(1., 1., 1.);
191 ChVector<double> local = ChTransform<double>::TransformParentToLocal(
trimesh_pos0[i],
194 ChVector<double> xNew = ChTransform<double>::TransformLocalToParent(local,
204 ChVector<double> xx = ChVector<double>(x[0], x[1], x[2]);
205 ChVector<double> local = ChTransform<double>::TransformParentToLocal(xx,
pos_last,
rotq_last);
206 ChVector<double> xNew = ChTransform<double>::TransformLocalToParent(local,
pos,
rotq);
212 collision::ChCollisionModel::SetDefaultSuggestedEnvelope(envelope);
213 collision::ChCollisionModel::SetDefaultSuggestedMargin(margin);
219 ChVector<double> local = ChTransform<double>::TransformParentToLocal(ChVector<double>(x[0],x[1],x[2]),
pos_last,
rotq_last);
220 ChVector<double> xNew = ChTransform<double>::TransformLocalToParent(local,
pos,
rotq);
221 return xNew.x() - x[0];
227 ChVector<double> local = ChTransform<double>::TransformParentToLocal(ChVector<double>(x[0],x[1],x[2]),
pos_last,
rotq_last);
228 ChVector<double> xNew = ChTransform<double>::TransformLocalToParent(local,
pos,
rotq);
229 return xNew.y() - x[1];
235 ChVector<double> local = ChTransform<double>::TransformParentToLocal(ChVector<double>(x[0],x[1],x[2]),
pos_last,
rotq_last);
236 ChVector<double> xNew = ChTransform<double>::TransformLocalToParent(local,
pos,
rotq);
237 return xNew.z() - x[2];
246 auto trimesh_coords =
trimesh->getCoordsVertices();
247 for (
int i = 0; i < trimesh_coords.size(); i++) {
248 trimesh_pos0.push_back(ChVector<double>(trimesh_coords[i].x(),
249 trimesh_coords[i].y(),
250 trimesh_coords[i].
z()));
251 trimesh_pos.push_back(ChVector<double>(trimesh_coords[i].x(),
252 trimesh_coords[i].y(),
253 trimesh_coords[i].
z()));
274 body->Empty_forces_accumulators();
276 double forceG[3]={0.,0.,0.};
280 body->Accumulate_force(ChVector<double>(forceG[0]+force[0]*
free_x.x(),
281 forceG[1]+force[1]*
free_x.y(),
282 forceG[2]+force[2]*
free_x.z()),
285 body->Accumulate_torque(ChVector<double>(torque[0]*
free_r.x(),
290 double spring_length =
spring->Get_SpringLength();
292 spring->SetDisabled(
true);
295 spring->SetDisabled(
false);
311 F =
body->Get_accumulated_force();
312 M =
body->Get_accumulated_torque();
315 if (lock_motion_t_max < t && lock_motion->IsDisabled() ==
false) {
322 std::vector<double> x,
323 std::vector<double> y,
324 std::vector<double>
z,
325 std::vector<double> ang,
326 std::vector<double> ang2,
327 std::vector<double> ang3,
329 auto fixed_body = chrono_types::make_shared<ChBody>();
330 fixed_body->SetPos(
body->GetPos());
331 fixed_body->SetBodyFixed(
true);
333 lock_motion = chrono_types::make_shared<ChLinkLockLock>();
338 auto forced_motion = chrono_types::make_shared<ChFunction_Recorder>();
339 for (
int i = 0; i < x.size(); i++) {
340 forced_motion->AddPoint(t[i], x[i]);
342 std::shared_ptr<ChFunction> forced_ptr = forced_motion;
346 auto forced_motion = chrono_types::make_shared<ChFunction_Recorder>();
347 for (
int i = 0; i < y.size(); i++) {
348 forced_motion->AddPoint(t[i], y[i]);
350 std::shared_ptr<ChFunction> forced_ptr = forced_motion;
354 auto forced_motion = chrono_types::make_shared<ChFunction_Recorder>();
355 for (
int i = 0; i <
z.size(); i++) {
356 forced_motion->AddPoint(t[i],
z[i]);
358 std::shared_ptr<ChFunction> forced_ptr = forced_motion;
361 if (ang.size() > 0) {
362 auto forced_motion = chrono_types::make_shared<ChFunction_Recorder>();
363 for (
int i = 0; i < ang.size(); i++) {
364 forced_motion->AddPoint(t[i], ang[i]);
366 std::shared_ptr<ChFunction> forced_ptr = forced_motion;
369 if (ang2.size() > 0) {
370 auto forced_motion = chrono_types::make_shared<ChFunction_Recorder>();
371 for (
int i = 0; i < ang2.size(); i++) {
372 forced_motion->AddPoint(t[i], ang2[i]);
374 std::shared_ptr<ChFunction> forced_ptr = forced_motion;
377 if (ang3.size() > 0) {
378 auto forced_motion = chrono_types::make_shared<ChFunction_Recorder>();
379 for (
int i = 0; i < ang3.size(); i++) {
380 forced_motion->AddPoint(t[i], ang3[i]);
382 std::shared_ptr<ChFunction> forced_ptr = forced_motion;
388 auto fixed_body = chrono_types::make_shared<ChBody>();
389 fixed_body->SetPos(
body->GetPos());
390 fixed_body->SetBodyFixed(
true);
392 auto lock = chrono_types::make_shared<ChLinkLockLock>();
393 lock->Initialize(
body, fixed_body, fixed_body->GetCoord());
395 auto forced_motion = chrono_types::make_shared<ChFunction_Poly>();
396 forced_motion->Set_order(1);
397 forced_motion->Set_coeff(coeff1, 1);
398 std::shared_ptr<ChFunction> forced_ptr = forced_motion;
399 lock->SetMotion_X(forced_ptr);
404 auto fixed_body = chrono_types::make_shared<ChBody>();
405 fixed_body->SetPos(
body->GetPos());
406 fixed_body->SetBodyFixed(
true);
408 auto lock = chrono_types::make_shared<ChLinkLockLock>();
409 lock->Initialize(
body, fixed_body, fixed_body->GetCoord());
411 auto forced_motion = chrono_types::make_shared<ChFunction_Sine>();
412 forced_motion->Set_amp(a);
413 forced_motion->Set_freq(
f);
414 std::shared_ptr<ChFunction> forced_ptr = forced_motion;
415 lock->SetMotion_X(forced_ptr);
419 free_x = ChVector<>(free_x_in[0], free_x_in[1], free_x_in[2]);
420 free_r = ChVector<>(free_r_in[0], free_r_in[1], free_r_in[2]);
430 spring = chrono_types::make_shared<ChLinkSpring>();
431 std::shared_ptr<ChBody> anchor_body = chrono_types::make_shared<ChBody>();
432 anchor_body->SetPos(ChVector<>(anchor[0], anchor[1], anchor[2]));
433 anchor_body->SetBodyFixed(
true);
438 ChVector<>(fairlead[0], fairlead[1], fairlead[2]),
439 ChVector<>(0.,0.,0.),
442 spring->Set_SpringK(stiffness);
443 spring->Set_SpringR(damping);
449 auto mybod2 = chrono_types::make_shared<ChBody>();
450 mybod2->SetName(
"PRIS1");
451 mybod2->SetPos(ChVector<>(pris1[0], pris1[1], pris1[2]));
452 mybod2->SetMass(0.00001);
453 mybod2->SetBodyFixed(
true);
455 auto mylink1 = chrono_types::make_shared<ChLinkLockPrismatic>();
456 auto mycoordsys1 = ChCoordsys<>(mybod2->GetPos(),Q_from_AngAxis(CH_C_PI/2., VECT_Y));
457 mylink1->Initialize(mybod2,
body, mycoordsys1);
468 auto fairlead = chrono_types::make_shared<ChBody>();
469 fairlead->SetName(
"PRIS3");
470 fairlead->SetPos(
body->GetPos());
471 fairlead->SetMass(0.00001);
473 auto mybod2 = chrono_types::make_shared<ChBody>();
474 mybod2->SetName(
"PRIS1");
475 mybod2->SetPos(ChVector<>(pris1[0], pris1[1], pris1[2]));
476 mybod2->SetMass(0.00001);
480 auto mybod3 = chrono_types::make_shared<ChBody>();
481 mybod3->SetName(
"PRIS2");
482 mybod3->SetPos(ChVector<>(pris2[0], pris2[1], pris2[2]));
483 mybod3->SetBodyFixed(
true);
486 auto mylink1 = chrono_types::make_shared<ChLinkLockPrismatic>();
488 auto mycoordsys1 = ChCoordsys<>(mybod2->GetPos(),Q_from_AngAxis(CH_C_PI/2., VECT_Y));
489 mylink1->Initialize(fairlead, mybod2, mycoordsys1);
493 auto mylink2 = chrono_types::make_shared<ChLinkLockPrismatic>();
495 auto mycoordsys2 = ChCoordsys<>(mybod3->GetPos(),Q_from_AngAxis(CH_C_PI/2., VECT_X));
496 mylink2->Initialize(mybod2, mybod3,mycoordsys2);
498 auto mylink3 = chrono_types::make_shared<ChLinkLockSpherical>();
502 mylink3->Initialize(fairlead,
body,
false, fairlead->GetCoord(),
body->GetCoord());
506 spring = chrono_types::make_shared<ChLinkSpring>();
507 spring->Initialize(fairlead,
510 ChVector<>(0.,0.,0.),
511 ChVector<>(0.,0.,0.),
514 spring->Set_SpringK(stiffness);
515 spring->Set_SpringR(damping);
516 spring->SetName(
"SPRING1");
521 body->SetNameString(name);
526 auto xxs =
trimesh->getCoordsVertices();
527 auto nns =
trimesh->getCoordsNormals();
529 double min_dist=1e10;
531 for (
int i = 0; i < xxs.size(); i++) {
532 dist_vec =
pos-xxs[i];
533 dist = dist_vec.Length();
534 if (dist < min_dist) {
537 if (dist_vec.Dot(nns[i]) > 0) {
541 min_dist = -min_dist;
544 dist_n[0] = min_dist;
547 dist_n[1] = dist_vec[0];
548 dist_n[1] = dist_vec[1];
549 dist_n[2] = dist_vec[2];
555 auto xxs =
trimesh->getCoordsVertices();
556 auto nns =
trimesh->getCoordsNormals();
557 double min_dist = 1e10;
558 ChVector<> p(x[0], x[1], x[2]);
559 ChVector<> d_vector(0.0);
562 int node_closest = -1;
563 for (
int i = 0; i < xxs.size(); i++) {
564 double dist = (p - xxs[i]).Length();
565 if (dist < min_dist) {
570 if (node_closest != -1) {
572 vel[0] = ddlast.x()/dt;
573 vel[1] = ddlast.y()/dt;
574 vel[2] = ddlast.z()/dt;
594 std::shared_ptr<ChBody> body2,
595 std::shared_ptr<ChSystem> system,
596 ChCoordsys<> coordsys,
602 double limit_Rz=0.) {
603 auto mylink = chrono_types::make_shared<ChLinkLock>();
604 system->AddLink(mylink);
605 auto chlimit_X = mylink->GetLimit_X();
606 chlimit_X.SetActive(
true);
607 chlimit_X.SetMax(limit_X);
608 auto chlimit_Y = mylink->GetLimit_Y();
609 chlimit_Y.SetActive(
true);
610 chlimit_Y.SetMax(limit_Y);
611 auto chlimit_Z = mylink->GetLimit_Z();
612 chlimit_Z.SetActive(
true);
613 chlimit_Z.SetMax(limit_Z);
614 auto chlimit_Rx = mylink->GetLimit_Rx();
615 chlimit_Rx.SetMax(limit_Rx);
616 chlimit_Rx.SetActive(
true);
617 auto chlimit_Ry = mylink->GetLimit_Ry();
618 chlimit_Ry.SetActive(
true);
619 chlimit_Ry.SetMax(limit_Ry);
620 auto chlimit_Rz = mylink->GetLimit_Rz();
621 chlimit_Rz.SetActive(
true);
622 chlimit_Rz.SetMax(limit_Rz);
623 mylink->Initialize(body1, body2, coordsys);
632 std::shared_ptr<ChPhysicsItem> sp(item,
no_op_delete());
635 static std::map<ChPhysicsItem*, std::shared_ptr<ChPhysicsItem>> spans;
638 std::shared_ptr<ChPhysicsItem> sp = spans.at(item);