URDF model falls through the ground
Dear all, I have the below URDF file:
This is a description for a inverse pendelum robot which I want to train in a simulation with AI. When I load this file with pybullet for the training, it falls down through the ground and won't stop falling.
Has anybody an idea what could be wrong with the URDF file?
If there are missing some important information please let me know.
Thanks a lot for your help guys!
<?xml version="1.0" ?>
<robot name="Cartpole">
<joint name="Rotation" type="continuous">
<parent link="Cart"/>
<child link="Shaft"/>
<origin rpy="0 0 0" xyz="0.0215 0.247 0.0435"/>
<axis xyz="1 0 0"/>
<limit effort="0.0" lower="0.0" upper="0.0" velocity="0.0"/>
</joint>
<joint name="Cart_joint" type="prismatic">
<parent link="Base"/>
<child link="Cart"/>
<origin rpy="0 0 0" xyz="-0.04147 -0.31058 0.22851"/>
<axis xyz="0 -1 0"/>
<limit effort="0.0" lower="-0.23555" upper="0.23555" velocity="0.0"/>
</joint>
<joint name="Pole_Shaft" type="fixed">
<parent link="Shaft"/>
<child link="Pole"/>
<origin rpy="0 0 0" xyz="0.0193 0 0.007"/>
<axis xyz="0 0 0"/>
<limit effort="0" lower="0" upper="0" velocity="0"/>
</joint>
<link name="Cart">
<inertial>
<mass value="0.4494280957660571"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.034344216689805106" ixy="-0.0013555840592494157" ixz="0.005746023053830929" iyy="0.033575305370647346" iyz="0.007655119926892856" izz="0.0029338994617400297"/>
</inertial>
<collision name="Cart_collision">
<origin rpy="0 0 0" xyz="-0.00606 0.24716 0.03996"/>
<geometry>
<mesh filename="package:///home/agent-pipeline/cad-assets/urdf_cadassets/meshes/CAD/Cart.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
<visual name="Cart_visual">
<origin rpy="0 0 0" xyz="-0.00606 0.24716 0.03996"/>
<geometry>
<mesh filename="package:///home/agent-pipeline/cad-assets/urdf_cadassets/meshes/CAD/Cart.stl" scale="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
<link name="Shaft">
<inertial>
<mass value="0.024209988665072436"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.00188987952436807" ixy="-1.1706804306416182e-05" ixz="5.008066577766269e-05" iyy="0.0017943029340322224" iyz="0.0004187314228447953" izz="0.00010090272031144335"/>
</inertial>
<collision name="Shaft_collision">
<origin rpy="0 0 0" xyz="0.01237 0 0"/>
<geometry>
<mesh filename="package:///home/agent-pipeline/cad-assets/urdf_cadassets/meshes/CAD/Shaft.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
<visual name="Shaft_visual">
<origin rpy="0 0 0" xyz="0.01237 0 0"/>
<geometry>
<mesh filename="package:///home/agent-pipeline/cad-assets/urdf_cadassets/meshes/CAD/Shaft.stl" scale="0.001 0.001 0.001"/>
</geometry>
</visual>
</link>
<link name="Pole">
<inertial>
<mass value="0.01797430178868597"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0008366739796019355" ixy="-7.689518680322801e-07" ixz="2.477907732299824e-06" iyy="0.0007640110742674137" iyz="0.0002341786839091567" izz="7.299569596665657e-05"/>
</inertial>
<collision name="Pole_collision">
<origin rpy="0 0 0" xyz="0 0 -0.07411"/>
<geometry>
<mesh filename="package:///home/agent-pipeline/cad-assets/urdf_cadassets/meshes/CAD/Pole.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
<visual name="Pole_visual">
<origin rpy="0 0 ...
Hi, i have the following progress:
I put a baseplate (ground) into the model and connected the ground with the base with a fixed joint like you can see in the comment below. Now the base part won't fall down, but the other parts still fall down. So it seems like the connections (joints) between the parts are not correct. Any ideas?
<link name="ground">
</link>
<joint name="ground_joint" type="fixed">
</joint>
then wouldnt the ground be falling?