Revolute2 not working in Gazebo 8.0.0?
To all,
I am trying to model a simple car wheel. I intended to use revolute2 so that the tire can roll and steer at the same time. I downloaded the gazebo model, "demojointstypes" from https://bitbucket.org/osrf/gazebo_models/src. I deleted most of the joints type except "Revolute2". But when I run the model, the model failed. The cylinder (revolute arm) link looks like dropped to below the ground. If I delete change the "revolute2" to "revolute" and deleted the associated
How can I make the model to work? I suspect I did not have things turn on or my Gazebo version is outdated? I am using Gazebo 8.0.0
Thank you.
<sdf version="1.6">
<model name="joint_types_SDF">
<link name="heavy_base">
<pose>0 0 0.05 0 0 0</pose>
<inertial>
<mass>100</mass>
<inertia>
<ixx>8.4167</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>40.417</iyy>
<iyz>0</iyz>
<izz>48.667</izz>
</inertia>
</inertial>
<collision name="heavy_base_collision">
<geometry>
<box>
<size>2.2 1 0.1</size>
</box>
</geometry>
</collision>
<visual name="heavy_base_visual">
<geometry>
<box>
<size>2.2 1 0.1</size>
</box>
</geometry>
</visual>
</link>
<link name="revolute2_base">
<pose >-0.17 0 0.35 0 0 0</pose>
<inertial>
<inertia>
<ixx>0.021667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.021667</iyy>
<iyz>0</iyz>
<izz>0.0016667</izz>
</inertia>
</inertial>
<collision name="revolute2_base_collision">
<geometry>
<box>
<size>0.1 0.1 0.5</size>
</box>
</geometry>
</collision>
<visual name="revolute2_base_visual">
<geometry>
<box>
<size>0.1 0.1 0.5</size>
</box>
</geometry>
</visual>
</link>
<link name="revolute2_arm">
<pose >-0.06 -0.075 0.55 1.5708 0 0</pose>
<inertial>
<inertia>
<ixx>0.0058333</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0058333</iyy>
<iyz>0</iyz>
<izz>0.00125</izz>
</inertia>
<pose >-0.1 -0.1 0.1 0 0 0</pose>
</inertial>
<collision name="revolute2_arm_collision">
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.25</length>
</cylinder>
</geometry>
</collision>
<visual name="revolute2_arm_visual">
<geometry>
<cylinder>
<radius>0.05</radius>
<length>0.25</length>
</cylinder>
</geometry>
</visual>
</link>
<joint name="revolute2_base_to_heavy_base" type="fixed">
<parent>heavy_base</parent>
<child>revolute2_base</child>
</joint>
<joint name="revolute2_demo" type="revolute2">
<parent>revolute2_base</parent>
<child>revolute2_arm</child>
<axis>
<xyz>1 0 0</xyz>
</axis>
<axis2>
<xyz>0 1 0</xyz>
</axis2>
<pose>0 0 -0.075 0 0 0</pose>
</joint>
</model>
Asked by seechew on 2018-01-08 15:17:54 UTC
Answers
Unfortunately, this is a known bug:
https://bitbucket.org/osrf/gazebo/issues/2239/all-links-teleport-to-origin-if-model-has
Asked by chapulina on 2018-01-08 19:03:38 UTC
Comments
Thank you.
Asked by seechew on 2018-01-09 13:29:26 UTC
Comments