Skip to content

Commit

Permalink
use wheel mount point instead of wheel separation
Browse files Browse the repository at this point in the history
  • Loading branch information
KmakD committed Feb 5, 2025
1 parent be0e8da commit 1f04313
Show file tree
Hide file tree
Showing 7 changed files with 47 additions and 24 deletions.
2 changes: 1 addition & 1 deletion husarion_ugv_description/config/WH01.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
wheel_radius: 0.1825
wheel_width: 0.14
wheel_separation: 0.697
mount_point_offset: 0.091
mass: 3.0
inertia: { ixx: 0.022510, iyy: 0.034850, izz: 0.022510 }
inertia_y_offset: 0.0
Expand Down
2 changes: 1 addition & 1 deletion husarion_ugv_description/config/WH02.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
wheel_radius: 0.1016
wheel_width: 0.08
wheel_separation: 0.6785
mount_point_offset: 0.08165
mass: 2.4
inertia: { ixx: 0.010050, iyy: 0.016496, izz: 0.010068 }
inertia_y_offset: 0.0
Expand Down
2 changes: 1 addition & 1 deletion husarion_ugv_description/config/WH04.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
wheel_radius: 0.1016
wheel_width: 0.04
wheel_separation: 0.616
mount_point_offset: 0.06
mass: 0.85
inertia: { ixx: 0.003099, iyy: 0.005849, izz: 0.003101 }
inertia_y_offset: 0.0
Expand Down
2 changes: 1 addition & 1 deletion husarion_ugv_description/config/WH05.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
wheel_radius: 0.1348
wheel_width: 0.09
wheel_separation: 0.45
mount_point_offset: 0.06
# TODO change inertia and mass when ready
mass: 2.5
inertia: { ixx: 0.014738, iyy: 0.0261, izz: 0.014738 }
Expand Down
33 changes: 23 additions & 10 deletions husarion_ugv_description/urdf/common/wheel.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,36 +2,49 @@
<robot xmlns:xacro="http://wiki.ros.org/xacro">

<!-- wheel defining macro -->
<xacro:macro name="wheel" params="wheel_config wheel_separation_x prefix">
<xacro:macro name="wheel"
params="wheel_config prefix wheel_mount_point_x wheel_mount_point_y">

<xacro:if value="${prefix == 'fl'}">
<xacro:property name="x" value="${wheel_separation_x/2.0}" />
<xacro:property name="y" value="${wheel_config['wheel_separation']/2.0}" />
<xacro:property name="x" value="${wheel_mount_point_x}" />
<xacro:property name="y" value="${wheel_mount_point_y}" />
<xacro:property name="mount_point_offset" value="${wheel_config['mount_point_offset']}" />
<xacro:property name="inertia_y_offset" value="${wheel_config['inertia_y_offset']}" />
<xacro:property name="fdir" value="1 -1 0" />
</xacro:if>
<xacro:if value="${prefix == 'fr'}">
<xacro:property name="x" value="${wheel_separation_x/2.0}" />
<xacro:property name="y" value="-${wheel_config['wheel_separation']/2.0}" />
<xacro:property name="x" value="${wheel_mount_point_x}" />
<xacro:property name="y" value="-${wheel_mount_point_y}" />
<xacro:property name="mount_point_offset" value="-${wheel_config['mount_point_offset']}" />
<xacro:property name="inertia_y_offset" value="${-wheel_config['inertia_y_offset']}" />
<xacro:property name="fdir" value="1 1 0" />
</xacro:if>
<xacro:if value="${prefix == 'rl'}">
<xacro:property name="x" value="-${wheel_separation_x/2.0}" />
<xacro:property name="y" value="${wheel_config['wheel_separation']/2.0}" />
<xacro:property name="x" value="-${wheel_mount_point_x}" />
<xacro:property name="y" value="${wheel_mount_point_y}" />
<xacro:property name="mount_point_offset" value="${wheel_config['mount_point_offset']}" />
<xacro:property name="inertia_y_offset" value="${wheel_config['inertia_y_offset']}" />
<xacro:property name="fdir" value="1 1 0" />
</xacro:if>
<xacro:if value="${prefix == 'rr'}">
<xacro:property name="x" value="-${wheel_separation_x/2.0}" />
<xacro:property name="y" value="-${wheel_config['wheel_separation']/2.0}" />
<xacro:property name="x" value="-${wheel_mount_point_x}" />
<xacro:property name="y" value="-${wheel_mount_point_y}" />
<xacro:property name="mount_point_offset" value="-${wheel_config['mount_point_offset']}" />
<xacro:property name="inertia_y_offset" value="${-wheel_config['inertia_y_offset']}" />
<xacro:property name="fdir" value="1 -1 0" />
</xacro:if>

