wip: testing

This commit is contained in:
2025-04-18 11:19:26 +02:00
parent ade1f91529
commit 2b450a6d86
5 changed files with 46 additions and 38 deletions

View File

@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" xmlns:gz="http://gazebosim.org">
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="mecanum_wheel_material">
<ambient>0.2 0.2 0.2 1</ambient>
@@ -27,16 +27,15 @@
<inertial>
<mass value="${mass}"/>
<inertia
ixx="${0.5 * mass * radius * radius}"
ixx="${(13.0/48.0) * mass * radius * radius}"
ixy="0.0"
ixz="0.0"
iyy="${0.5 * mass * radius * radius}"
iyz="0.0"
izz="${0.25 * mass * radius * radius}"
izz="${(13.0/48.0) * mass * radius * radius}"
/>
</inertial>
<visual name='visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh
filename="${mesh}"
@@ -46,27 +45,30 @@
<material name="mecanum_wheel_material"/>
</visual>
<collision name='collision'>
<origin xyz="0 0 0" rpy="-1.5707 0 0"/>
<geometry>
<sphere radius="${radius}"/>
<cylinder radius="${radius}" length="${radius}"/>
</geometry>
<surface>
<friction>
<ode>
<mu>1.2</mu>
<mu2>0</mu2>
<fdir1 gz:expressed_in="${parent}_link">1 ${friction_dir} 0</fdir1>
</ode>
</friction>
</surface>
</collision>
</link>
<xacro:element xacro:name="gazebo" reference="${name}_link">
<surface>
<friction>
<ode>
<mu>1.0</mu>
<mu2>0.0</mu2>
<fdir1>1 ${friction_dir} 0</fdir1>
</ode>
</friction>
</surface>
</xacro:element>
<joint name='${name}_joint' type='continuous'>
<parent link="${parent}_link"/>
<child link="${name}_link"/>
<axis xyz="0 1 0"/>
<limit
velocity="5"
effort="100000"
velocity="35"
effort="350"
/>
<origin xyz="${xyz}" rpy="${rpy}"/>
</joint>