Joints forming a closed loop of linkages - parallel linkages with SDF
Given the joints have a parent child relationship, is it possible to form loops? If not, are there workarounds? Does this vary between versions of Gazebo?
For context, I have been trying to adapt this urdf ( https://code.google.com/p/utexas-art-ros-pkg/source/browse/branches/sandbox/stacks/artexperimental/artgazebo_plugins/urdf/ackermann.urdf.xacro?r=1545 ) for Gazebo 1.5 that is included with the ROS-groovy. So far I have this ( https://gist.github.com/ftalex/5988718 )
Originally they used player and did this:
<gazebo>
<joint:hinge name="ackermann_right_bar_joint">
<body1>ackermann_bar_link</body1>
<body2>front_right_bar_link</body2>
<anchor>ackermann_bar_link</anchor>
<axis>0 0 1</axis>
<anchorOffset>0 -0.45 0</anchorOffset>
</joint:hinge>
</gazebo>
The original has a set of links and with joints so that they form parallel linkages, the two player joints close the loop on each side. I tried to just add joints to replace those in player:
<joint name='ackermann_left_bar_joint' type='revolute'>
<parent>ackermann_bar_link</parent>
<child>front_left_bar_link</child>
<axis>
<xyz>0.000000 0.000000 1.000000</xyz>
<limit>
<lower>-0.500000</lower>
<upper>0.500000</upper>
<effort>100.000000</effort>
<velocity>10.000000</velocity>
</limit>
<dynamics/>
</axis>
</joint>
This seems to do nothing and doesn't give any errors.
Eventually I want to use this with a plugin, but I am still learning about plugins.