Skip to content

Commit

Permalink
Update to Chrono 8ff3488
Browse files Browse the repository at this point in the history
  • Loading branch information
dariomangoni committed Mar 18, 2024
1 parent 525ca2a commit 7c66bd0
Show file tree
Hide file tree
Showing 65 changed files with 180 additions and 180 deletions.
6 changes: 3 additions & 3 deletions configuration_tests/cascade/demo_CAS_robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,9 +83,9 @@ int main(int argc, char* argv[]) {
// Note, In most CADs the Y axis is horizontal, but we want it vertical.
// So define a root transformation for rotating all the imported objects.
ChQuaternion<> rotation1;
rotation1.SetFromAngleX(-CH_C_PI_2); // 1: rotate 90 deg on X axis
rotation1.SetFromAngleX(-CH_PI_2); // 1: rotate 90 deg on X axis
ChQuaternion<> rotation2;
rotation2.SetFromAngleY(CH_C_PI); // 2: rotate 180 deg on vertical Y axis
rotation2.SetFromAngleY(CH_PI); // 2: rotate 180 deg on vertical Y axis
ChQuaternion<> tot_rotation = rotation2 * rotation1; // rotate on 1 then on 2, using quaternion product
ChFrameMoving<> root_frame(ChVector3d(0, 0, 0), tot_rotation);

Expand Down Expand Up @@ -309,7 +309,7 @@ int main(int argc, char* argv[]) {
body_base->AddMarker(my_marker_move);

ChQuaternion<> rot_on_x;
rot_on_x.SetFromAngleX(CH_C_PI_2);
rot_on_x.SetFromAngleX(CH_PI_2);
ChFrame<> frame_marker_move = ChFrame<>(VNULL, rot_on_x) >> frame_marker_wrist_hand;

my_marker_hand->ImposeAbsoluteTransform(frame_marker_wrist_hand);
Expand Down
4 changes: 2 additions & 2 deletions configuration_tests/fsi/demo_FSI_cylinderDrop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ void CreateSolidPhase(ChSystemSMC& sysMBS, ChSystemFsi& sysFSI) {
cylinder->EnableCollision(true);
cylinder->SetFixed(false);
chrono::utils::AddCylinderGeometry(cylinder.get(), cmaterial, cyl_radius, cyl_length, VNULL,
QuatFromAngleX(CH_C_PI_2));
QuatFromAngleX(CH_PI_2));
cylinder->GetCollisionModel()->SetSafeMargin(initSpace0);

cylinder->GetVisualShape(0)->SetColor(ChColor(0.65f, 0.20f, 0.10f));
Expand All @@ -184,7 +184,7 @@ void CreateSolidPhase(ChSystemSMC& sysMBS, ChSystemFsi& sysFSI) {
sysFSI.AddFsiBody(cylinder);

// Add BCE particles attached on the cylinder into FSI system
sysFSI.AddCylinderBCE(cylinder, ChFrame<>(VNULL, QuatFromAngleX(CH_C_PI_2)), cyl_radius, cyl_length,
sysFSI.AddCylinderBCE(cylinder, ChFrame<>(VNULL, QuatFromAngleX(CH_PI_2)), cyl_radius, cyl_length,
true);
}

Expand Down
4 changes: 2 additions & 2 deletions configuration_tests/gpu/demo_GPU_ballcosim.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ void runBallDrop(ChSystemGpuMesh& gpu_sys, ChGpuSimulationParameters& params) {
// Add a ball mesh to the GPU system
float ball_radius = 20.f;
float ball_density = params.sphere_density;
float ball_mass = 4.0f * (float)CH_C_PI * ball_radius * ball_radius * ball_radius * ball_density / 3.f;
float ball_mass = 4.0f * (float)CH_PI * ball_radius * ball_radius * ball_radius * ball_density / 3.f;
gpu_sys.AddMesh(GetChronoDataFile("models/sphere.obj"), ChVector3f(0), ChMatrix33<float>(ball_radius),
ball_mass);

Expand Down Expand Up @@ -269,7 +269,7 @@ int main(int argc, char* argv[]) {
double3 pos = {0, 0, 0};
double t0 = 0.5;
double freq = CH_C_PI / 4;
double freq = CH_PI / 4;
if (t > t0) {
pos.x = 0.1 * params.box_X * std::sin((t - t0) * freq);
Expand Down
4 changes: 2 additions & 2 deletions configuration_tests/mbs/demo_IRR_collisionNSC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,8 +124,8 @@ std::shared_ptr<ChBody> AddContainer(ChSystemNSC& sys) {
// .. a motor between mixer and truss

auto my_motor = chrono_types::make_shared<ChLinkMotorRotationSpeed>();
my_motor->Initialize(rotatingBody, floorBody, ChFrame<>(ChVector3d(0, 0, 0), QuatFromAngleAxis(CH_C_PI_2, VECT_X)));
auto mfun = chrono_types::make_shared<ChFunctionConst>(CH_C_PI / 4.0); // speed 45 deg/s
my_motor->Initialize(rotatingBody, floorBody, ChFrame<>(ChVector3d(0, 0, 0), QuatFromAngleAxis(CH_PI_2, VECT_X)));
auto mfun = chrono_types::make_shared<ChFunctionConst>(CH_PI / 4.0); // speed 45 deg/s
my_motor->SetSpeedFunction(mfun);
sys.AddLink(my_motor);

Expand Down
2 changes: 1 addition & 1 deletion configuration_tests/mbs/demo_IRR_invPendulum.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,7 @@ int main(int argc, char* argv[]) {
// Translational joint ground-cart
// -------------------------------
auto prismatic = chrono_types::make_shared<ChLinkLockPrismatic>();
prismatic->Initialize(ground, cart, ChFrame<>(ChVector3d(0, 0, 0), QuatFromAngleY(CH_C_PI_2)));
prismatic->Initialize(ground, cart, ChFrame<>(ChVector3d(0, 0, 0), QuatFromAngleY(CH_PI_2)));
system.AddLink(prismatic);

// Revolute joint cart-pendulum
Expand Down
6 changes: 3 additions & 3 deletions configuration_tests/mbs/demo_IRR_sliderCrank.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,8 +132,8 @@ int main(int argc,
// - a rotation of -90 degrees around x (z2y)
ChQuaternion<> y2x;
ChQuaternion<> z2y;
y2x.Q_from_AngAxis(-CH_C_PI/2, ChVector<>(0, 0, 1));
z2y.Q_from_AngAxis(-CH_C_PI/2, ChVector<>(1, 0, 0));
y2x.Q_from_AngAxis(-CH_PI/2, ChVector<>(0, 0, 1));
z2y.Q_from_AngAxis(-CH_PI/2, ChVector<>(1, 0, 0));

// Ground
ChSharedBodyPtr ground(new ChBody);
Expand Down Expand Up @@ -191,7 +191,7 @@ int main(int argc,
engine_ground_crank->Initialize(ground, crank, ChCoordsys<>(ChVector<>(0, 0, 0), z2y));
engine_ground_crank->Set_eng_mode(ChLinkEngine::ENG_MODE_SPEED);
if (ChSharedPtr<ChFunction_Const> mfun = engine_ground_crank->Get_spe_funct().DynamicCastTo<ChFunction_Const>())
mfun->Set_yconst(CH_C_PI);
mfun->Set_yconst(CH_PI);
system.AddLink(engine_ground_crank);
#else
// Revolute between ground and crank.
Expand Down
2 changes: 1 addition & 1 deletion configuration_tests/multicore/demo_MCORE_mixerSMC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ std::shared_ptr<ChBody> AddContainer(ChSystemMulticoreSMC* sys) {
// Create a motor between the two bodies, constrained to rotate at 90 deg/s
auto motor = chrono_types::make_shared<ChLinkMotorRotationAngle>();
motor->Initialize(mixer, bin, ChFrame<>(ChVector3d(0, 0, 0), ChQuaternion<>(1, 0, 0, 0)));
motor->SetAngleFunction(chrono_types::make_shared<ChFunctionRamp>(0, CH_C_PI / 2));
motor->SetAngleFunction(chrono_types::make_shared<ChFunctionRamp>(0, CH_PI / 2));
sys->AddLink(motor);

return mixer;
Expand Down
12 changes: 6 additions & 6 deletions configuration_tests/synchrono/demo_SYN_scm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -129,7 +129,7 @@ int main(int argc, char* argv[]) {
} else {
// Start odd vehicles staggered going up the west edge, driving east
initLoc = offset + ChVector3d(2.0 * (node_id - 1), -5.0 - 2.0 * (node_id - 1), 0.5);
initRot = QuatFromAngleZ(CH_C_PI / 2);
initRot = QuatFromAngleZ(CH_PI / 2);
curve_pts = {initLoc, initLoc + ChVector3d(0, 100, 0)};
}

Expand Down Expand Up @@ -259,13 +259,13 @@ int main(int argc, char* argv[]) {
ChQuaternion<> rotation = QUNIT;
const bool USE_ISO_VIEW = true;
if (USE_ISO_VIEW) {
ChQuaternion<> qA = QuatFromAngleAxis(35 * CH_C_DEG_TO_RAD, VECT_Y);
ChQuaternion<> qB = QuatFromAngleAxis(135 * CH_C_DEG_TO_RAD, VECT_Z);
ChQuaternion<> qA = QuatFromAngleAxis(35 * CH_DEG_TO_RAD, VECT_Y);
ChQuaternion<> qB = QuatFromAngleAxis(135 * CH_DEG_TO_RAD, VECT_Z);
rotation = rotation >> qA >> qB;
} else {
// Top down view
ChQuaternion<> qA = QuatFromAngleAxis(90 * CH_C_DEG_TO_RAD, VECT_Y);
ChQuaternion<> qB = QuatFromAngleAxis(180 * CH_C_DEG_TO_RAD, VECT_Z);
ChQuaternion<> qA = QuatFromAngleAxis(90 * CH_DEG_TO_RAD, VECT_Y);
ChQuaternion<> qB = QuatFromAngleAxis(180 * CH_DEG_TO_RAD, VECT_Z);
rotation = rotation >> qA >> qB;
}

Expand All @@ -275,7 +275,7 @@ int main(int argc, char* argv[]) {
chrono::ChFrame<double>(camera_loc, rotation), // offset pose
cam_res_width, // image width
cam_res_height, // image height
(float)CH_C_PI / 3 // FOV
(float)CH_PI / 3 // FOV
);

overhead_camera->SetName("Overhead Cam");
Expand Down
2 changes: 1 addition & 1 deletion configuration_tests/urdf/demo_PARSER_URDF_RoboSimian.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,7 +207,7 @@ int main(int argc, char* argv[]) {
vis->SetUseSkyBox(false);
vis->SetCameraAngleDeg(40.0);
vis->SetLightIntensity(1.0f);
vis->SetLightDirection(1.5 * CH_C_PI_2, CH_C_PI_4);
vis->SetLightDirection(1.5 * CH_PI_2, CH_PI_4);
vis->SetWireFrameMode(false);
vis->Initialize();

Expand Down
20 changes: 10 additions & 10 deletions configuration_tests/vsg/demo_VSG_assets.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ int main(int argc, char* argv[]) {
pathfloor->GetPathGeometry()->AddSubLine(mseg1);
ChLineSegment mseg2(ChVector3d(1, 3, 0), ChVector3d(2, 3, 0));
pathfloor->GetPathGeometry()->AddSubLine(mseg2);
ChLineArc marc1(ChCoordsys<>(ChVector3d(2, 3.5, 0)), 0.5, -CH_C_PI_2, CH_C_PI_2);
ChLineArc marc1(ChCoordsys<>(ChVector3d(2, 3.5, 0)), 0.5, -CH_PI_2, CH_PI_2);
pathfloor->GetPathGeometry()->AddSubLine(marc1);
pathfloor->SetColor(ChColor(0.0f, 0.5f, 0.8f));
floor->AddVisualShape(pathfloor);
Expand Down Expand Up @@ -138,7 +138,7 @@ int main(int argc, char* argv[]) {
// Attach also a 'cylinder' shape
auto cyl = chrono_types::make_shared<ChVisualShapeCylinder>(0.3, 0.7);
cyl->AddMaterial(orange_mat);
body->AddVisualShape(cyl, ChFrame<>(ChVector3d(2, 0.15, 0), QuatFromAngleX(CH_C_PI_2)));
body->AddVisualShape(cyl, ChFrame<>(ChVector3d(2, 0.15, 0), QuatFromAngleX(CH_PI_2)));
body->AddVisualShape(chrono_types::make_shared<ChVisualShapeSphere>(0.03), ChFrame<>(ChVector3d(2, -0.2, 0), QUNIT));
body->AddVisualShape(chrono_types::make_shared<ChVisualShapeSphere>(0.03), ChFrame<>(ChVector3d(2, +0.5, 0), QUNIT));

Expand All @@ -162,15 +162,15 @@ int main(int argc, char* argv[]) {
body->AddVisualShape(objmesh, ChFrame<>(ChVector3d(0, 0.0, 2)));
body->AddVisualShape(objmesh, ChFrame<>(ChVector3d(3, 0.0, 2.5)));
body->AddVisualShape(objmesh, ChFrame<>(ChVector3d(5, 0.0, 3)));
body->AddVisualShape(objmesh, ChFrame<>(ChVector3d(4, 0.0, -3), QuatFromAngleY(0.5 * CH_C_PI)));
body->AddVisualShape(objmesh, ChFrame<>(ChVector3d(0, 0.0, -5), QuatFromAngleY(CH_C_PI)));
body->AddVisualShape(objmesh, ChFrame<>(ChVector3d(-4, 0.0, -6), QuatFromAngleY(-CH_C_PI_4)));
body->AddVisualShape(objmesh, ChFrame<>(ChVector3d(4, 0.0, -3), QuatFromAngleY(0.5 * CH_PI)));
body->AddVisualShape(objmesh, ChFrame<>(ChVector3d(0, 0.0, -5), QuatFromAngleY(CH_PI)));
body->AddVisualShape(objmesh, ChFrame<>(ChVector3d(-4, 0.0, -6), QuatFromAngleY(-CH_PI_4)));

// Attach an array of boxes, each rotated to make a spiral
for (int j = 0; j < 20; j++) {
auto smallbox = chrono_types::make_shared<ChVisualShapeBox>(0.2, 0.2, 0.02);
smallbox->SetColor(ChColor(j * 0.05f, 1 - j * 0.05f, 0.0f));
ChMatrix33<> rot(QuatFromAngleY(j * 21 * CH_C_DEG_TO_RAD));
ChMatrix33<> rot(QuatFromAngleY(j * 21 * CH_DEG_TO_RAD));
ChVector3d pos = rot * ChVector3d(0.4, 0, 0) + ChVector3d(0, j * 0.02, 0);
body->AddVisualShape(smallbox, ChFrame<>(pos, rot));
}
Expand Down Expand Up @@ -297,12 +297,12 @@ int main(int argc, char* argv[]) {
vis->AddCamera(ChVector3d(-8, 8, -16));
vis->SetCameraAngleDeg(40);
vis->SetLightIntensity(1.0f);
vis->SetLightDirection(1.5 * CH_C_PI_2, CH_C_PI_4);
vis->AddGrid(0.5, 0.5, 12, 12, ChCoordsys<>(ChVector3d(0, -0.49, 0), QuatFromAngleX(CH_C_PI_2)),
vis->SetLightDirection(1.5 * CH_PI_2, CH_PI_4);
vis->AddGrid(0.5, 0.5, 12, 12, ChCoordsys<>(ChVector3d(0, -0.49, 0), QuatFromAngleX(CH_PI_2)),
ChColor(0.31f, 0.43f, 0.43f));

// add scenery objects, not bound to bodies
auto Zup = QuatFromAngleX(-CH_C_PI_2);
auto Zup = QuatFromAngleX(-CH_PI_2);

auto sceneMesh1 = chrono_types::make_shared<ChVisualShapeModelFile>();
sceneMesh1->SetFilename(GetChronoDataFile("models/red_teapot.obj"));
Expand Down Expand Up @@ -380,7 +380,7 @@ int main(int argc, char* argv[]) {
vis->WriteImageToFile(out_dir + "/newshot.png"); // does not work with frame == 0!
}

vis->UpdateVisualModel(teapotId1, ChFrame<>(ChVector3d(0, 3.5 + 0.5 * sin(CH_C_PI * time / 10), 3), Zup));
vis->UpdateVisualModel(teapotId1, ChFrame<>(ChVector3d(0, 3.5 + 0.5 * sin(CH_PI * time / 10), 3), Zup));
vis->UpdateVisualModel(teapotId2, ChFrame<>(ChVector3d(-5, 3.5, 3), Zup * QuatFromAngleY(time / 20)));
vis->UpdateVisualModel(boxId, ChFrame<>(ChVector3d(0, 0.01 * time, 0), QUNIT));
vis->UpdateVisualModel(ellId, ChFrame<>(ellPos, Zup * QuatFromAngleY(0.2 * time) * QuatFromAngleZ(0.1 * time)));
Expand Down
4 changes: 2 additions & 2 deletions misc/mpi_tests/demo_DEM_MPI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,8 +125,8 @@ void create_falling_items(ChSystemMPI& mySys, double prad, int n_bodies, double

void add_other_falling_item(ChSystemMPI& mySys, double prad, double box_dim, double rho, int n_curr_bodies) {
int id_offset = 10;
double m_s = (2 / 3) * CH_C_PI * pow(prad, 3) * rho;
double m_c = CH_C_PI * pow(prad, 2) * (2 * prad) * rho;
double m_s = (2 / 3) * CH_PI * pow(prad, 3) * rho;
double m_c = CH_PI * pow(prad, 2) * (2 * prad) * rho;
double m_cube = prad * prad * prad * rho;

ChVector<> pos1(0, prad, 0);
Expand Down
4 changes: 2 additions & 2 deletions misc/multicore_tests/test_NSC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ int max_iteration_sliding = 10000;

double radius = 0.0025 * UNIT_SCALE;
double density = 2500 / (UNIT_SCALE * UNIT_SCALE * UNIT_SCALE);
double mass = density * (4.0 / 3) * CH_C_PI * radius * radius * radius;
double mass = density * (4.0 / 3) * CH_PI * radius * radius * radius;
float COR = 0.9f;
float mu = 0.5f;

Expand Down Expand Up @@ -290,7 +290,7 @@ int main(int argc, char* argv[]) {
// align it with the Y axis of the global reference frame.

ChQuaternion<> z2y;
z2y.Q_from_AngX(-CH_C_PI / 2);
z2y.Q_from_AngX(-CH_PI / 2);

ChSharedPtr<ChLinkLockPrismatic> prismatic(new ChLinkLockPrismatic);
prismatic->Initialize(plate, ground, ChCoordsys<>(ChVector<>(0, 0, 0), z2y));
Expand Down
2 changes: 1 addition & 1 deletion misc/multicore_tests/test_ball.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ bool clamp_bilaterals = false;
double bilateral_clamp_speed = 0.1;

// Tilt angle (about global Y axis) of the container.
double tilt_angle = 45.0 * CH_C_PI / 180;
double tilt_angle = 45.0 * CH_PI / 180;

// Simulation duration
double end_simulation_time = 10;
Expand Down
4 changes: 2 additions & 2 deletions misc/multicore_tests/test_constraints.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ int main(int argc, char* argv[]) {
// Rotation of -90 degrees around z
ChVector<> zero(0, 0, 0);
ChQuaternion<> y2x(1, 0, 0, 0);
y2x.Q_from_AngAxis(-CH_C_PI / 2, ChVector<>(0, 0, 1));
y2x.Q_from_AngAxis(-CH_PI / 2, ChVector<>(0, 0, 1));

// ground
ChSharedPtr<ChBody> ground(new ChBody(new ChCollisionModelParallel, ChBody::DEM));
Expand Down Expand Up @@ -117,7 +117,7 @@ int main(int argc, char* argv[]) {
////engine_ground_crank->Initialize(ground_, crank_, ChCoordsys<>(ChVector<>(0,0,0)));
////engine_ground_crank->Set_eng_mode(ChLinkEngine::ENG_MODE_SPEED);
////if (ChFunction_Const* mfun = dynamic_cast<ChFunction_Const*>(engine_ground_crank->Get_spe_funct()))
//// mfun->Set_yconst(CH_C_PI); // speed w=3.145 rad/sec
//// mfun->Set_yconst(CH_PI); // speed w=3.145 rad/sec
////msystem->AddLink(engine_ground_crank);

// Revolute between ground and crank
Expand Down
2 changes: 1 addition & 1 deletion misc/multicore_tests/test_fill.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -445,7 +445,7 @@ int main(int argc, char* argv[]) {
force = -calculateContactForceOnBody(msystem, 0);
}
double actualWeight =
(msystem->Get_bodylist()->size() - 1) * (4.0 / 3.0) * CH_C_PI * pow(r_g, 3.0) * rho_g * gravity;
(msystem->Get_bodylist()->size() - 1) * (4.0 / 3.0) * CH_PI * pow(r_g, 3.0) * rho_g * gravity;

// get maximum body velocity
double maxVelocity = 0;
Expand Down
4 changes: 2 additions & 2 deletions misc/multicore_tests/test_mesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,10 @@ int main(int argc, char* argv[]) {
ChVector<> initVel2(0, 0, 0);

ChQuaternion<> initRot1(1, 0, 0, 0);
initRot1.Q_from_AngAxis(CH_C_PI / 4, ChVector<>(1 / sqrt(2.0), 1 / sqrt(2.0), 0));
initRot1.Q_from_AngAxis(CH_PI / 4, ChVector<>(1 / sqrt(2.0), 1 / sqrt(2.0), 0));

ChQuaternion<> initRot2(1, 0, 0, 0);
initRot2.Q_from_AngAxis(CH_C_PI / 4, ChVector<>(-1 / sqrt(2.0), -1 / sqrt(2.0), 0));
initRot2.Q_from_AngAxis(CH_PI / 4, ChVector<>(-1 / sqrt(2.0), -1 / sqrt(2.0), 0));

// -------------
// Create system
Expand Down
2 changes: 1 addition & 1 deletion misc/multicore_tests/test_scaling.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ int max_iteration = 20;
// Parameters for the mixture balls
double radius = 0.1;
double density = 2000;
double vol = (4.0 / 3) * CH_C_PI * radius * radius * radius;
double vol = (4.0 / 3) * CH_PI * radius * radius * radius;
double mass = density * vol;
ChVector<> inertia = 0.4 * mass * radius * radius * ChVector<>(1, 1, 1);

Expand Down
2 changes: 1 addition & 1 deletion misc/multicore_tests/test_timing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ int max_iteration = 50;
// Parameters for the mixture balls
double radius = 0.1;
double density = 2000;
double vol = (4.0 / 3) * CH_C_PI * radius * radius * radius;
double vol = (4.0 / 3) * CH_PI * radius * radius * radius;
double mass = density * vol;
ChVector<> inertia = 0.4 * mass * radius * radius * ChVector<>(1, 1, 1);

Expand Down
2 changes: 1 addition & 1 deletion misc/multicore_tests/test_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ void checkGenerators() {
int ballId = 100;
double radius = .1;
double density = 2000;
double volume = (4.0 / 3) * CH_C_PI * radius * radius * radius;
double volume = (4.0 / 3) * CH_PI * radius * radius * radius;
double mass = density * volume;
ChVector<> inertia = 0.4 * mass * radius * radius * ChVector<>(1, 1, 1);
ChVector<> init_vel(0, 0, 0);
Expand Down
6 changes: 3 additions & 3 deletions projects/constraint_fluids/test_CNFL_humvee_water_tank.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@ double hthick = 0.1;
int Id_g = 100;
double r_g = 0.02;
double rho_g = 2500;
double vol_g = (4.0 / 3) * CH_C_PI * r_g * r_g * r_g;
double vol_g = (4.0 / 3) * CH_PI * r_g * r_g * r_g;
double mass_g = rho_g * vol_g;
ChVector<> inertia_g = 0.4 * mass_g * r_g * r_g * ChVector<>(1, 1, 1);

Expand Down Expand Up @@ -526,8 +526,8 @@ int main(int argc, char* argv[]) {
}

for (int j = 0; j < 30; j++) {
ChQuaternion<> qq = Q_from_AngAxis(j * 12 * CH_C_DEG_TO_RAD, VECT_Y);
ChVector<> ppp = ChVector<>(sin(12 * CH_C_DEG_TO_RAD * j), 0, cos(12 * CH_C_DEG_TO_RAD * j)) * .6;
ChQuaternion<> qq = Q_from_AngAxis(j * 12 * CH_DEG_TO_RAD, VECT_Y);
ChVector<> ppp = ChVector<>(sin(12 * CH_DEG_TO_RAD * j), 0, cos(12 * CH_DEG_TO_RAD * j)) * .6;

utils::AddBoxGeometry(m_chassis.get(), material, hdim, ppp + ChVector<>(-1.9306 + .24, 0, 1.3011), qq);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ double hthick = 0.25;
int Id_g = 100;
double r_g = 0.02;
double rho_g = 2500;
double vol_g = (4.0 / 3) * CH_C_PI * r_g * r_g * r_g;
double vol_g = (4.0 / 3) * CH_PI * r_g * r_g * r_g;
double mass_g = rho_g * vol_g;
ChVector<> inertia_g = 0.4 * mass_g * r_g * r_g * ChVector<>(1, 1, 1);

Expand Down
2 changes: 1 addition & 1 deletion projects/core_tests/test_CH_function_recorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
using namespace chrono;

double Reference(double x) {
return std::cos(x * CH_C_2PI);
return std::cos(x * CH_2PI);
}

void Evaluate(const ChFunctionInterp& fun, double x) {
Expand Down
4 changes: 2 additions & 2 deletions projects/core_tests/test_CH_integratorHHT.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class OscillatorProblem : public ChIntegrableIIorder {
}

/// number of coordinates in the state, x position part:
virtual unsigned int GetNumCoordsPosLevel() override { return 1; }
virtual unsigned int GetNumCoordsPosLevel() const override { return 1; }

/// number of coordinates in the state, x position part:
virtual unsigned int GetNumCoordsVelLevel() override { return 1; }
Expand Down Expand Up @@ -178,7 +178,7 @@ class PendulumProblem : public ChIntegrableIIorder {
}

/// number of coordinates in the state, x position part:
virtual unsigned int GetNumCoordsPosLevel() override { return 2; }
virtual unsigned int GetNumCoordsPosLevel() const override { return 2; }

/// number of coordinates at velocity level
virtual unsigned int GetNumCoordsVelLevel() override { return 2; }
Expand Down
Loading

0 comments on commit 7c66bd0

Please sign in to comment.