object sinks into fixed object [Solved]
Hello,
I created a scene, in which a hanoi tower is placed on top of a supporting box, which stands on a table next to a robot.
The board and also the supporting box have a fixed joint to the world reference forcing them to stick to there position.
The disks, which should later be grapped by the robot arm have not such a fixed joint and spawn on top of the board, sliding down into the appropriate position.
But as you can see in the image, the lowest disk sinks into the board and ignores somehow the collision properties of the table (visual and collision are both based on the same .stl file). Also, if you stack multiple tokens on top of each other, they stack appropriatly to their collision properties.
board.urdf.xacro
<link name="world"/>
<gazebo reference="world">
<static>true</static>
</gazebo>
<xacro:towers_of_hanoi_board board_name="$(arg board_name)" parent="world">
<origin xyz="$(arg origin_xyz)" rpy="$(arg origin_rpy)" />
</xacro:towers_of_hanoi_board>
board.xacro
<?xml version="1.0"?>
<!-- <xacro:include filename="$(find edo_description)/urdf/utilities.xacro" /> -->
<xacro:macro name="towers_of_hanoi_board" params="parent board_name *origin">
<!--joint between {parent} and base_link-->
<joint name="${parent}_${board_name}_joint" type="fixed">
<xacro:insert_block name="origin"/>
<parent link="${parent}"/>
<child link="${board_name}_base_link"/>
</joint>
<link name="${board_name}_base_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.07"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://hanoi_tower_description/meshes/towers_of_hanoi/hanoi-board.stl"/>
</geometry>
<material name="Brown"/>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://hanoi_tower_description/meshes/towers_of_hanoi/hanoi-board.stl"/>
</geometry>
<material name="Brown"/>
</collision>
</link>
<gazebo reference="${board_name}_base_link">
<material>Gazebo/Wood</material>
</gazebo>
</xacro:macro>
token.xacro
<?xml version="1.0"?>
<xacro:property name="color" value="White" />
<xacro:property name="diameter" value="0.07" />
<xacro:property name="hole_diameter" value="0.012" />
<xacro:property name="height" value="0.015" />
<xacro:property name="name" value="700" />
<!-- mass in KG -->
<xacro:property name="mass" value="0.1" />
<xacro:macro name="hanoi_token" params="name mass height color diameter hole_diameter">
<xacro:property name="box_width" value="${(diameter - hole_diameter) / 2}" />
<xacro:property name="box_center" value="${(box_width + hole_diameter) / 2}" />
<link name="token_d${name}_link">
<inertial>
<origin xyz="0 0 ${height / 2}"/>
<mass value="${ mass }" />
<!-- See https://www.amesweb.info/SectionalPropertiesTabs/Mass-Moment-Inertia-Hollow-Cylinder-Shaft.aspx -->
<inertia ixx="${(mass / 12) * ( 3 * ( (diameter / 2) * (diameter / 2) + (hole_diameter / 2) * (hole_diameter / 2)) + (height * height))}" ixy="0.0" ixz="0.0" iyy="${(mass / 12) * ( 3 * ( (diameter / 2) * (diameter / 2) + (hole_diameter / 2) * (hole_diameter / 2)) + (height * height))}" iyz="0.0" izz="${(mass / 2) * ( (diameter / 2) * (diameter / 2) + (hole_diameter / 2) * (hole_diameter / 2) )}" />
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://hanoi_tower_description/meshes/towers_of_hanoi/token-${name}.stl" />
</geometry>
<material name="${color}"/>
</visual>
<collision name="collision_d${name}_b1">
<origin rpy="0 0 0" xyz="0 ${box_center} ${height / 2}"/>
<geometry>
<box size="${diameter} ${box_width} ${height}"/>
</geometry>
</collision>
<collision name="collision_d${name}_b2">
<origin rpy="0 0 0" xyz="0 -${box_center} ${height / 2}"/>
<geometry>
<box size="${diameter} ${box_width} ${height}"/>
</geometry>
</collision>
<collision name="collision_d${name}_b3">
<origin rpy="0 0 0" xyz="-${box_center} 0 ${height / 2}"/>
<geometry>
<box size="${box_width} ${hole_diameter} ${height}"/>
</geometry>
</collision>
<collision name="collision_d${name}_b4">
<origin rpy="0 0 0" xyz="${box_center} 0 ${height / 2}"/>
<geometry>
<box size="${box_width} ${hole_diameter} ${height}"/>
</geometry>
</collision>
</link>
<gazebo reference="token_d${name}_link">
<minDepth>0.001</minDepth>
<maxVel>0.01</maxVel>
<kp>1e8</kp>
<kd>1</kd>
<dampingFactor>0.8</dampingFactor>
<material>Gazebo/${color}</material>
</gazebo>
</xacro:macro>
token-d700.urdf.xacro (lowest token)
<?xml version="1.0"?>
<xacro:include filename="$(find hanoi_tower_description)/urdf/materials.xacro" />
<!--Import the hanoi_token macro -->
<xacro:include filename="$(find hanoi_tower_description)/urdf/hanoi_token.xacro"/>
<xacro:hanoi_token name="700" diameter="0.07" hole_diameter="0.012" height="0.015" color="Purple" mass="0.45">
</xacro:hanoi_token>
Asked by Fatalon on 2020-08-15 11:59:05 UTC
Comments