Fatal Error caused by vtkPicker in simulation

Dear all,
After implementing my own control, I tried to specify Ghost/object 3D positions by picking with vtkCellPicker.

myControl.cpp
 void MyControl::OnMouseMove(const Vec2d& pos)
{
        cellpicker->Pick
        (
            m_viewer->getVtkRenderWindow()->GetInteractor()->GetEventPosition()[0],
            m_viewer->getVtkRenderWindow()->GetInteractor()->GetEventPosition()[1],
            0,
            m_viewer->getVtkRenderWindow()->GetRenderers()->GetFirstRenderer()
        );
        double picked[3];
        cellpicker->GetPickPosition(picked);
        const Vec3d worldPos = Vec3d(picked[0], picked[1], picked[2]);

        m_goshmesh->setTranslation(worldPos);
        m_goshmesh->setRotation(Mat3d::Identity());
        m_goshmesh->updatePostTransformData();
        m_goshmesh->postModified();
}
main.cpp
    connect<Event>(sceneManager, &SceneManager::postUpdate, [&](Event*)
        {
            //keep the tool moving in real time
            rbdObj->getRigidBodyModel2()->getConfig()->m_dt = sceneManager->getDt();
            femurObj->getLevelSetModel()->getConfig()->m_dt = sceneManager->getDt();

            const Vec3d worldPos = ghostMesh->getCenter();

            const Vec3d fS = Vec3d(worldPos[0] - rbdObj->getRigidBody()->getPosition()[0],
                                                   worldPos[1] - rbdObj->getRigidBody()->getPosition()[1],
                                                   worldPos[2] - rbdObj->getRigidBody()->getPosition()[2]) * 100000.0; 
            const Vec3d fD = -rbdObj->getRigidBody()->getVelocity() * 100.0;

            //push factor in the interaction to change cut/erosion speed.
            (*rbdObj->getRigidBody()->m_force) += (fS + fD);
        });

Result:

In the video It goes well untill the object collision happen and I receive some fatal errors.


Any comments will be appreciated!

My first guess is that you have a data race here. What calls your OnMouseMove function ? Try moving the imstk parts of your OnMouseMove function to a postUpdate callback. Don’t forget to guard the worldPos on read and write

In general iMSTK is not threadsafe wrt to changes to the mesh, you can do updates from inside the physics pipeline, in the scenemanager postUpdate event or in a SceneObjects update() call (this is for every physics dt) or the visualUpdate() call which will be called at the render rate

Hi Harald:
Thanks for your assistance!

1.Here is my callstack in the debugger:

2.According to your suggestion, I moved transformation back to postUpdate event in scenemanager and tried to set the mutex to avoid data race problem like the following. But I still got same error.

Control.cpp
    void Control::OnMouseMove(const Vec2d& pos)
    {
         qmutex.lock();

         if (!getEnabled())
         {
             return;
         }
         cellpicker->Pick
         (
            m_viewer->getVtkRenderWindow()->GetInteractor()->GetEventPosition()[0],
            m_viewer->getVtkRenderWindow()->GetInteractor()->GetEventPosition()[1],
            0,
            m_viewer->getVtkRenderWindow()->GetRenderers()->GetFirstRenderer()
        );
        double picked[3];
        cellpicker->GetPickPosition(picked);
        worldPos = Vec3d(picked[0], picked[1],picked[2]);

        qmutex.unlock();
    }
main.cpp
    connect<Event>(sceneManager, &SceneManager::postUpdate, [&](Event*)
        {
            qmutex.lock();
            //keep the tool moving in real time
            rbdObj->getRigidBodyModel2()->getConfig()->m_dt = sceneManager->getDt();
            femurObj->getLevelSetModel()->getConfig()->m_dt = sceneManager->getDt();
            
            const Vec3d fS = Vec3d(imstk::Control::worldPos[0] - rbdObj->getRigidBody()->getPosition()[0],
                                                   imstk::Control::worldPos[1] - rbdObj->getRigidBody()->getPosition()[1],
                                                   imstk::Control::worldPos[2] - rbdObj->getRigidBody()->getPosition()[2]) 
                                                   * 100000.0;
            
            const Vec3d fD = -rbdObj->getRigidBody()->getVelocity() * 100.0; 
            //push factor in the interaction to change cut/erosion speed.
            (*rbdObj->getRigidBody()->m_force) += (fS + fD);

            //Also apply controller transform to ghost geometry
            ghostMesh->setTranslation(imstk::Control::worldPos);
            ghostMesh->setRotation(Mat3d::Identity());
            ghostMesh->updatePostTransformData();
            ghostMesh->postModified();
            qmutex.unlock();
       }

Just as a note you really only need to protect worldPos.

Am I seeing this right the crash happens inside the cellpicker->Pick() function, is that correct ? Have you tried moving the code from OnMouseMove() to the Update callback, it doesn’t actually use the iMSTK mouse position.

Can you explain a bit more what is going on in the scene, what’s being simulated.

I did tried moving the code from OnMouseMove() to the Update callback. The reason why i gave up is vtkCellPicker really caused poor system performance.

Indeed the crash happens inside the cellpicker->Pick() function when simulation activated. My guess is the ray shoot by Cellpicker probably intersects with actor which already removed inside physics pipeline.

The inner workings are basically the same with the Femur Cut Eample. The difference is I integrated with QtWindow Eample.
(https://gitlab.kitware.com/andrew.wilson/iMSTK/-/tree/c05814e53a4969792b0617293b4f082a962d3165/Examples/QtWindow)

Here is my version:

I haven’t had any time to try and build your sources. I’d have to look at how the simulation, the vtk renderer and the picker interact but i wouldn’t expect to be able to use the picker during the simulation/rendering.

There is a brute force Raycast implemented in imstkPointPicker, it utilizes some of our geometry functionality. This might be helpful to write your on picking within the imstk code

Appreciate your suggestions.
I turned my glare to generalized Picking part in imsk recently and it worked well now.
Now i can specify position precisely and provide drilling interaction with expanded mouse event.