Gazebo | Ignition | Community
Ask Your Question
0

create a static mount in gz with urdf

asked 2018-08-29 04:36:31 -0500

markus gravatar image

Hey there,

I would like to create a static mount for a plate: So that the plate can rotate and is not hitting the ground plate.

image description

The bar in the picture should just hold the plate at its center position.

How to set the inertias of the bar?

I tried like this: but when I start the simulation the bar is moving like crazy and shaking etc.....

<link name="bar_mount" >
<inertial>
   <origin rpy="${0} 0 0" xyz="0.0 0.0 0.5"/>
   <mass value="10" />
   <inertia ixx="${0}" ixy="0" ixz="0" iyy="${0}" iyz="0" izz="${0.8333333333333334}" />
</inertial>
<collision>
   <origin rpy="0 0 0" xyz="0.0 0 0" />
   <geometry>
       <mesh filename="package://plate_aruco_description/meshes/collision/bar.stl" scale="2 2 1" />
   </geometry>
</collision>
  <visual name="plate">
    <origin rpy="0 0 0" xyz="0 0 0" />
    <geometry>
      <mesh filename="package://plate_aruco_description/meshes/collision/bar.stl" scale="2 2 1"/>
    </geometry>
  </visual>
</link>
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-08-29 06:05:11 -0500

Raskkii gravatar image

You could attach the mount to the world as a fixed joint. Doing that should keep your pole stable no matter what the inertial is.

<joint name = "bar_joint" type = "fixed">
    <pose>0 0 0 0 0 0</pose>
    <parent>world</parent>
    <child>bar_mount</child>
</joint>

Also, you might want to separate the plate into a separate link considering it would rotate on top of the pole. (Use a revolute joint for that)

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-08-29 04:36:31 -0500

Seen: 660 times

Last updated: Aug 29 '18