Link with multiple parent or multiple joint with same child
I need to connect four links(below each link there is a motor, i.e actuated joint) all together to a single big square link, so I needed to model four joints(no actuator attached to them, free), with each joint having the same child(which is the big square link), but after running the simulation in Gazebo, the model was not stable and I could not actuate other joints which were supposed to lift up and down big square link. So my very basic question for starter here is, is it possible to have multiple joint sharing the same child (or parent, if the difference matters) ? If so, what parameters should I include in sdf modeling to keep it stable.
Here is a small chunck of my sdf modeling:
<link name="aaly__body">
<self_collide>1</self_collide>
<pose>-0.06573 -0.000135 0.235000 0 0 0</pose>
<inertial>
<mass>0.5</mass>
<inertia>
<ixx>0.002110537983145438</ixx>
<ixy>6.068160057964515e-06</ixy>
<ixz>5.782219040307764e-05</ixz>
<iyy>0.0025371464552802047</iyy>
<iyz>-3.9203677986423195e-06</iyz>
<izz>0.003081784306452865</izz>
</inertia>
</inertial>
<collision name="aaly__body_collision">
<geometry>
<box>
<size>0.14 0.14 0.12</size>
</box>
</geometry>
</collision>
<visual name="aaly__body_visual">
<geometry>
<mesh>
<uri>model://my_tracks/meshes/Body.stl</uri>
</mesh>
</geometry>
<material>
<ambient>0.4 0.4 0.4 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0 0 0 0</specular>
<emissive>0 0 0 1</emissive>
</material>
</visual>
</link>
<joint name="aaly__body_front_right_joint" type="revolute">
<pose>0.04073 -0.05200 -0.065 0 0 0</pose>
<parent>aaly__thigh_right_front</parent>
<child>aaly__body</child>
<axis>
<xyz>1 0 0</xyz>
</axis>
</joint>
<joint name="aaly__body_back_right_joint" type="revolute">
<pose>-0.04573 -0.052 -0.065 0 0 0</pose>
<parent>aaly__thigh_right_back</parent>
<child>aaly__body</child>
<axis>
<xyz>1 0 0</xyz>
</axis>
</joint>
<joint name="aaly__body_front_left_joint" type="revolute">
<pose>0.04073 0.05200 -0.065 0 0 0</pose>
<parent>aaly__thigh_left_front</parent>
<child>aaly__body</child>
<axis>
<xyz>1 0 0</xyz>
</axis>
</joint>
<joint name="aaly__body_back_left_joint" type="revolute">
<pose>-0.04573 0.052 -0.065 0 0 0</pose>
<parent>aaly__thigh_left_back</parent>
<child>aaly__body</child>
<axis>
<xyz>1 0 0</xyz>
</axis>
</joint>
I'm using ROS Kinetic (ROS control of the joints) with Gazebo 7.14 (sdf 1.4)
It's hard to tell what's going on without having all the links, but I think it's more common for multiple links to share a parent than a child, can you give that a try?
Can you post your complete model?
@chapulina , How does that make any difference?, I've tried with your suggestion and still not stable.
@nkoenig, here is the repo in github: https://github.com/IronFist16/aaly_project .