sim with small drift

This commit is contained in:
2025-04-25 14:03:44 +02:00
parent 2b450a6d86
commit 694a120dfd
7 changed files with 183 additions and 23 deletions

View File

@@ -0,0 +1,84 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="wheel_rim_material">
<ambient>0.05 0.05 0.2 05</ambient>
<diffuse>0.9 0.9 0.9 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<emissive>0 0 0 0</emissive>
<color rgba="0.025 0.025 0.025 1"/>
</material>
<material name="wheel_spoke_material">
<ambient>0.2 0.2 0.2 1</ambient>
<diffuse>0.25 0.25 0.25 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<emissive>0 0 0 0 1</emissive>
<color rgba="0.8 0.0 0.0 1"/>
</material>
<xacro:macro name="wheel" params="name parent xyz rpy radius mass">
<xacro:property name="mesh_scale" value="${0.0078 * radius}"/>
<link name='${name}_link'>
<inertial>
<mass value="${mass}"/>
<inertia
ixx="${(13.0/48.0) * mass * radius * radius}"
ixy="0.0"
ixz="0.0"
iyy="${0.5 * mass * radius * radius}"
iyz="0.0"
izz="${(13.0/48.0) * mass * radius * radius}"
/>
</inertial>
<visual name='visual'>
<geometry>
<mesh
filename="package://sherpa/urdf/meshes/wheel_cape.stl"
scale="${mesh_scale} ${mesh_scale} ${mesh_scale}"
/>
</geometry>
<material name="wheel_rim_material"/>
</visual>
<visual name='visual'>
<geometry>
<mesh
filename="package://sherpa/urdf/meshes/wheel_spoke.stl"
scale="${mesh_scale} ${mesh_scale} ${mesh_scale}"
/>
</geometry>
<material name="wheel_spoke_material"/>
</visual>
<collision name='collision'>
<origin xyz="0 0 0" rpy="-1.5707 0 0"/>
<geometry>
<cylinder radius="${radius}" length="${radius/1.5}"/>
</geometry>
</collision>
</link>
<xacro:element xacro:name="gazebo" reference="${name}_link">
<surface>
<friction>
<ode>
<mu>1.5</mu>
<mu2>1.2</mu2>
</ode>
</friction>
<soft_cfm>0.01</soft_cfm> <!-- Soft contact to prevent rigid collisions -->
<soft_erp>0.1</soft_erp> <!-- Error reduction parameter (makes contact softer) -->
</surface>
</xacro:element>
<joint name='${name}_joint' type='continuous'>
<parent link="${parent}_link"/>
<child link="${name}_link"/>
<axis xyz="0 1 0"/>
<limit
velocity="35"
effort="350"
/>
<origin xyz="${xyz}" rpy="${rpy}"/>
</joint>
</xacro:macro>
</robot>