Skip to content

Commit

Permalink
Corrected camera position and added a zero dimension visual box
Browse files Browse the repository at this point in the history
  • Loading branch information
Tordjx committed Jul 31, 2024
1 parent 43da803 commit 5862225
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 7 deletions.
8 changes: 7 additions & 1 deletion urdf/upkie_camera.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -169,9 +169,15 @@ Conventions in this file are detailed in:
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
<material name="black"/>
</visual>
</link>
<joint name="camera_eye_fix" type="fixed">
<origin rpy="0 0 0" xyz="-0.045 0 0.005"/>
<origin rpy="0 0 0" xyz="0.00875 0 0.005"/>
<parent link="camera"/>
<child link="camera_eye"/>
</joint>
Expand Down
18 changes: 12 additions & 6 deletions xacro/torso.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -127,12 +127,18 @@
</joint>
<link name="camera_eye">
<xacro:virtual_link_inertia />
</link>
<joint name="camera_eye_fix" type="fixed">
<origin rpy="0 0 0" xyz="-0.045 0 0.005"/>
<parent link="camera"/>
<child link="camera_eye"/>
</joint>
<visual>
<geometry>
<box size="0 0 0"/>
</geometry>
<material name="black"/>
</visual>
</link>
<joint name="camera_eye_fix" type="fixed">
<origin rpy="0 0 0" xyz="0.00875 0 0.005"/>
<parent link="camera"/>
<child link="camera_eye"/>
</joint>
</xacro:if>

<xacro:if value="${with_handle}">
Expand Down

0 comments on commit 5862225

Please sign in to comment.