Robotics StackExchange | Archived questions

After version 1.8.0 (currently 2.1.0) dynamically created joints act unnatural [Resolved]

Hi,

I am creating dynamically joints between multiple spheres, by connecting all spheres to a center one. This feature stopped working after version 1.8.0, the joints started acting very unnatural, spheres exploding and stuff. I tried many ways to change parameters when creating the joints, however without any significant changes.

Here is the function used in creating the joints:

void DynamicJointPlugin::CreateDynamicJoint(
        physics::LinkPtr _parent_link, physics::LinkPtr _child_link)
{
    physics::JointPtr joint;
    math::Vector3 axis;

    // for axis multiple examples tried
    axis = math::Vector3(1,0,0);  

    joint = world->GetPhysicsEngine()->CreateJoint(
            "revolute", this->liquidModel);

    // switched attach order as well        
    joint->Attach(_parent_link, _child_link);

    // for anchor also tried different values, including a default math::Pose
    joint->Load(_parent_link, _child_link, _child_link->GetWorldPose());

    // tried it with multiple values, even commented out
    joint->SetAxis(0,       axis);
    joint->SetHighStop(0,   M_PI);
    joint->SetLowStop(0,    -M_PI);

    // tried with/without
    joint->Init();

    // tried it commented out and with several other values (no significant changes occured)
    this->pancakeJoints.back()->SetAttribute("stop_cfm",        0,  this->stop_cfm);
    this->pancakeJoints.back()->SetAttribute("stop_erp",        0,  this->stop_erp);
    this->pancakeJoints.back()->SetAttribute("fudge_factor",    0,  this->fudge_factor);
    this->pancakeJoints.back()->SetAttribute("cfm",             0,  this->cfm);
    this->pancakeJoints.back()->SetAttribute("erp",             0,  this->erp);

}

The sdf of the model including all the spheres are loaded as well dynamically and it looks like this:

<?xml version='1.0'?>
<sdf version='1.4'>
<model name='liquid_spheres'>
    <static>false</static>
    <pose>0.2 0.1 1 0 0 0 </pose>
        <link name='sphere_link_0'>
            <self_collide>true</self_collide>
            <pose>0 0 0 0 0 0</pose>
            <inertial>
                <pose> 0 0 0 0 0 0 </pose>
                <inertia>
                    <ixx>0.000102</ixx>
                    <ixy>0</ixy>
                    <ixz>0</ixz>
                    <iyy>0.000102</iyy>
                    <iyz>0</iyz>
                    <izz>0.000102</izz>
                </inertia>
                <mass>0.001</mass>
            </inertial>
            <collision name='collision_0'>
                <geometry>
                    <sphere>
                        <radius>0.005</radius>
                    </sphere>
                </geometry>
                <surface>
                    <friction>
                        <ode>
                            <mu>0.85</mu>
                            <mu2>0.85</mu2>
                            <fdir1>0.0 0.0 0.0</fdir1>
                            <slip1>1</slip1>
                            <slip2>1</slip2>
                        </ode>
                    </friction>
                    <bounce>
                        <restitution_coefficient>0</restitution_coefficient>
                        <threshold>10000.0</threshold>
                    </bounce>
                    <contact>
                        <ode>
                            <soft_cfm>0.58</soft_cfm>
                            <soft_erp>0.58</soft_erp>
                            <kp>100</kp>
                            <kd>1</kd>
                            <max_vel>100.0</max_vel>
                            <min_depth>0.001</min_depth>
                        </ode>
                    </contact>
                </surface>
            </collision>
            <visual name='sphere_visual_0'>
                <geometry>
                    <sphere>
                        <radius>0.005</radius>
                    </sphere>
                </geometry>
                <material>
                    <script>
                        <uri>file://media/materials/scripts/gazebo.material</uri>
                        <name>Gazebo/Red</name>
                    </script>
                </material>
            </visual>
        </link>

        ...

</model>
</sdf>

Videos about the behavior: 50 spheres, joints created between all of them and a middle sphere, joints created consecutively:

https://vimeo.com/80458794

50 spheres, joints created, iteratively, only acts weird after it has been touched by another item:

https://vimeo.com/80457826

3 spheres:

https://vimeo.com/80457823

https://vimeo.com/80457822

2 spheres:

https://vimeo.com/80457820

Thanks, Andrei

UPDATE

Problem doesn't appear in newer versions.

Asked by AndreiHaidu on 2013-11-27 09:13:25 UTC

Comments

Answers