Open Gou-T opened 4 years ago
Hey @Gou-T I am not sure if I understand correctly. Do you mean the four-bar linkage example code is not working on your system or your modification of it? In any case a video, screenshots or a more accurate description of what you have done precisely (robot typology, how you have broken up the robot into a serial one, ROS distribution, Gazebo settings, ...) and how precisely it breaks down would help a lot. Even better if you could supply some code or a minimum working example that is able to replicate your error.
I have also used the same strategy with a 1R2T and a 3R3T cable robot without any issues. I encountered some stability issues with the Gazebo solver though where the simulation would literally blow up for certain configurations. I fixed it by adjusting my physics solver settings. Weirdly enough Bullet would also handle it a lot better than ODE.
In any case the basic working principle of my example is that you can also use SDF to describe a system to Gazebo while ROS is only able to handle URDF-files. I break up the parallel robot into serial chains and connect the additional "redundant" joints that make it parallel with SDF joints. I add the additional joints as SDF code into the URDF that will be recognised by Gazebo only while they will be invisible to ROS. This way I can read the geometry parameters of the URDF in ROS and adjust my ROS nodes (e.g. for forward or inverse kinematics) accordingly but I am still able to simulate the full parallel system in Gazebo.
Thanks for replying. I have converted your code to URDF and added a new link. I've attached the code below. I'd like to connect the arm6_link and arm7_link in the code with an arm9_joint. The complete system is that arm1_link and arm6_link will be parallel no matter how you turn arm1_joint
Hey @Guo-T
I just had a look at it. Your model breaks also for me at arm9_joint
when i remove the transmissions/motors and then apply an external torque to arm6_link
.
First of all there seems to be an issue with your model: If you remove links arm5_link
, arm6_link
and arm7_link
and their joints you will see that if you apply a torque to arm4_link
it won't spin correctly. It collides with link arm3_link
!
Furthermore in your initial file (i named it initial_robotg.urdf
) when adding the fixed joint between arm2_link
and arm7_link
this is reduced to a single link arm2_link
in Gazebo. This can be seen when spawning the initial model into Gazebo and checking World/Models/robotg/LINKS
. This is probably the reason why it breaks down.
So what I did was tried to fix it by connecting arm7_link
to arm6_link
with an URDF continuous joint and then arm7_link
to arm2_link
with a fixed SDF joint. This keeps together but starts to dance because of the self-collision mentioned before (file fixedjoint_collision_robotg.urdf
). If I remove the collision objects for all objects (file fixedjoint_nocollision_robotg.urdf
) or only of the link arm4_link
it works and the joints hold.
Here are your modified URDF-files without the transmissions/motors robotg.zip and similarly the same example with Xacro double_closed_loop.zip
I have also played around with the initial model and while it works with the SDF between the base link (worked both for fixed and floating to world) and the last child, it seems it does not work between two children of the base link. So there might be restrictions to this trick. So far is has worked quite well for my applications which are these simple examples and several cable-driven parallel robots.
Thank you for your answer. It was very helpful that you took the trouble to create a file of answers. I was able to make the system the way I wanted it. However, I still don't fully understand the closed loop. What are the general conditions under which joints are come off ? I am trying to figure out the main causes of joints coming off. I'm sorry for asking this question so many times. I am thinking of making a delta robot in the future.
Hey again @Gou-T after your comment yesterday I played with the URDF quite a bit and tried over 10 possible ways of connecting the different joints. A lot of them failed and I could not fully understand why. E.g. already my simple four-bar-linkage might not work if I would connect two children of the base link to each other instead of connecting the last child to the base link again. It seems to be that there are some limitations to this trick but I don't fully understand them yet. Weirdly enough I never encountered this issues before. Either i) I got just lucky, ii) there was a Gazebo update that changed something or iii) I was aware of the limitations and I forgot to note them down somewhere. For fixed joints on the other hand there didn't seem to be such issues. Potentially this has to do with how Gazebo handles the URDF internally but I will definitely try to investigate further. Please notify me if you encounter problems again (e.g. with your delta robot) or have any idea on why this might happen.
P.S.: If I was you, I would use Xacro instead of URDF directly. It is way easier if you have to change parameters and you can always generate an URDF by typing xacro --inorder your_robot.xacro > your_robot.urdf
. It takes a day or two to get used two but it is totally worth it in my opinion.
I'm programming a closed-loop robot. So this code helped me a lot. But when I added a new link to a square closed loop, the joint described in the SDF came off. I can't see how the joints described in the SDF are connected in any way. It seems that adding a joint described by SDF to URDF is not enough.
Please let me know.