Hi Wing, I think I know what happened and it was my mistake. I transformed the angular velocity vector as a position vector when it really should be transformed as a direction vector.
In other words, instead of: top1->SetAngVelParent(X_G1 * ChVector3d(0, omega1, 0)); I should have used: top1->SetAngVelParent(X_G1.GetRotMat() * ChVector3d(0, omega1, 0)); I’ll push the fix to demo_MBS_spinning_tops a little bit later with a couple of other commits. In the meantime, please check that the above fixes the problem. Best, Radu From: [email protected] <[email protected]> On Behalf Of kuwt Sent: Tuesday, January 13, 2026 11:45 AM To: ProjectChrono <[email protected]> Subject: Re: [chrono] Re: Simulation of spinning top collision Hello Radu, Thank you again for your help. Using the approach from the new demo, the spinningTop5 spins more "properly". But there is still a problem. Here in these example, i used spinningTop1 and spinningTop2. In 12_proper.mp4, i use the following code: auto top1 = chrono_types::make_shared<ChBodyEasyMesh>("../resource/spinningTop1.obj", 7000, true, true, true,contact_mat, 0.005); top1->SetFrameRefToAbs(ChFramed(ChVector3d(3, 0, 0), QuatFromAngleX(CH_PI_2))); top1->SetAngVelLocal(ChVector3d(0, 0, omega1)); sys.Add(top1); auto top2 = chrono_types::make_shared<ChBodyEasyMesh>("../resource/spinningTop2.obj", 7000, true, true, true, contact_mat, 0.005); top2->SetFrameRefToAbs(ChFramed(ChVector3d(-3, 0, 0), QuatFromAngleX(CH_PI_2))); top2->SetAngVelLocal(ChVector3d(0, 0, omega2)); sys.Add(top2); Focusing in the first few seconds of the video before the tops drop to the floor, we can see the spinning top rotates exactly with the thin rod as the spinning axis. This is the desired behaviour. In 12_swirling.mp4, i use the following code: auto top1 = chrono_types::make_shared<ChBodyEasyMesh>("../resource/spinningTop1.obj", 7000, true, true, true,contact_mat, 0.005); ChFramed X_G1 = ChFramed(ChVector3d(3, 0, 0), QuatFromAngleX(CH_PI_2)); top1->SetFrameRefToAbs(X_G1); top1->SetAngVelParent(X_G1 * ChVector3d(0, omega1, 0)); sys.Add(top1); auto top2 = chrono_types::make_shared<ChBodyEasyMesh>("../resource/spinningTop2.obj", 7000, true, true, true, contact_mat, 0.005); ChFramed X_G2 = ChFramed(ChVector3d(-3, 0, 0), QuatFromAngleX(CH_PI_2)); top2->SetFrameRefToAbs(X_G2); top2->SetAngVelParent(X_G2 * ChVector3d(0, omega2, 0)); sys.Add(top2); Before the tops drop to the floor, we can see that the spinning top rotates along an axis slightly different from the thin rod. By placing the tops farther from each other (x=6 and -6 instead) initially(12_swirling_farther.mp4), the spinning axis shifts farther away. I suspect the cause might be the order when we apply translation and rotation. I would like to know if the body reference frame you mentioned before is the frame that I define the mesh in the obj file. Regards, Wing On Monday, 12 January 2026 at 16:22:44 UTC+1 Radu Serban wrote: Hi Wing, This problem is similar to the previous one about using SetFrameRefToAbs instead of SetPos. Just like SetPos and SetRot, the function SetAngVelLocal expects an angular velocity expressed in the centroidal reference frame. However, the centroidal reference frame is calculated internally in the ChBodyEasyMesh constructor and may end up rotated relative to the body reference frame. What you want is to specify the angular velocity relative to the body reference frame. You can either convert the desired angular velocity from the body reference frame to the body centroidal frame (using the transform returned by GetFrameCOMToRef) or else convert the desired angular velocity from the body reference frame to the global frame and set it using SetAngVelParent. I pushed a new demo based on your code and there I adopted the 2nd approach. See demo_MBS_spinning_tops<https://urldefense.com/v3/__https:/github.com/projectchrono/chrono/blob/main/src/demos/mbs/demo_MBS_spinning_tops.cpp__;!!Mak6IKo!KuRTx_feSB0fz7sTdnyP4kidta3RfUecFIdDjhg2oqUkIZJKzhIwmAc4eiR0nt4khcPol5Yfqo1khzc$>. One more reason to change how one specifies initial position and velocity in Chrono. The current API is a continuous source of confusion. Best, Radu From: [email protected] <[email protected]> On Behalf Of kuwt Sent: Monday, January 12, 2026 2:33 PM To: ProjectChrono <[email protected]> Subject: Re: [chrono] Re: Simulation of spinning top collision Hello Radu, I want the tops to spin with the thin tip as the spinning axis. But now spinningTop5 is spinning with another axis (see bad2.mp4 which shows the motion more slowly). I am now using the following code(whole code spinningtop.cpp) to set the initial top orientation and its local angular speed, which already used SetFrameRefToAbs. The problem of wrong orientation only happens for the top spinningTop5.obj. I suspect there might be some calculations that automatically align the the top in a different way when I load the obj file to project chrono. auto falling1 = chrono_types::make_shared<ChBodyEasyMesh>("../resource/spinningTop5.obj", 7000, true, true, true,contact_mat, 0.005); falling1->SetFrameRefToAbs(ChFramed(ChVector3d(3, 0, 0), QuatFromAngleX(CH_PI_2))); falling1->SetAngVelLocal(ChVector3d(0, 0, omg1)); sys.Add(falling1); auto falling2 = chrono_types::make_shared<ChBodyEasyMesh>("../resource/spinningTop6.obj", 7000, true, true, true, contact_mat, 0.005); falling2->SetFrameRefToAbs(ChFramed(ChVector3d(-3, 0, 0), QuatFromAngleX(CH_PI_2))); falling2->SetAngVelLocal(ChVector3d(0, 0, omg2)); sys.Add(falling2); On Monday, 12 January 2026 at 13:54:11 UTC+1 Radu Serban wrote: Wei, It is not clear to me how you want these new tops to be oriented and spin. Right now, it looks like the top on the right hits the platform with its thin tip with large velocity (dure to its off-axis angular velocity). Use the code I provided to properly set the initial top orientation and its local angular speed. --Radu From: [email protected] <[email protected]> On Behalf Of kuwt Sent: Monday, January 12, 2026 1:15 PM To: ProjectChrono <[email protected]> Subject: Re: [chrono] Re: Simulation of spinning top collision Hello Radu, I am glad that the demo can be available for everyone. For the installation issue, I believe my vulkan version is too old (see figure buildchrono.png) so when I build chrono with vsg on then it gives me this error. Because I am not familiar with vulkan so I cannot fix it now. For the simulation, I encounter new problems (bad.mp4). Here in the simulation, I use two other spinning tops(spinningTop5.obj and spinningTop6.obj). They are oriented such that the y-axis is spinning axis(spinningtop5.png and spinningtop6.png), the same as my previous spinningTop1 and spinningTop2. However, now spinningTop5 are spinning in a weird way. Regards, Wing On Monday, 12 January 2026 at 11:34:57 UTC+1 Radu Serban wrote: Good to hear that, Wing. A couple of things: * I think this would make for a nice Chrono demo. Would you mind if I include it in the Chrono distribution and make it available to everyone? * Ubuntu 20.04 is indeed a bit old. I had no issues with VSG on 22.04 and 24.04. But we’re interested in knowing what prevents using Chrono::VSG on an older OS. Could you please provide some details on what problems you are encountering? Are you using an appropriate version of Vulkan? Are you using the buildVSG.sh script we provide with Chrono (see https://api.projectchrono.org/module_vsg_installation.html<https://urldefense.com/v3/__https:/api.projectchrono.org/module_vsg_installation.html__;!!Mak6IKo!MiTrB2jr4Hy_lFkI8FvT0CvVOYB5p4lH5MvW6P2Sc23EV8U81gEd4NwTzl3V96lNvhX3eVfatOXKj0g$>)? --Radu From: [email protected] <[email protected]> On Behalf Of kuwt Sent: Monday, January 12, 2026 11:26 AM To: ProjectChrono <[email protected]> Subject: Re: [chrono] Re: Simulation of spinning top collision Hello Radu, Thank you very much for your help. With the latest Chrono and the use of SetFrameRefToAbs, I manage to do a proper simulation (good.mp4). I am still using Irrlicht for the visualization since i am using an older version of ubuntu (20.04) and I encountered some problems installing Chrono::VSG. Wing On Friday, 9 January 2026 at 14:56:59 UTC+1 Radu Serban wrote: This is a cute simulation. >From the code you provided, I take it that you are using an older version of >Chrono. I just tried your code with the latest Chrono from the main git >branch, and I cannot reproduce the issue. Regarding your question about ChBodyEasMesh, note that this creates under the hood a ChBodyAuxRef (and not a ChBody). In that case, you probably want to control the pose of the reference frame with respect to the global frame. However, SetPos and SetRot actually affect the pose of the centroidal frame (relative to the global frame). I know that this is *very* confusing and it’s something I intend to change throughout Chrono whenever I will find the time. In the meantime, I suggest you * Use the latest code in the Chrono main branch * Switch to using Chrono::VSG for run-time visualization (better than Irrlicht) I attached a modification of your code where I * Changed the way the initial body poses are set * Used Chrono::VSG for run-time visualization * Flipped one of the spinning tops * Increased the initial angular velocities to 50 rad/s Let me know what you get. Radu From: [email protected] <[email protected]> On Behalf Of kuwt Sent: Friday, January 9, 2026 2:43 PM To: ProjectChrono <[email protected]> Subject: [chrono] Re: Simulation of spinning top collision Interestingly if I change the object from mesh to simple ChBodyEasyBox(as shown below). The weird attraction disappears(video a.mp4). I am not sure if I misunderstand anything for ChBodyEasyMesh. Forgot to mention that i'm using version release 9.0. // auto falling = chrono_types::make_shared<ChBodyEasyMesh>("../resource/spinningTop1.obj",7000,true,true,true,contact_mat,0.005); auto falling = chrono_types::make_shared<ChBodyEasyBox>(2,2,2,7000,true,true,contact_mat); falling->SetRot(QuatFromAngleY(180 * CH_DEG_TO_RAD)); falling->SetPos(ChVector3d(3, 0, 0)); falling->SetAngVelLocal(ChVector3d(0,0, 5)); sys.Add(falling); // auto falling2 = chrono_types::make_shared<ChBodyEasyMesh>( "../resource/spinningTop2.obj",7000,true,true,true,contact_mat,0.005); auto falling2 = chrono_types::make_shared<ChBodyEasyBox>(2,2,2,7000,true,true,contact_mat); falling2->SetRot(QuatFromAngleY(180 * CH_DEG_TO_RAD)); falling2->SetPos(ChVector3d(-3, 0, 0)); falling2->SetAngVelLocal(ChVector3d(0,0, 5)); sys.Add(falling2); On Thursday, 8 January 2026 at 15:05:36 UTC+1 kuwt wrote: Hello project chrono community, I want to simulate the collision of two spinning top using project chrono. However, I encounter a weird problem that the two spinning top goes towards each other. v0.mp4 is a video showing how they go towards each other.. v1.mp4 is a video showing another viewing angle. I release the two spinning top mid air with some angular velocity and let them drop to the floor. I expect they will go towards each other after they hit the floor but not during initially mid air. I inserted the object as shown in the following code script(whole minimal script attached as spinningtop2.cpp. The resources are attached too. I made the floor myself. The spinning tops are from github as mentioned in the code.): auto falling = chrono_types::make_shared<ChBodyEasyMesh>( "../resource/spinningTop1.obj",7000,true,true,true,contact_mat,0.005); falling->SetRot(QuatFromAngleY(180 * CH_DEG_TO_RAD)); falling->SetPos(ChVector3d(3, 0, 0)); falling->SetAngVelLocal(ChVector3d(0,0, 5)); sys.Add(falling); auto falling2 = chrono_types::make_shared<ChBodyEasyMesh>( "../resource/spinningTop2.obj",7000,true,true,true,contact_mat,0.005); falling2->SetRot(QuatFromAngleY(180 * CH_DEG_TO_RAD)); falling2->SetPos(ChVector3d(-3, 0, 0)); falling2->SetAngVelLocal(ChVector3d(0,0, 5)); sys.Add(falling2); auto floor = chrono_types::make_shared<ChBodyEasyMesh>( "../resource/floor.obj",7000,true,true,true,contact_mat,0.005); floor->SetPos(ChVector3d(0, 0, -3)); floor->SetFixed(true); sys.Add(floor); Does anybody know what I have misunderstood? Thank you. -- You received this message because you are subscribed to the Google Groups "ProjectChrono" group. To unsubscribe from this group and stop receiving emails from it, send an email to [email protected]. To view this discussion visit https://groups.google.com/d/msgid/projectchrono/c35f6ec9-0d9f-4311-8b8c-f09a3afdbb94n%40googlegroups.com<https://urldefense.com/v3/__https:/groups.google.com/d/msgid/projectchrono/c35f6ec9-0d9f-4311-8b8c-f09a3afdbb94n*40googlegroups.com?utm_medium=email&utm_source=footer__;JQ!!Mak6IKo!IURuo14tx79V4w0442j6WmjWXUdDLjbMh3Y44YSSYSxBO1TM1X5rt1x_f8gaOknaMcEc26tdMrCBs9k$>. -- You received this message because you are subscribed to the Google Groups "ProjectChrono" group. To unsubscribe from this group and stop receiving emails from it, send an email to [email protected]. To view this discussion visit https://groups.google.com/d/msgid/projectchrono/29a899b2-e402-4de5-8978-840e0ee4b4fan%40googlegroups.com<https://urldefense.com/v3/__https:/groups.google.com/d/msgid/projectchrono/29a899b2-e402-4de5-8978-840e0ee4b4fan*40googlegroups.com?utm_medium=email&utm_source=footer__;JQ!!Mak6IKo!PwoZl-FfH7V09tKxZyiofSUK3E8jrXdLPBMczcpsOrk9hoiX_7tt8MpCa4tnPi6-jW-hLyMnhU_5fkI$>. -- You received this message because you are subscribed to the Google Groups "ProjectChrono" group. To unsubscribe from this group and stop receiving emails from it, send an email to [email protected]. To view this discussion visit https://groups.google.com/d/msgid/projectchrono/14e31e7c-3365-4547-96b5-ec90ca59296dn%40googlegroups.com<https://urldefense.com/v3/__https:/groups.google.com/d/msgid/projectchrono/14e31e7c-3365-4547-96b5-ec90ca59296dn*40googlegroups.com?utm_medium=email&utm_source=footer__;JQ!!Mak6IKo!MiTrB2jr4Hy_lFkI8FvT0CvVOYB5p4lH5MvW6P2Sc23EV8U81gEd4NwTzl3V96lNvhX3eVfaQGm8RJ8$>. -- You received this message because you are subscribed to the Google Groups "ProjectChrono" group. To unsubscribe from this group and stop receiving emails from it, send an email to [email protected]. To view this discussion visit https://groups.google.com/d/msgid/projectchrono/5162a87b-bbf4-4adb-b2c5-bfbf19650850n%40googlegroups.com<https://urldefense.com/v3/__https:/groups.google.com/d/msgid/projectchrono/5162a87b-bbf4-4adb-b2c5-bfbf19650850n*40googlegroups.com?utm_medium=email&utm_source=footer__;JQ!!Mak6IKo!MwIXzoxahONqdZiBLnFwXMCcSePcaFEIqt4eP__eN3IMQ1PxmDovmMKJ70IucYAqhb6fkbaj0fMXJK8$>. -- You received this message because you are subscribed to the Google Groups "ProjectChrono" group. To unsubscribe from this group and stop receiving emails from it, send an email to [email protected]<mailto:[email protected]>. To view this discussion visit https://groups.google.com/d/msgid/projectchrono/2b5106aa-c1d3-4817-a460-0361cd8720b1n%40googlegroups.com<https://urldefense.com/v3/__https:/groups.google.com/d/msgid/projectchrono/2b5106aa-c1d3-4817-a460-0361cd8720b1n*40googlegroups.com?utm_medium=email&utm_source=footer__;JQ!!Mak6IKo!KuRTx_feSB0fz7sTdnyP4kidta3RfUecFIdDjhg2oqUkIZJKzhIwmAc4eiR0nt4khcPol5Yfj37qLhE$>. -- You received this message because you are subscribed to the Google Groups "ProjectChrono" group. To unsubscribe from this group and stop receiving emails from it, send an email to [email protected]. To view this discussion visit https://groups.google.com/d/msgid/projectchrono/CH3PPF46CDC2185B2572F92F3FA9EB9377AA78EA%40CH3PPF46CDC2185.namprd06.prod.outlook.com.
