Fixed real <> sim transfer

This commit is contained in:
Tim Korjakow
2023-06-22 21:03:35 +02:00
parent 951058e644
commit ebb17be5af
12 changed files with 68 additions and 59 deletions

View File

@ -17,12 +17,12 @@ diff_cont:
left_wheel_names: ['left_wheel_joint']
right_wheel_names: ['right_wheel_joint']
wheel_separation: 0.215
wheel_radius: 0.0477464829
wheel_radius: 0.049338032
linear:
x:
max_acceleration: 0.05
has_acceleration_limits: true
# linear:
# x:
# max_acceleration: 0.15
# has_acceleration_limits: true
use_stamped_vel: false

View File

@ -9,21 +9,20 @@
<param name="device">/dev/ttyUSB0</param>
<param name="baud_rate">57600</param>
<param name="timeout">1000</param>
<param name="enc_counts_per_rev">3436</param>
</hardware>
<!-- Note everything below here is the same as the Gazebo one -->
<joint name="left_wheel_joint">
<command_interface name="velocity">
<param name="min">-0.005</param>
<param name="max">0.005</param>
<param name="min">-0.5</param>
<param name="max">0.5</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="right_wheel_joint">
<command_interface name="velocity">
<param name="min">-0.005</param>
<param name="max">0.005</param>
<param name="min">-0.5</param>
<param name="max">0.5</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>

View File

@ -41,17 +41,17 @@
<link name="left_wheel">
<visual>
<geometry>
<cylinder radius="${0.3/(2*pi)}" length="0.04"/>
<cylinder radius="${0.31/(2*pi)}" length="0.04"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<!-- Better collosion behaviour than a cylinder -->
<sphere radius="${0.3/(2*pi)}"/>
<sphere radius="${0.31/(2*pi)}"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" radius="${0.3/(2*pi)}" length="0.04">
<xacro:inertial_cylinder mass="0.1" radius="${0.31/(2*pi)}" length="0.04">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
@ -73,16 +73,16 @@
<visual>
<geometry>
<!-- Better collosion behaviour than a cylinder -->
<cylinder radius="${0.3/(2*pi)}" length="0.04"/>
<cylinder radius="${0.31/(2*pi)}" length="0.04"/>
</geometry>
<material name="blue"/>
</visual>
<collision>
<geometry>
<sphere radius="${0.3/(2*pi)}" />
<sphere radius="${0.31/(2*pi)}" />
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" radius="${0.3/(2*pi)}" length="0.04">
<xacro:inertial_cylinder mass="0.1" radius="${0.31/(2*pi)}" length="0.04">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
@ -110,16 +110,16 @@
<link name="caster_wheel_front">
<visual>
<geometry>
<sphere radius="${0.3/(2*pi)}"/>
<sphere radius="${0.31/(2*pi)}"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<sphere radius="${0.3/(2*pi)}"/>
<sphere radius="${0.31/(2*pi)}"/>
</geometry>
</collision>
<xacro:inertial_sphere mass="0.1" radius="${0.3/(2*pi)}">
<xacro:inertial_sphere mass="0.1" radius="${0.31/(2*pi)}">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_sphere>
</link>
@ -142,16 +142,16 @@
<link name="caster_wheel_back">
<visual>
<geometry>
<sphere radius="${0.3/(2*pi)}"/>
<sphere radius="${0.31/(2*pi)}"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<geometry>
<sphere radius="${0.3/(2*pi)}"/>
<sphere radius="${0.31/(2*pi)}"/>
</geometry>
</collision>
<xacro:inertial_sphere mass="0.1" radius="${0.3/(2*pi)}">
<xacro:inertial_sphere mass="0.1" radius="${0.31/(2*pi)}">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_sphere>
</link>