How to simulate a Stewart Platform with Gazebo and ROS?
Hi :)
For an own project I want to move a platform with a pneumatic system (like the Stewart platform and for this I need a simulation with Gazebo. I'm really a beginner in using Gazebo and ROS and so I started with some tests (and tutorials) to learn how to use both systems. To begin with a "simple urdf-file" I created a table (1 platform with 4 legs) where I want to change the size of the legs. My aim is that Gazebo simulates the position of the platform when I change the size of each leg. But now I have some problems where I don't know how to solve them - maybe you can help me :)
I'm using the standalone version of Gazebo with Groovy on Ubuntu 12.04 32-Bit.
1) Unfortunately the tutorials ends before the description of how to manipulate the robot with controllers (here) and in addition I can't find a controller which simulates a pneumatic actuator. So I decided to create two boxes and to change the position of the inner box with a c++-program - this works for the moment very nice :) The problem is that I have to switch of the gravity for the inner box to avoid that it falls down - do you have a better idea to solve this problem?
<!-- Link 1 (outer box)-->
<joint name="Pn1_joint1" type="fixed">
<origin xyz="0 0 0"/>
<parent link="world"/>
<child link="Pn1_link1"/>
</joint>
<link name="Pn1_link1">
<collision>
<origin xyz="0 0 0.05" rpy="0 0 0"/>
<geometry>
<box size="${widthPneumatic} ${widthPneumatic} 0.1"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 ${heightPneumatic/2}" rpy="0 0 0"/>
<geometry>
<box size="${widthPneumatic} ${widthPneumatic} ${heightPneumatic}"/>
</geometry>
<material name="orange"/>
</visual>
<inertial>
<origin xyz="0 0 ${heightPneumatic/2}" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0"/>
</inertial>
</link>
<gazebo reference="Pn1_link1">
<material>Gazebo/Orange</material>
</gazebo>
<!-- Link 2 (inner box) -->
<joint name="Pn1_joint2" type="prismatic">
<origin xyz="0 0 0"/>
<parent link="Pn1_link1"/>
<child link="Pn1_link2"/>
<axis xyz="0 0 1"/>
<dynamics damping="100"/>
<limit lower="0" upper="${heightPneumatic}" effort="0.00001" velocity="0.00001"/>
</joint>
<link name="Pn1_link2">
<collision>
<origin xyz="0 0 ${heightPneumatic/2}" rpy="0 0 0"/>
<geometry>
<box size="${widthPneumatic-diffInOut} ${widthPneumatic-diffInOut} ${heightPneumatic+diffInOut}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 ${heightPneumatic/2}" rpy="0 0 0"/>
<geometry>
<box size="${widthPneumatic-diffInOut} ${widthPneumatic-diffInOut} ${heightPneumatic+diffInOut}"/>
</geometry>
<material name="orange"/>
</visual>
<inertial>
<origin xyz="0 0 ${heightPneumatic/2}" rpy="0 0 0"/>
<mass value="1"/>
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0"/>
</inertial>
</link>
<gazebo reference="Pn1_link2">
<material>Gazebo/Orange</material>
<turnGravityOff>true</turnGravityOff>
<mu1>100</mu1>
<mu2>100</mu2>
<selfCollide>true</selfCollide>
</gazebo>
2) So I added a second one to the world and wanted to connect these two actuators with the platform. There the tree structure of the urdf-file causes the second problem: I can't connect the two actuators with the world and the platform (which I have to do for the simulation) -.- So my idea was (yes it's a little bit tricky) to lock the actuator with the platform like this:
Head of the actuator:
AAAAA
A
A
...and on the bottom of the platform two structures like this:
AAAAAA -> platform
A A
AAAAAA
...so I can clip the head of the actuator into the building at the bottom of the platform (I'm sorry for these drafts but it isn't very helpful when you can't upload an image -.-). When I don't move the actuators the simulation still works - the platform is locked to the actuator. But when I start my c++-program (which changes the z-position of the inner-box) the platform moves randomly in any direction and the actuator breaks. When I connect one actuator with the platform over a joint and the second over my construction the actuator still work - but only the one which is directly connected over the joint (the other one keep at his place and does not move how expected - like when you lift an element with a crane). Do you have an idea to solve this problem?
Thank you in advance :)
Asked by Alex on 2013-07-21 13:12:30 UTC
Answers
Sounds like you were looking for this tutorial or this one about pid control and prismatic joints.
I haven't used this type of joint yet, but I think I'll try this week. These tutorials haven't been updated yet, so some interpretations would be required.
Also, what do you mean by "the platform moves randomly in any direction and the actuator breaks"?
Asked by SL Remy on 2013-07-22 10:24:13 UTC
Comments
Thanks a lot :) I tried out the two tutorials (it looks like both have nearly the same code?!) and after some changes (had to rename common.h and physics.h to common.hh and physics.hh and also the function *.GetAsRadian() to *.Radian()) it compiled. But when I started gazebo I got this message: Error [Plugin.hh:126] Failed to load plugin libpid_joints.so: cannot open shared object file: No such file or directory - even if I can find the file in my build-directory. Do you have an idea?
Asked by Alex on 2013-07-24 11:43:55 UTC
My program increase/decrease in a loop every second the z-pos of the box since a limit I set. So the box change his position slowly which works when I don't connect it with the platform over my connection explained above (over a joint it works). "the platform moves randomly in any direction and the actuator breaks" mean that if I connect the platform without a joint it falls out of the connection even if it couldn't and the box which pos I change begins to move really fast between the limits.
Asked by Alex on 2013-07-24 11:57:43 UTC
Comments
After some other test I would say that the problem is that gazebo does not detect a collision. I found some other questions about this topic but no solution...true is set in all links. Do I have to do something more?
Asked by Alex on 2013-07-24 12:54:58 UTC