Measuring Contact Force in Forward Simulation
- Thomas Uchida
- Posts: 1792
- Joined: Wed May 16, 2012 11:40 am
Re: Measuring Contact Force in Forward Simulation
The ExampleContactPlayground creates a model programmatically whereas you're loading a model from file. Thus, rather than create a CompliantContactSubsystem on line 44, you need to fish out a reference to the relevant ForceSubsystem that is created when you call initSystem(). See the Simbody doxygen for CompliantContactSubsystem (https://simtk.org/api_docs/simbody/3.5/ ... ystem.html) and related classes. There may also be some useful information in the Simbody Theory Manual (https://github.com/simbody/simbody/blob ... Manual.pdf).
- Kenechukwu Mbanisi
- Posts: 51
- Joined: Fri Feb 10, 2017 2:50 pm
Re: Measuring Contact Force in Forward Simulation
Thank you, Tom.
I believe that is precisely my problem right now. I did check to make sure that new subsystems (CompliantContact & ContactTracking) were included in the current state iobject (s_new) and they were.
I have gone through the documentation on CompliantContactSubsystem. I don't see a way of properly setting up (or initializing) the subsystem such that it interfaces with my model and current state. The theory manual helped giving a clear understanding of the internal workings of the contact interface, but I wasn't able to understand how to overcome my current challenge.
Any insights would be very much appreciated.
Kenechukwu
I believe that is precisely my problem right now. I did check to make sure that new subsystems (CompliantContact & ContactTracking) were included in the current state iobject (s_new) and they were.
I have gone through the documentation on CompliantContactSubsystem. I don't see a way of properly setting up (or initializing) the subsystem such that it interfaces with my model and current state. The theory manual helped giving a clear understanding of the internal workings of the contact interface, but I wasn't able to understand how to overcome my current challenge.
Any insights would be very much appreciated.
Kenechukwu
- Thomas Uchida
- Posts: 1792
- Joined: Wed May 16, 2012 11:40 am
Re: Measuring Contact Force in Forward Simulation
Unfortunately, I don't have time at the moment to work out the details. I had an idea a couple days ago, though: you might try building the model in OpenSim without contact (i.e., removing the contact components from your current model) and adding contact programmatically on the Simbody side as is done in ExampleContactPlayground. You would then be able to use the reporting infrastructure from ExampleContactPlayground without much modification. You would still need to fish out references to objects in the model, but in that case you would be fishing for bodies which might be easier to tackle (pun intended ).
- Kenechukwu Mbanisi
- Posts: 51
- Joined: Fri Feb 10, 2017 2:50 pm
Re: Measuring Contact Force in Forward Simulation
Hello,
Thank you for your comments and suggestions, Tom.
I was able to try out what you suggested with a much simpler model (3 bodies, including ground -- somewhat a pendulum) without any contact geometries specified.
Here's how I went about programmatically adding contact geometries (as in the ExampleContactPlayground)
The simulation results seem like the model state is not advancing after being initialized. I guess my challenge at this point is how to upload a model, get access to its multibodysystem (and subsystems), modify them and then run a valid simulation on the 'modified' model/system. I thought that my code above would be able to achieve this but it is not. I am apparently missing something.
Any help here would be highly appreciated.
Kenechukwu
Thank you for your comments and suggestions, Tom.
I was able to try out what you suggested with a much simpler model (3 bodies, including ground -- somewhat a pendulum) without any contact geometries specified.
Here's how I went about programmatically adding contact geometries (as in the ExampleContactPlayground)
Code: Select all
Model osimModel = Model("Two_Link_Model.osim");
osimModel.setUseVisualizer(true);
State& s = osimModel.initSystem();
MultibodySystem& system = osimModel.updMultibodySystem();
SimbodyMatterSubsystem& matter = system.updMatterSubsystem();
GeneralContactSubsystem& contactSystem = system.updContactSubsystem();
ContactTrackerSubsystem tracker(system);
CompliantContactSubsystem contactForces(system, tracker);
const ContactSetIndex contactSet = contactSystem.createContactSet();
SimTK::ContactGeometry::HalfSpace groundGeo;
SimTK::ContactGeometry::Sphere body1Geo(0.1);
SimTK::ContactGeometry::Sphere body2Geo(0.1);
const Real st = 1000000;
const Real dis = 0.2;
const Real stFr = 0.0;
const Real dyFr = 0.0;
const Real visFr = 0.0;
matter.updGround().updBody().addContactSurface(Transform(Rotation(-Pi / 2, ZAxis), Vec3(0)),
ContactSurface(groundGeo, ContactMaterial(st, dis, stFr, dyFr, visFr)));
SimTK::MobilizedBody& body1ToGround = matter.updMobilizedBody(MobilizedBodyIndex(1));
SimTK::MobilizedBody& body2Tobody1 = matter.updMobilizedBody(MobilizedBodyIndex(2));
SimTK::Body& body1 = body1ToGround.updBody();
SimTK::Body& body2 = body2Tobody1.updBody();
body1.addContactSurface(Transform(),
ContactSurface(body1Geo, ContactMaterial(st, dis, stFr, dyFr, visFr)));
body2.addContactSurface(Transform(),
ContactSurface(body2Geo, ContactMaterial(st, dis, stFr, dyFr, visFr)));
contactSystem.addBody(contactSet, matter.Ground(), groundGeo, Transform());
contactSystem.addBody(contactSet, body1ToGround, body1Geo, Transform());
contactSystem.addBody(contactSet, body2Tobody1, body2Geo, Transform());
matter.setShowDefaultGeometry(true);
Visualizer& viz = osimModel.updVisualizer().updSimbodyVisualizer();
forceReport* conforceReporter = new forceReport(system, contactForces, 0.005);
system.addEventReporter(conforceReporter);
system.realizeTopology();
State s_new = system.getDefaultState();
body2Tobody1.setOneQ(s_new, 0, Pi / 3);
SimTK::RungeKuttaMersonIntegrator integrator(system);
integrator.setAccuracy(1.0e-5);
integrator.setMaximumStepSize(0.0001); integrator.setMinimumStepSize(1e-08);
SimTK::TimeStepper ts(system, integrator);
ts.initialize(s_new); ts.stepTo(10.);
Any help here would be highly appreciated.
Kenechukwu
- Kenechukwu Mbanisi
- Posts: 51
- Joined: Fri Feb 10, 2017 2:50 pm
Re: Measuring Contact Force in Forward Simulation
Hello All,
I am still in need of help with this. I'd appreciate any help or pointers.
Thank you very much.
Kenechukwu
I am still in need of help with this. I'd appreciate any help or pointers.
Thank you very much.
Kenechukwu
- Thomas Uchida
- Posts: 1792
- Joined: Wed May 16, 2012 11:40 am
Re: Measuring Contact Force in Forward Simulation
To narrow down the issue, I suggest simplifying your code until it works and then adding pieces back in, verifying that each new piece is working correctly. For example, does the simulation run successfully without trying to add contact? Do the results change as expected if you access one of the bodies and, say, change its mass? Can you load an OpenSim model, fetch references to two bodies, and connect the bodies with a joint? Are the contents of the system what you expect after the call to realizeTopology()?The simulation results seem like the model state is not advancing after being initialized.