Skip to content

Commit

Permalink
Add an empty visual box to all virtual links
Browse files Browse the repository at this point in the history
See #19 (comment)

Fixes #20
  • Loading branch information
stephane-caron committed Jul 31, 2024
1 parent 760810d commit bf84be6
Show file tree
Hide file tree
Showing 9 changed files with 125 additions and 71 deletions.
64 changes: 48 additions & 16 deletions urdf/upkie.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,13 @@ Conventions in this file are detailed in:
<color rgba="0.93 0.64 0.52 0.8"/>
</material>
<link name="base">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand Down Expand Up @@ -74,9 +78,13 @@ Conventions in this file are detailed in:
</joint>
<!-- IMU -->
<link name="imu">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand Down Expand Up @@ -437,9 +445,13 @@ Conventions in this file are detailed in:
<origin rpy="3.141592653589793 0 0" xyz="0 0 -0.0015"/>
</joint>
<link name="left_anchor">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand Down Expand Up @@ -532,9 +544,13 @@ Conventions in this file are detailed in:
<origin rpy="0 0 0" xyz="0 0 0.0209"/>
</joint>
<link name="left_contact">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand All @@ -548,9 +564,13 @@ Conventions in this file are detailed in:
<origin rpy="1.5707963267948966 0 0" xyz="0 0.047 0"/>
</joint>
<link name="left_wheel_center">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand Down Expand Up @@ -861,9 +881,13 @@ Conventions in this file are detailed in:
<origin rpy="3.141592653589793 0 0" xyz="0 0 -0.0015"/>
</joint>
<link name="right_anchor">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand Down Expand Up @@ -956,9 +980,13 @@ Conventions in this file are detailed in:
<origin rpy="0 0 0" xyz="0 0 0.0209"/>
</joint>
<link name="right_contact">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand All @@ -972,9 +1000,13 @@ Conventions in this file are detailed in:
<origin rpy="1.5707963267948966 0 0" xyz="0 0.047 0"/>
</joint>
<link name="right_wheel_center">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand Down
64 changes: 48 additions & 16 deletions urdf/upkie_camera.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,13 @@ Conventions in this file are detailed in:
<color rgba="0.93 0.64 0.52 0.8"/>
</material>
<link name="base">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand Down Expand Up @@ -74,9 +78,13 @@ Conventions in this file are detailed in:
</joint>
<!-- IMU -->
<link name="imu">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand Down Expand Up @@ -461,9 +469,13 @@ Conventions in this file are detailed in:
<origin rpy="3.141592653589793 0 0" xyz="0 0 -0.0015"/>
</joint>
<link name="left_anchor">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand Down Expand Up @@ -556,9 +568,13 @@ Conventions in this file are detailed in:
<origin rpy="0 0 0" xyz="0 0 0.0209"/>
</joint>
<link name="left_contact">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand All @@ -572,9 +588,13 @@ Conventions in this file are detailed in:
<origin rpy="1.5707963267948966 0 0" xyz="0 0.047 0"/>
</joint>
<link name="left_wheel_center">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand Down Expand Up @@ -885,9 +905,13 @@ Conventions in this file are detailed in:
<origin rpy="3.141592653589793 0 0" xyz="0 0 -0.0015"/>
</joint>
<link name="right_anchor">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand Down Expand Up @@ -980,9 +1004,13 @@ Conventions in this file are detailed in:
<origin rpy="0 0 0" xyz="0 0 0.0209"/>
</joint>
<link name="right_contact">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand All @@ -996,9 +1024,13 @@ Conventions in this file are detailed in:
<origin rpy="1.5707963267948966 0 0" xyz="0 0.047 0"/>
</joint>
<link name="right_wheel_center">
<!-- virtual link -->
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
</visual>
<inertial>
<!-- mass should not be zero [1] -->
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
Expand Down
12 changes: 3 additions & 9 deletions xacro/left_leg.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -331,9 +331,7 @@
<origin rpy="3.141592653589793 0 0" xyz="0 0 -0.0015" />
</joint>

<link name="left_anchor">
<xacro:virtual_link_inertia />
</link>
<xacro:virtual_link name="left_anchor" />

<joint name="left_anchor_fix" type="fixed">
<parent link="left_ankle_mj5208_stator" />
Expand Down Expand Up @@ -429,9 +427,7 @@
<origin rpy="0 0 0" xyz="0 0 0.0209" />
</joint>

