-
Notifications
You must be signed in to change notification settings - Fork 89
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Gazebo9 Issues :-( #37
Comments
Hi all, Has any progress been made regarding these issues? It's difficult to tell how well localization, navigation, etc. are working without a physical robot for the upcoming fetchit challenge due to this issue with simulating in Gazebo9. Additionally, switching between simulators makes integration across pipelines (e.g. nav and manipulation) difficult. Thanks in advance! |
There hasn't been any forward progress on this issue- we're looking into it and have made it worse, or marginally better in some ways but not overall fixed. @narora1 and I will check different versions of ROS and Gazebo, and see if we can narrow down where things changed. I just spoke with @ajzeller and @ediehr about how the original models and URDF files were generated. |
An update on this. We're checking where things stopped working. I don't think this is a ROS Melodic issue, because everything is working with Melodic on the robot. The two issues: Seem to be related. A real robot, has suspension system which keeps the main drive wheels and all 4 caster wheels in contact with the ground, and the base link frame stable. The base driving is similar when #35 and #36 really start to fail when rotating, but in a straight line don't fail as bad, there is a bit of a "seesaw" motion as the robot rotates and it tilts back and forth onto the front and rear casters. I'm going to do some testing with the main drive wheels moved up into the robot further (as if the suspension system is compressed- which on the real robot it always is) this should give us 6 points of contact with the ground and a more stable base. |
Sinking the wheels into the robot, did help make it bounce or seesaw less, but not completely. And there is still something unstable in the controller. I won't check in this change because I'm still not happy with the behaviour, especially going through the doors. the value 0.059 was just picked by launching gazebo with different values. diff --git a/fetch_description/robots/fetch.urdf b/fetch_description/robots/fetch.urdf
index 88297f0..b492567 100644
--- a/fetch_description/robots/fetch.urdf
+++ b/fetch_description/robots/fetch.urdf
@@ -44,7 +44,7 @@
</collision>
</link>
<joint name="r_wheel_joint" type="continuous">
- <origin rpy="-6.123E-17 0 0" xyz="0.0012914 -0.18738 0.055325" />
+ <origin rpy="-6.123E-17 0 0" xyz="0.0012914 -0.18738 0.059" />
<parent link="base_link" />
<child link="r_wheel_link" />
<axis xyz="0 1 0" />
@@ -72,7 +72,7 @@
</collision>
</link>
<joint name="l_wheel_joint" type="continuous">
- <origin rpy="-6.123E-17 0 0" xyz="0.0012914 0.18738 0.055325" />
+ <origin rpy="-6.123E-17 0 0" xyz="0.0012914 0.18738 0.059" />
<parent link="base_link" />
<child link="l_wheel_link" />
<axis xyz="0 1 0" />
|
Thanks for all updates Alex! We're closely following. |
I still haven't gotten a stable model. But I have made progress. The current model shows jitter, and if you view it with "transparent" and "center of mass" on in Gazebo, it can bee seen that the wheels move. There are a large number of issues similar to this on Gazebo, and it seems to be a matter of parameter tuning. Instead of simply sinking the main drive wheels as above, I've created 4 invisible "caster" wheels near to where the real caster wheels are, but with the diameter and on same z height as the drive wheels. This is because the exact height of the casters is hard to determine. diff --git a/fetch_gazebo/robots/fetch.gazebo.xacro b/fetch_gazebo/robots/fetch.gazebo.xacro
index b826ea2..a1b896c 100644
--- a/fetch_gazebo/robots/fetch.gazebo.xacro
+++ b/fetch_gazebo/robots/fetch.gazebo.xacro
@@ -1,6 +1,49 @@
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="fetch" >
<xacro:include filename="$(find fetch_description)/robots/fetch.urdf" />
+ <!-- Add four casters to the base -->
+ <xacro:macro name="caster" params="prefix joint_x joint_y">
+ <link name="${prefix}_caster_link">
+ <visual>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <sphere radius="0.060"/> <!-- 0.06033 -->
+ </geometry>
+ <material name="">
+ <color rgba="0.086 0.506 0.767 1"/>
+ </material>
+ </visual>
+ <collision>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <geometry>
+ <sphere radius="0.060"/>
+ </geometry>
+ </collision>
+ <inertial>
+ <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
+ <origin rpy="0 0 0" xyz="0 0 0"/>
+ <mass value="1"/>
+ </inertial>
+ </link>
+ <gazebo reference="${prefix}_caster_link">
+ <mu1>0.01</mu1>
+ <mu2>0.01</mu2>
+ <!-- <kp>500000</kp> -->
+ <!-- <kd>10.0</kd> -->
+ <!-- <maxVel>10</maxVel> -->
+ </gazebo>
+ <joint name="${prefix}_caster_joint" type="fixed">
+ <parent link="base_link"/>
+ <child link="${prefix}_caster_link"/>
+ <origin rpy="0 0 0" xyz="${joint_x} ${joint_y} 0.055325"/>
+ <axis xyz="0 1 0"/>
+ </joint>
+ </xacro:macro>
+ <xacro:caster prefix="fl" joint_x="0.15" joint_y="0.12"/>
+ <xacro:caster prefix="fr" joint_x="0.15" joint_y="-0.12"/>
+ <xacro:caster prefix="br" joint_x="-0.2" joint_y="0.12"/>
+ <xacro:caster prefix="bl" joint_x="-0.2" joint_y="-0.12"/>
+
<!-- Base is modeled as a big tub sitting on floor, with two wheels -->
<gazebo reference="base_link">
<kp>100000000.0</kp> I also have replaced our wheel stl mesh, with an cylinder. The radius comes from the CAD model. diff --git a/fetch_description/robots/fetch.urdf b/fetch_description/robots/fetch.urdf
index 88297f0..4548fde 100644
--- a/fetch_description/robots/fetch.urdf
+++ b/fetch_description/robots/fetch.urdf
@@ -37,9 +37,11 @@
</material>
</visual>
<collision>
- <origin rpy="0 0 0" xyz="0 0 0" />
+ <origin rpy="1.57079 0 0" xyz="0 0 0" />
<geometry>
- <mesh filename="package://fetch_description/meshes/r_wheel_link_collision.STL" />
+ <!-- mesh filename="package://fetch_description/meshes/r_wheel_link_collision.STL" -->
+ <cylinder radius="0.06033" length="0.051"/>
+ <!-- sphere radius="0.06033" -->
</geometry>
</collision>
</link>
@@ -65,9 +67,11 @@
</material>
</visual>
<collision>
- <origin rpy="0 0 0" xyz="0 0 0" />
+ <origin rpy="1.57079 0 0" xyz="0 0 0" />
<geometry>
- <mesh filename="package://fetch_description/meshes/l_wheel_link_collision.STL" />
+ <!-- mesh filename="package://fetch_description/meshes/l_wheel_link_collision.STL" -->
+ <cylinder radius="0.06033" length="0.051"/>
+ <!-- sphere radius="0.06033" -->
</geometry>
</collision>
</link> |
If anyone is able to further tune these gazebo physics values I'm throwing a help wanted label on this as we'll accept PRs, and it might speed up the process. |
I can give it a try tomorrow to see if I'm more lucky in the physics parameters. Gazebo is really bad sometimes with physics... Especially when you want precision. I'll try some configurations that in other simulations worked in the past, but who knows ;). @moriarty To better know the issue, could you post a video showing the issue? I think it would center more what we want to improve. |
Yes, sorry I did record a video and it's on my desktop at home. I'll post it after work |
If you view "transparent" "links" and "center of mass" and "inertia" you'll see that the center of mass- which are black and white spheres, for the drive wheels will rotate. This could be invalid inertia values, or invalid friction values, or the PID Controller, or a combination of the above, I've been tuning and testing with all combinations of the above. The caster wheels, in the The robot is able to drive straight and pick, but when it turns #30 the behaviour is now a bit worse, and it appears to be the wheels slipping, and throwing off the odom. |
Here is the behaviour prior to Gazebo9. Specifically running the two launch files from #31 using the Dockerfile I shared in #46 roslaunch fetch_gazebo pickplace_playground.launch
roslaunch fetch_gazebo_demo pick_place_demo.launch
Surprisingly it worked in Gazebo9 this time- not on the first grasp attempt. Also note, this version did not have any changes from the diff which I posted above. I was preparing a Before and After video, to show the difference with and without the diff I posted here: #37 (comment) on the first few grasp attempts the robot touched the cube but didn't grasp it, and later it dropped the cube after moving it a couple of times. |
Ok, I'll create a ROSject with a testing environment to test only the locomotion and the grasping in Gazebo9 Melodic, to see if we can improve that grasping so that the cube doesn't fall and also we can dig in into the base caster wheels problem. Hope to have it today last hour. |
Ok I tested it yesterday and yeah, it needs some adjustments in the physics. The pick and place works quite bad and as you said depends a lot on luck sometimes in Melodic Gazebo 9. fetchit_challenge testing_env.launch This way we can concentrate on the vital elements. I'm trying two things:
But anyway I would create a branch in the fetch_gazebo or something similar so that we can have the ROSject updated with the latest improvements from all of us. What do you think @moriarty ? |
Okay thanks @RDaneelOlivav I'll make the changes with the caster wheels, and I'll check the branch creation github settings and figure something out |
This adds 4 casters to the gazebo model, and updates the physics params. This should fix ZebraDevs#31. This is related to ZebraDevs#37
I'm going to close this issue now. Further comments can go into remaining open issues or new issues. |
We have a problem with the Gazebo Robot Model. Things work fine on the Robot, but we've had a number of bugs reported with the simulated robot.
Update (March 20)
I've just added a help wanted label to this issue, as I've been tuning the model, and have attached the
git diff
to this issue, but we'll accept any PRs if anyone as time to try and further tune the models. It might be best if we work in parallel and communicate back via this issue.We've been investigating the issue, and tuning/tweaking parameters. However we haven't found a solution yet. Thank you for the detailed bug reports, and youtube videos of gazebo.
#36 #35 #30 #31
I suspect, that Gazebo has gotten better, and we were relaying on some values which didn't make sense but use to work. Here is one inline comment which leads to that suspicion...
https://github.com/fetchrobotics/fetch_gazebo/blob/643217ce74c4c7537c2832a634944b4a528173c1/fetch_gazebo/robots/fetch.gazebo.xacro#L47
But in the past between gazebo jumps I've seen similar cases were we've had to go back and tune the kp kd values as gazebo gets better they needed to be updated.
http://gazebosim.org/tutorials/?tut=ros_urdf
The text was updated successfully, but these errors were encountered: