Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,9 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
### Deprecated
### Removed
### Fixed

* [PR-6](https://github.com/AGH-CEAI/robotiq_hande_description/pull/6) - Added prefix to inertial macro name. Added descriptive names for params.

### Security

## [0.1.0] - 2025-03-13
Expand Down
13 changes: 10 additions & 3 deletions urdf/cylinder_inertial.xacro
Original file line number Diff line number Diff line change
@@ -1,10 +1,17 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="cylinder_inertial" params="r h m *origin">
<xacro:macro name="__robotiq_hande_cylinder_inertial" params="radius height mass *origin">
<inertial>
<mass value="${m}"/>
<mass value="${mass}"/>
<xacro:insert_block name="origin"/>
<inertia ixx="${0.0833333 * m * (3 * (r * r) + h * h)}" ixy="0.0" ixz="0.0" iyy="${0.0833333 * m * (3 * (r * r) + h * h)}" iyz="0.0" izz="${0.5 * m * (r * r)}"/>
<inertia
ixx="${0.0833333 * mass * (3 * (radius * radius) + height * height)}"
ixy="0.0"
ixz="0.0"
iyy="${0.0833333 * mass * (3 * (radius * radius) + height * height)}"
iyz="0.0"
izz="${0.5 * mass * (radius * radius)}"
/>
</inertial>
</xacro:macro>
</robot>
8 changes: 4 additions & 4 deletions urdf/robotiq_hande_gripper.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -55,9 +55,9 @@
</geometry>
</collision>

<xacro:cylinder_inertial r="$(arg hande_radius)" h="$(arg coupler_shell_height)" m="${coupler_mass}">
<xacro:__robotiq_hande_cylinder_inertial radius="$(arg hande_radius)" height="$(arg coupler_shell_height)" mass="${coupler_mass}">
<origin xyz="0 0 ${$(arg coupler_shell_height) / 2 - $(arg coupler_parent_cutoff)}" rpy="0 0 0"/>
</xacro:cylinder_inertial>
</xacro:__robotiq_hande_cylinder_inertial>
</link>

<joint name="${prefix}robotiq_hande_base_joint" type="fixed">
Expand All @@ -81,9 +81,9 @@
</geometry>
</collision>

<xacro:cylinder_inertial r="$(arg hande_radius)" h="$(arg hande_height)" m="0.86387">
<xacro:__robotiq_hande_cylinder_inertial radius="$(arg hande_radius)" height="$(arg hande_height)" mass="0.86387">
<origin xyz="0 0 ${$(arg hande_height) / 2}" rpy="0 0 0"/>
</xacro:cylinder_inertial>
</xacro:__robotiq_hande_cylinder_inertial>
</link>

<joint name="${prefix}robotiq_hande_left_finger_joint" type="prismatic">
Expand Down