Closed osrf-migration closed 8 years ago
Original comment by Jose Luis Rivero (Bitbucket: Jose Luis Rivero, GitHub: j-rivero).
I've verified the bug or the problem with programming following Sam's instruction with gazebo4 and gazebo7 using ROS Indigo.
Original comment by Sam Pfeiffer (Bitbucket: awesomebytes).
Seems like the problem came from my code, I needed to call SetModel with the second model that the joint needed (I was giving the same model than the one when calling CreateJoint).
Thanks for the attention. My final code looks like:
#!c++
// m1 is model1, m2 is model2, l1 is link of model1 and l2 is link of model2
this->fixedJoint = this->physics->CreateJoint("revolute", m1);
this->fixedJoint->Attach(l1, l2);
this->fixedJoint->Load(l1,
l2, math::Pose());
this->fixedJoint->SetModel(m2);
/*
* If SetModel is not done we get:
* ***** Internal Program Error - assertion (this->GetParentModel() != __null)
failed in void gazebo::physics::Entity::PublishPose():
/tmp/buildd/gazebo2-2.2.3/gazebo/physics/Entity.cc(225):
An entity without a parent model should not happen
* If SetModel is given the same model than CreateJoint given
* Gazebo crashes with
* ***** Internal Program Error - assertion (self->inertial != __null)
failed in static void gazebo::physics::ODELink::MoveCallback(dBodyID):
/tmp/buildd/gazebo2-2.2.3/gazebo/physics/ode/ODELink.cc(183): Inertial pointer is NULL
*/
this->fixedJoint->SetAxis(0, math::Vector3(0, 0, 1));
this->fixedJoint->SetHighStop(0, 0);
this->fixedJoint->SetLowStop(0, 0);
this->fixedJoint->SetName("fixedjoint");
this->fixedJoint->Init();
Original comment by Sam Pfeiffer (Bitbucket: awesomebytes).
I solved the problem, it was in my code, see the comment I made before for a full explanation.
Original comment by Sam Pfeiffer (Bitbucket: awesomebytes).
For anyone that may end up here trying to implement the same, in the repo you can find a plugin that through a service call you can attach (and later detach) any two links in the simulation: https://github.com/pal-robotics/gazebo_ros_link_attacher
There are also a couple of comments on things that make it crash and with what error, so someone else may end up googling those errors and find my solution.
Original comment by Nate Koenig (Bitbucket: Nathan Koenig).
Original report (archived issue) by Sam Pfeiffer (Bitbucket: awesomebytes).
I've made a package:
https://github.com/pal-robotics/gazebo_ros_link_attacher
To attach two models in gazebo with a virtual joint dynamically. This is for doing fake grasping in Gazebo as the objects keep slipping from my end effectors.
The repo has docs on how to compile the package and use it and the code is as simple as I could make it. In a few commands you can reproduce my case. This happens on gazebo 2 and gazebo 4, and I've been told also gazebo 7.
I'm following the example of the Gripper.cc/.hh of Gazebo, which is also what seems everyone is doing in github (and answers.gazebosim.org). But Gazebo keeps crashing with:
***** Internal Program Error - assertion (self->inertial != __null) failed in static void gazebo::physics::ODELink::MoveCallback(dBodyID): /tmp/buildd/gazebo4-4.1.3/gazebo/physics/ode/ODELink.cc(178): Inertial pointer is NULL Aborted (core dumped)