Problems creating multiple joints dynamically after version 1.8.0
Hi,
I have this piece of code to create joints between spheres dynamically, it worked on version 1.8.0 but after installing 1.8.2 / 1.8.4 when I create the joints between more than 5 spheres, it gives no error, but the the model explodes.
Here is the code:
void DynamicJointPlugin::createJoint(physics::LinkPtr _center_link, physics::LinkPtr _ext_link)
{
math::Vector3 axis,direction;
// compute the axis
direction = _ext_link->GetWorldPose().pos - _center_link->GetWorldPose().pos;
direction.Normalize();
axis = direction.Cross(math::Vector3(0.0, 0.0, 1.0));
this->myJoints.push_back(this->liquid_model->GetWorld()->GetPhysicsEngine()->CreateJoint("revolute", this->liquid_model));
this->myJoints.back()->Attach(_ext_link, _center_link );
this->myJoints.back()->Load(_ext_link, _center_link , math::Pose(_center_link->GetWorldPose().pos, math::Quaternion()));
this->myJoints.back()->SetAxis(0, axis);
this->myJoints.back()->SetAttribute("stop_cfm",0, this->stop_cfm);
this->myJoints.back()->SetAttribute("stop_erp",0, this->stop_erp);
this->myJoints.back()->SetAttribute("hi_stop",0, this->limit_stop);
this->myJoints.back()->SetAttribute("lo_stop",0, - this->limit_stop);
}
What changes should I make so it will work again?
Cheers, Andrei