<link name="left_contact">
<xacro:virtual_link_inertia />
</link>
<xacro:virtual_link name="left_contact" />

<joint name="left_contact_fix" type="fixed">
<parent link="left_wheel_tire" />
Expand All @@ -441,9 +437,7 @@
<origin rpy="1.5707963267948966 0 0" xyz="0 0.047 0" />
</joint>

<link name="left_wheel_center">
<xacro:virtual_link_inertia />
</link>
<xacro:virtual_link name="left_wheel_center" />

<joint name="left_wheel_center_fix" type="fixed">
<parent link="left_wheel_tire" />
Expand Down
12 changes: 3 additions & 9 deletions xacro/right_leg.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -331,9 +331,7 @@
<origin rpy="3.141592653589793 0 0" xyz="0 0 -0.0015" />
</joint>

<link name="right_anchor">
<xacro:virtual_link_inertia />
</link>
<xacro:virtual_link name="right_anchor" />

<joint name="right_anchor_fix" type="fixed">
<parent link="right_ankle_mj5208_stator" />
Expand Down Expand Up @@ -429,9 +427,7 @@
<origin rpy="0 0 0" xyz="0 0 0.0209" />
</joint>

<link name="right_contact">
<xacro:virtual_link_inertia />
</link>
<xacro:virtual_link name="right_contact" />

<joint name="right_contact_fix" type="fixed">
<parent link="right_wheel_tire" />
Expand All @@ -441,9 +437,7 @@
<origin rpy="1.5707963267948966 0 0" xyz="0 0.047 0" />
</joint>

<link name="right_wheel_center">
<xacro:virtual_link_inertia />
</link>
<xacro:virtual_link name="right_wheel_center" />

<joint name="right_wheel_center_fix" type="fixed">
<parent link="right_wheel_tire" />
Expand Down
8 changes: 2 additions & 6 deletions xacro/torso.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,7 @@
<!-- SPDX-License-Identifier: Apache-2.0 -->
<robot name="upkie" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="torso" params="with_camera with_handle">
<link name="base">
<xacro:virtual_link_inertia />
</link>
<xacro:virtual_link name="base" />

<!-- Torso -->

Expand Down Expand Up @@ -35,9 +33,7 @@

<!-- IMU -->

<link name="imu">
<xacro:virtual_link_inertia />
</link>
<xacro:virtual_link name="imu" />

<joint name="imu_fix" type="fixed">
<!-- not that the origin frame is not translated -->
Expand Down
2 changes: 1 addition & 1 deletion xacro/upkie.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ Conventions in this file are detailed in:
<xacro:include filename="xacro/utils/box_inertia.xacro" />
<xacro:include filename="xacro/utils/cylinder_inertia.xacro" />
<xacro:include filename="xacro/utils/materials.xacro" />
<xacro:include filename="xacro/utils/virtual_link_inertia.xacro" />
<xacro:include filename="xacro/utils/virtual_link.xacro" />

<xacro:include filename="xacro/left_leg.xacro" />
<xacro:include filename="xacro/right_leg.xacro" />
Expand Down
2 changes: 1 addition & 1 deletion xacro/upkie_camera.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ Conventions in this file are detailed in:
<xacro:include filename="xacro/utils/box_inertia.xacro" />
<xacro:include filename="xacro/utils/cylinder_inertia.xacro" />
<xacro:include filename="xacro/utils/materials.xacro" />
<xacro:include filename="xacro/utils/virtual_link_inertia.xacro" />
<xacro:include filename="xacro/utils/virtual_link.xacro" />

<xacro:include filename="xacro/left_leg.xacro" />
<xacro:include filename="xacro/right_leg.xacro" />
Expand Down
19 changes: 19 additions & 0 deletions xacro/utils/virtual_link.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<?xml version="1.0" encoding="utf-8" ?>
<!-- SPDX-License-Identifier: Apache-2.0 -->
<robot name="utils" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="virtual_link" params="name">
<link name="${name}">
<!-- virtual link: https://github.com/upkie/upkie_description/wiki/Model-conventions#virtual-links -->
<visual>
<geometry>
<box size="0 0 0" />
</geometry>
</visual>
<inertial>
<mass value="0.001" />
<origin rpy="0 0 0" xyz="0 0 0" />
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" />
</inertial>
</link>
</xacro:macro>
</robot>
13 changes: 0 additions & 13 deletions xacro/utils/virtual_link_inertia.xacro

This file was deleted.

0 comments on commit bf84be6

Please sign in to comment.