<joint name="${prefix}_wheel_joint" type="continuous">
<joint name="base_to_${prefix}_wheel_base_joint" type="fixed">
<origin xyz="${x} ${y} 0.0" rpy="0.0 0.0 0.0" />
<parent link="base_link" />
<child link="${prefix}_wheel_base_link" />
</joint>

<link name="${prefix}_wheel_base_link" />

<joint name="${prefix}_wheel_joint" type="continuous">
<origin xyz="0.0 ${mount_point_offset} 0.0" rpy="0.0 0.0 0.0" />
<parent link="${prefix}_wheel_base_link" />
<child link="${prefix}_wheel_link" />
<axis xyz="0.0 1.0 0.0" />

Expand Down
15 changes: 10 additions & 5 deletions husarion_ugv_description/urdf/lynx/lynx_macro.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,8 @@
<xacro:property name="ns" value='${namespace + "/" if namespace else ""}' />

<xacro:property name="wheel_config" value="${xacro.load_yaml(wheel_config_file)}" />
<xacro:property name="wheel_separation_x" value="0.35" />
<xacro:property name="wheelbase" value="0.35" />
<xacro:property name="wheel_mount_point_y" value="0.1675" />

<!-- INCLUDE ROBOT PARTS DEFINITIONS -->
<xacro:include filename="$(find husarion_ugv_description)/urdf/lynx/base.urdf.xacro" ns="body" />
Expand All @@ -30,22 +31,26 @@
<!-- WHEEL DECLARATION -->
<xacro:wheel.wheel
wheel_config="${wheel_config}"
wheel_separation_x="${wheel_separation_x}"
wheel_mount_point_x="${wheelbase/2.0}"
wheel_mount_point_y="${wheel_mount_point_y}"
prefix="fl" />

<xacro:wheel.wheel
wheel_config="${wheel_config}"
wheel_separation_x="${wheel_separation_x}"
wheel_mount_point_x="${wheelbase/2.0}"
wheel_mount_point_y="${wheel_mount_point_y}"
prefix="fr" />

<xacro:wheel.wheel
wheel_config="${wheel_config}"
wheel_separation_x="${wheel_separation_x}"
wheel_mount_point_x="${wheelbase/2.0}"
wheel_mount_point_y="${wheel_mount_point_y}"
prefix="rl" />

<xacro:wheel.wheel
wheel_config="${wheel_config}"
wheel_separation_x="${wheel_separation_x}"
wheel_mount_point_x="${wheelbase/2.0}"
wheel_mount_point_y="${wheel_mount_point_y}"
prefix="rr" />

<ros2_control name="${ns}lynx_system" type="system">
Expand Down
15 changes: 10 additions & 5 deletions husarion_ugv_description/urdf/panther/panther_macro.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,8 @@
<xacro:property name="ns" value='${namespace + "/" if namespace else ""}' />

<xacro:property name="wheel_config" value="${xacro.load_yaml(wheel_config_file)}" />
<xacro:property name="wheel_separation_x" value="0.44" />
<xacro:property name="wheelbase" value="0.44" />
<xacro:property name="wheel_mount_point_y" value="0.2575" />

<!-- INCLUDE ROBOT PARTS DEFINITIONS -->
<xacro:include filename="$(find husarion_ugv_description)/urdf/panther/base.urdf.xacro" ns="body" />
Expand All @@ -35,22 +36,26 @@
<!-- WHEEL DECLARATION -->
<xacro:wheel.wheel
wheel_config="${wheel_config}"
wheel_separation_x="${wheel_separation_x}"
wheel_mount_point_x="${wheelbase/2.0}"
wheel_mount_point_y="${wheel_mount_point_y}"
prefix="fl" />

<xacro:wheel.wheel
wheel_config="${wheel_config}"
wheel_separation_x="${wheel_separation_x}"
wheel_mount_point_x="${wheelbase/2.0}"
wheel_mount_point_y="${wheel_mount_point_y}"
prefix="fr" />

<xacro:wheel.wheel
wheel_config="${wheel_config}"
wheel_separation_x="${wheel_separation_x}"
wheel_mount_point_x="${wheelbase/2.0}"
wheel_mount_point_y="${wheel_mount_point_y}"
prefix="rl" />

<xacro:wheel.wheel
wheel_config="${wheel_config}"
wheel_separation_x="${wheel_separation_x}"
wheel_mount_point_x="${wheelbase/2.0}"
wheel_mount_point_y="${wheel_mount_point_y}"
prefix="rr" />

<ros2_control name="${ns}panther_system" type="system">
Expand Down

0 comments on commit 1f04313

Please sign in to comment.