Skip to content

Commit

Permalink
Updated PTU mesh geometry (#40)
Browse files Browse the repository at this point in the history
  • Loading branch information
dniewinski authored and tonybaltovski committed Mar 18, 2019
1 parent 16e59a6 commit 4f0d12c
Show file tree
Hide file tree
Showing 7 changed files with 54 additions and 37 deletions.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file removed flir_ptu_description/meshes/flir-ptu-simple.stl
Binary file not shown.
Binary file not shown.
Binary file not shown.
91 changes: 54 additions & 37 deletions flir_ptu_description/urdf/d46.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,20 @@
<xacro:property name="tilt_down_range" value="0.82" />
<xacro:property name="joint_effort" value="30" />

<xacro:macro name="d46_stepper_module"
params="ptu_name joint_name">
<link name="${ptu_name}_${joint_name}_link">
<xacro:macro name="d46_transmission" params="name">
<transmission name="${name}_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>

<xacro:macro name="ptu_d46" params="name pan_offset:=0.0">
<link name="${name}_tilt_link">
<inertial>
<mass value="0.65" />
<origin xyz="0 0 0" rpy="0 0 0" />
Expand All @@ -19,76 +30,82 @@
<material name="ptu_body_color">
<color rgba="0.3 0.3 0.3 1.0" />
</material>
<origin xyz="-0.0295 0.011 0" rpy="3.14 0 0" />
<geometry>
<mesh filename="package://flir_ptu_description/meshes/flir-ptu-simple.stl"/>
<mesh filename="package://flir_ptu_description/meshes/flir-ptu-tilt-motor.stl"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.045 0.065 0.044" />
<mesh filename="package://flir_ptu_description/meshes/flir-ptu-tilt-motor-collision.stl"/>
</geometry>
<origin xyz="0 0.011 0" />
</collision>
<collision>
</link>
<gazebo reference="${name}_tilt_link">
<material>Gazebo/DarkGrey</material>
</gazebo>

<link name="${name}_pan_link">
<inertial>
<mass value="0.65" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001" />
</inertial>
<visual>
<material name="ptu_body_color">
<color rgba="0.3 0.3 0.3 1.0" />
</material>
<geometry>
<box size="0.046 0.044 0.044" />
<mesh filename="package://flir_ptu_description/meshes/flir-ptu-pan-motor.stl"/>
</geometry>
<origin xyz="-0.045 0.0215 0" />
</collision>
</visual>
<collision>
<geometry>
<cylinder length="0.015" radius="0.005" />
<mesh filename="package://flir_ptu_description/meshes/flir-ptu-pan-motor-collision.stl"/>
</geometry>
<origin xyz="-0.074 0.021 0" rpy="0 1.57 0" />
</collision>
</link>
<gazebo reference="${ptu_name}_${joint_name}_link">
<gazebo reference="${name}_pan_link">
<material>Gazebo/DarkGrey</material>
</gazebo>
</xacro:macro>

<xacro:macro name="d46_transmission" params="name">
<transmission name="${name}_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}">
<hardwareInterface>PositionJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>

<xacro:macro name="ptu_d46" params="name pan_offset:=0.0">
<d46_stepper_module ptu_name="${name}" joint_name="pan" />
<d46_stepper_module ptu_name="${name}" joint_name="tilt" />
<link name="${name}_base_link">
<inertial>
<mass value="2e-06"/>
<inertia ixx="1.1e-09" ixy="0" ixz="0" iyy="1.1e-09" iyz="0" izz="1.1e-09"/>
</inertial>
</link>
<link name="${name}_tilted_link"/>
<link name="${name}_tilted_link">
<visual>
<material name="ptu_body_color">
<color rgba="0.3 0.3 0.3 1.0" />
</material>
<geometry>
<mesh filename="package://flir_ptu_description/meshes/flir-ptu-camera-mount.stl"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://flir_ptu_description/meshes/flir-ptu-camera-mount.stl"/>
</geometry>
</collision>
</link>
<link name="${name}_mount_link">
<inertial>
<mass value="2e-06"/>
<inertia ixx="1.1e-09" ixy="0" ixz="0" iyy="1.1e-09" iyz="0" izz="1.1e-09"/>
</inertial>
</link>

<!-- There's an offset between the origin of the pan joint and the origin of
the overall device, which is between the mounting screws on its base. -->
<joint name="${name}_base" type="fixed">
<parent link="${name}_base_link"/>
<child link="${name}_pan_link"/>
<origin xyz="0 -0.011 0.022"/>
<origin xyz="0 0 0"/>
</joint>

<!-- The pan joint -->
<joint name="${name}_pan" type="revolute">
<parent link="${name}_pan_link" />
<origin xyz="0 0 0.066" rpy="-1.5708 0 ${pan_offset}" />
<origin xyz="0 -0.00955 0.046774" rpy="-1.5708 0 ${pan_offset}" />
<child link="${name}_tilt_link" />
<axis xyz="0 -1 0" rpy="3.14159 0 0" />
<limit lower="${-pan_range}" upper="${pan_range}"
Expand All @@ -100,7 +117,7 @@
<!-- The tilt joint -->
<joint name="${name}_tilt" type="revolute">
<parent link="${name}_tilt_link" />
<origin xyz="0 0 0" rpy="-1.5708 0 0" />
<origin xyz="0 -0.043713 0" rpy="-1.5708 0 0" />
<child link="${name}_tilted_link" />
<axis xyz="0 1 0" />
<limit lower="${-tilt_down_range}" upper="${tilt_up_range}"
Expand All @@ -113,7 +130,7 @@
<joint name="${name}_mount" type="fixed">
<parent link="${name}_tilted_link"/>
<child link="${name}_mount_link"/>
<origin xyz="0 0 -0.03912" rpy="3.1416 0 0" />
<origin xyz="0 0 -0.039116" rpy="3.1416 0 0" />
</joint>

</xacro:macro>
Expand Down

0 comments on commit 4f0d12c

Please sign in to comment.