Robotics StackExchange | Archived questions

Fixing location of a sub-model

I currently have a model of a tire, and a seperate sub-model for the holes used for mounting. As shown in the following images, these two meshes are not rigidly connected in any way. I have also included the SDF for the wheel.

(Unfortunately, I cannot upload images. Here's a Link)

How can I join these two objects so that they never separate?

Wheel SDF

<?xml version='1.0'?>
<sdf version="1.4">

<model name="Wheel">
  <pose>0 0 0  0.0 0.0 0.0 </pose>
  <static>false</static>

<include>
  <uri> model://Wheel_Hub </uri>
  <name> Hub </name>
  <pose> 0.1 0.0 0.0   0.0 0.0 0.0 </pose>
</include>

<link name="body">
  <inertial>
    <mass>5.0</mass>
    <inertia>
      <ixx>0.555</ixx>
      <ixy>0.000</ixy>
      <ixz>0.000</ixz>
      <iyy>0.976</iyy>
      <iyz>0.000</iyz>
      <izz>0.555</izz>
    </inertia>
  </inertial>

  <visual name="visual">
    <geometry>
      <mesh><uri>model://Wheel/meshes/wheel.dae</uri></mesh>
    </geometry>
    <material>
      <emissive> 1 1 1 1 </emissive>
    </material>
  </visual>

  <collision name="collision">
    <geometry>
      <mesh><uri>model://Wheel/meshes/wheel.dae</uri></mesh>
    </geometry>
    <surface>
      <bounce>
        <restitution_coefficient> 0.4 </restitution_coefficient>
        <threshold> 0 </threshold>
      </bounce>
      <contact>
        <ode>
          <max_vel>10</max_vel>
        </ode>
      </contact>
    </surface>
  </collision>

</link>
</model>
</sdf>

Hub SDF

<?xml version='1.0'?>
<sdf version="1.4">

<model name="Wheel_Hub">
<pose>0 0 0  0.0 0.0 0.0 </pose>
<static>false</static>

<link name="body">
  <inertial>
    <mass>0.1</mass>
    <inertia>
      <ixx>1</ixx>
      <ixy>0.000</ixy>
      <ixz>0.000</ixz>
      <iyy>1</iyy>
      <iyz>0.000</iyz>
      <izz>1</izz>
    </inertia>
  </inertial>

  <visual name="visual">
    <geometry>
      <mesh><uri>model://Wheel_Hub/meshes/wheel_hub.dae</uri></mesh>
    </geometry>
    <material>
      <emissive> 1 1 1 1 </emissive>
    </material>
  </visual>

  <collision name="collision">
    <geometry>
      <mesh><uri>model://Wheel_Hub/meshes/wheel_hub.dae</uri></mesh>
    </geometry>
  </collision>

</link>
</model>

</sdf>

Asked by Peaches491 on 2014-01-28 14:44:29 UTC

Comments

Answers

You'll have to create a joint between the wheel and the hub. Along the lines of:

<joint name="hub_fixed" type="revolute">
  <parent>Wheel_Hub::body</parent>
  <child>body</child>
  <axis>
    <xyz>0 0 1</xyz>
    <limit>
      <upper>0</upper>
      <lower>0</lower>
    </limit>
  </axis>
</joint>

Put that in the Wheel model, after the </link> and before the </model>

Asked by nkoenig on 2014-01-29 00:01:13 UTC

Comments