Skip to content

Commit

Permalink
Merge pull request #18 from Tordjx/main
Browse files Browse the repository at this point in the history
Added camera to the "camera variant"
  • Loading branch information
stephane-caron authored Jul 29, 2024
2 parents 828ee6c + f8f1678 commit fe66055
Show file tree
Hide file tree
Showing 3 changed files with 53 additions and 4 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ All notable changes to this project will be documented in this file.
- CICD: Add packaging workflow
- Camera variant of the URDF
- python: Add "variant" keyword argument to `load_in_pinocchio`
- Added camera support mass and camera to the "camera" variant

### Changed

Expand Down
28 changes: 26 additions & 2 deletions urdf/upkie_camera.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -128,15 +128,39 @@ Conventions in this file are detailed in:
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="0.0005416666666666668" ixy="0" ixz="0" iyy="0.0013333333333333333" iyz="0" izz="0.0016083333333333334"/>
<mass value="0.167"/>
<inertia ixx="9.045833333333334e-05" ixy="0" ixz="0" iyy="0.0002226666666666667" iyz="0" izz="0.0002685916666666667"/>
</inertial>
</link>
<joint name="camera_support_fix" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.16"/>
<parent link="torso"/>
<child link="camera_support"/>
</joint>
<link name="camera">
<visual>
<geometry>
<box size="0.0175 0.091 0.028"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.0175 0.091 0.028"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.061"/>
<inertia ixx="4.6080416666666663e-05" ixy="0" ixz="0" iyy="5.542104166666667e-06" iyz="0" izz="4.3651854166666664e-05"/>
</inertial>
</link>
<joint name="camera_fix" type="fixed">
<origin rpy="0 0 0" xyz="0.045 0 0"/>
<parent link="camera_support"/>
<child link="camera"/>
</joint>
<!-- Left leg -->
<!-- Left hip -->
<link name="left_hip_qdd100_stator">
Expand Down
28 changes: 26 additions & 2 deletions xacro/torso.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -89,10 +89,10 @@
<box size="0.11 0.12 0.07" />
</geometry>
</collision>
<!-- mass NOT MEASURED YET -->
<!-- mass measured with USB cable -->
<xacro:box_inertia
rpy="0 0 0" xyz="0 0 0"
mass="1.0"
mass="0.167"
len_x="0.120" len_y="0.07" len_z="0.04" />
</link>

Expand All @@ -101,6 +101,30 @@
<parent link="torso" />
<child link="camera_support" />
</joint>

<link name="camera">
<visual>
<geometry>
<box size="0.0175 0.091 0.028"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.0175 0.091 0.028"/>
</geometry>
</collision>
<xacro:box_inertia
rpy="0 0 0" xyz="0 0 0"
mass="0.061"
len_x="0.0175" len_y="0.091" len_z="0.028" />
</link>
<joint name="camera_fix" type="fixed">
<origin rpy="0 0 0" xyz="0.045 0 0"/>
<parent link="camera_support"/>
<child link="camera"/>
</joint>
</xacro:if>

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

0 comments on commit fe66055

Please sign in to comment.