Tractor Simulation: Conflicting Collision / Link / Joint values in SDF
Hello All,
I am new to ROS and Gazebo, so I'm sure I'm dealing with some very basic problem. I will give a basic description of the problem in the hopes that someone might point me in the right direction. You can visually understand the problem better, by looking at the picture at the end of the post.Thanks!
I have a tractor model, which I extended with a front loader. The entire frontal-shovel is made up of 2 links registered in my sdf file. I also registered 2 joints: the shovel-joint has base as parent and the front-arm-joint has the shovel-joint as parent. When I position the front loader, my entire tractor gets pushed back and upwards in a way that the front wheel lose contact to the ground. This of course makes the entire tractor uncontrollable.
I did also make other changes to my simulation by creating a publisher and subscriber,as well as messages to catch keyboard press in order to move the frontloader up and down. Despite of this, I believe that the main problem is in the SDF file where I declare the positioning of my two frontloader links and collisions.
Somehow my configurations are conflicting with the tractor. I have tweaked values several times, but nothing seems to get me what I need, which is the tractor with all four wheels on the ground and the frontloader positioned in front of it as it should.
Any help with this would be highly appreciated.
Thanks you all in advance
<link name="base">
<pose>0.0 0.0 0.1 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<mass>150.0</mass>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<collision name="base_geom">
<pose>0 0 1.7 0.05 0.0 1.570796326794897</pose>
<geometry>
<box>
<size>3.2 4.25 2.5</size>
</box>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name="base_visual">
<pose>0.3 0 0.0 0.05 0.0 1.570796326794897</pose>
<geometry>
<mesh>
<uri>model://Fendt/base.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
</link>
<link name="back_left_wheel_link">
<pose>-1.5 0.9 1.1 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<mass>5</mass>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<collision name="back_left_wheel_link_geom">
<pose>0.0 0.375 0.0 -1.570796326794897 0.0 0</pose>
<geometry>
<cylinder>
<length>0.75</length>
<radius>1.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="back_left_wheel_link_visual">
<pose>0.0 0.375 0.0 0 0.0 1.570796326794897</pose>
<geometry>
<mesh>
<uri>model://Fendt/wheel_rear_left.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
</link>
<joint name="back_left_wheel_joint" type="revolute">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<child>back_left_wheel_link</child>
<parent>base</parent>
<axis>
<xyz>0.0 1.0 0.0</xyz>
<limit>
<lower>-10000000000000000.0</lower>
<upper>10000000000000000.0</upper>
</limit>
<dynamics/>
</axis>
</joint>
<link name="back_right_wheel_link">
<pose>-1.5 -0.9 1.1 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<mass>5</mass>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<collision name="back_right_wheel_link_geom">
<pose>0.0 -0.375 0.0 1.570796326794897 0.0 0.0</pose>
<geometry>
<cylinder>
<length>0.75</length>
<radius>1.1</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="back_right_wheel_link_visual">
<pose>0.0 -0.375 0.0 0 0.0 -1.570796326794897</pose>
<geometry>
<mesh>
<uri>model://Fendt/wheel_rear_right.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
</link>
<joint name="back_right_wheel_joint" type="revolute">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<child>back_right_wheel_link</child>
<parent>base</parent>
<axis>
<xyz>0.0 1.0 0.0</xyz>
<limit>
<lower>-10000000000000000.0</lower>
<upper>10000000000000000.0</upper>
</limit>
<dynamics/>
</axis>
</joint>
<link name="front_left_bar_link">
<pose>1.5 1.1 0.79 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<mass>5</mass>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<collision name="front_left_bar_link_geom">
<pose>-0.02 0.0 0.0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.08 0.02 0.005</size>
</box>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name="front_left_bar_link_visual">
<pose>-0.02 0.0 0.0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.08 0.02 0.005</size>
</box>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
</link>
<joint name="front_left_bar_joint" type="revolute">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<child>front_left_bar_link</child>
<parent>base</parent>
<axis>
<xyz>0.0 0.0 1.0</xyz>
<limit>
<lower>-0.5</lower>
<upper>0.5</upper>
</limit>
<dynamics/>
</axis>
</joint>
<link name="front_left_wheel_link">
<pose>1.5 1.1 0.79 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<mass>5</mass>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<collision name="front_left_wheel_link_geom">
<pose>0.0 0.0 0.0 1.570796326794897 0.0 0.0</pose>
<geometry>
<cylinder>
<length>0.5</length>
<radius>0.79</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="front_left_wheel_link_visual">
<pose>0.0 0.0 0.0 0 0.0 1.570796326794897</pose>
<geometry>
<mesh>
<uri>model://Fendt/wheel_front_left.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
</link>
<joint name="front_left_wheel_joint" type="revolute">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<child>front_left_wheel_link</child>
<parent>front_left_bar_link</parent>
<axis>
<xyz>0.0 1.0 0.0</xyz>
<limit>
<lower>-10000000000000000.0</lower>
<upper>10000000000000000.0</upper>
</limit>
<dynamics/>
</axis>
</joint>
<link name="front_right_bar_link">
<pose>1.5 -1.1 0.79 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<mass>1</mass>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<collision name="front_right_bar_link_geom">
<pose>-0.02 0.0 0.0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.08 0.02 0.005000</size>
</box>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name="front_right_bar_link_visual">
<pose>-0.02 0.0 0.0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>0.08 0.02 0.005</size>
</box>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
</link>
<joint name="front_right_bar_joint" type="revolute">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<child>front_right_bar_link</child>
<parent>base</parent>
<axis>
<xyz>0.0 0.0 1.0</xyz>
<limit>
<lower>-0.500000</lower>
<upper>0.500000</upper>
</limit>
<dynamics/>
</axis>
</joint>
<link name="front_right_wheel_link">
<pose>1.5 -1.1 0.79 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<mass>5</mass>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<collision name="front_right_wheel_link_geom">
<pose>0.0 0.0 0.0 1.570796326794897 0.0 0.0</pose>
<geometry>
<cylinder>
<length>0.5</length>
<radius>0.79</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="front_right_wheel_link_visual">
<pose>0.0 0.0 0.0 0.0 0.0 -1.570796326794897</pose>
<geometry>
<mesh>
<uri>model://Fendt/wheel_front_right.dae</uri>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
</link>
<joint name="front_right_wheel_joint" type="revolute">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<child>front_right_wheel_link</child>
<parent>front_right_bar_link</parent>
<axis>
<xyz>0.0 1.0 0.0</xyz>
<limit>
<lower>-10000000000000000.0</lower>
<upper>10000000000000000.0</upper>
</limit>
<dynamics/>
</axis>
</joint>
<link name="trailer_hitch">
<pose>-2.3 0.0 1.1 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<mass>1</mass>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<gravity>1</gravity>
<self_collide>0</self_collide>
</link>
<joint name="trailer_hitch_joint" type="revolute">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<child>trailer_hitch</child>
<parent>base</parent>
<axis>
<xyz>0.0 0.0 1.0</xyz>
<limit>
<lower>-10.00000</lower>
<upper>10.0</upper>
</limit>
<dynamics/>
</axis>
</joint>
And now what I added to include the frontloader
<link name="frontloader_link">
<pose>1.8 0.0 0.0 3.14159265 0.0 -1.570796326794897</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<mass>1</mass>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<collision name="frontloader_link_geom">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>3.2 2.0 1.0</size>
</box>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="frontloader_link_visual">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<geometry>
<mesh>
<uri>model://Fendt/frontloader.dae</uri>
<scale>0.01 0.01 0.01</scale>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
</link>
<joint name="frontloader_joint" type="revolute">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<child>frontloader_link</child>
<parent>shovel_link</parent>
<axis>
<xyz>1.0 0.0 0.0</xyz>
<limit>
<lower>0.0</lower>
<upper>90.0</upper>
</limit>
<dynamics/>
</axis>
</joint>
And for the shovel
<link name="shovel_link">
<pose>4.0 0.0 0.0 0.0 0.0 1.570796326794897</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<mass>1</mass>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<collision name="shovel_link_geom">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<geometry>
<box>
<size>2.0 3.0 1.0</size>
</box>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="shovel_link_visual">
<pose>0.0 0.0 0.0 0.0 1.570796326794897 0.0</pose>
<geometry>
<mesh>
<uri>model://Fendt/shovel.dae</uri>
<scale>0.01 0.01 0.01</scale>
</mesh>
</geometry>
</visual>
<gravity>1</gravity>
<self_collide>0</self_collide>
And the joint for the shovel
<joint name="shovel_joint" type="revolute">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<child>shovel_link</child>
<parent>base</parent>
<axis>
<xyz>0.0 0.0 0.0</xyz>
<limit>
<lower>0.0</lower>
<upper>45.0</upper>
</limit>
<dynamics/>
</axis>
Asked by thephphero on 2015-11-08 03:18:20 UTC
Answers
Hi there,
try adding larger mass values to the base/wheels, and check if your inertia matrices are correct.
Right click -> Show inertia ? (Something like that.)
And make sure the pink box you get visualized it is aprox. the size of its corresponding link.
If that still doesn't work, try uploading a picture when visualizing the inertia. So we can get a better idea.
Cheers, Andrei
Asked by AndreiHaidu on 2015-11-08 07:55:34 UTC
Comments
Thank you for taking the time to answer the question. I made some changes to the SDF file. I have a joint which connects the shovel to the frontloader (shovel_joint) and another joint, which is supposed to connect the frontloader to the tractor (frontloader_joint). The is supposed to revolute around the frontloader_joint. Originally, my shovel_joint had a parent of base and the frontloader_joint was it's child. I changed things around, so that now frontloader_joint is connected to base and shovel_joint has front_loader_link as it's parent as here:
<joint name="frontloader_joint" type="revolute">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<child>frontloader_link</child>
<parent>base</parent>
<axis>
<xyz>0.0 1.0 0.0</xyz>
<limit>
<lower>0.0</lower>
<upper>90.0</upper>
</limit>
<dynamics/>
</axis>
</joint>`<joint name="shovel_joint" type="revolute">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<child>shovel_link</child>
<parent>frontloader_link</parent>
<axis>
<xyz>0.0 0.0 0.0</xyz>
<limit>
<lower>0.0</lower>
<upper>45.0</upper>
</limit>
<dynamics/>
</axis>
This new configuration makes the tractor move very slowly backwards. And the frontloader arm appear under the tractor making it tilt even more. Below is a picture with the inertial boxes displayed as you asked.
I have also raised the enertia values as you suggested from
<pose>1.8 0.0 0.0 3.14159265 0.0 -1.570796326794897</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<mass>1</mass>
<inertia>
<ixx>0.01</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.01</iyy>
<iyz>0.0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
To
<pose>1.8 0.0 0.0 3.14159265 0.0 -1.570796326794897</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<mass>1</mass>
<inertia>
<ixx>0.5</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>0.5</iyy>
<iyz>0.0</iyz>
<izz>0.5</izz>
</inertia>
</inertial>
I'm pretty sure this is a misconfiguration in my values...perhaps pose? Could you tell me if the way these 2 joints are configured makes sense? Is there a better way to do it? As I stated before, the idea is to have the frontloader arm revolute up and down when I press two previously configured keys. For this, I have setup a plugin already. Any other ideas of what I am doing wrong?
Thank you very much for your time. it is deeply appreciated!
Asked by thephphero on 2015-11-10 08:42:10 UTC
Comments
Hi, I suggested larger mass
values for the base and wheels, not inertias
. Also try playing around with the inertias until the pink boxes fit their given links.
Asked by AndreiHaidu on 2015-11-12 06:04:38 UTC
Comments
Hello. If it is not private, can you share DAE files?
Asked by Akif on 2016-03-15 01:44:38 UTC