Skip to content

Commit

Permalink
Merge pull request PR2#250 from archielee/indigo-devel
Browse files Browse the repository at this point in the history
Removed optenv conditions in upload_pr2.launch which are unnecessary
  • Loading branch information
archielee committed Feb 4, 2016
2 parents 8246f2a + eb49588 commit 6afaf54
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 30 deletions.
44 changes: 23 additions & 21 deletions pr2_description/robots/pr2.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -136,27 +136,6 @@
</xacro:wge100_camera_v0>

<!-- Kinect models -->
<!-- Kinect1 xacro -->
<xacro:if value="$(optenv KINECT1 false)">
<xacro:include filename="$(find pr2_description)/urdf/sensors/kinect_prosilica_camera.urdf.xacro" />
<!-- Base of Kinect/Prosilica Mount -->
<xacro:kinect_prosilica_camera_swept_back_v0 name="head_mount" parent="head_plate_frame" >
<origin xyz="-0.137376 0 0.091746" rpy="0 0 0" />
<!--
Was -0.1 0 0.09225, -0.138 0 0.09225 looks good front back and sheet metal on bolt pattern,
-0.138 0 0.06225 is where Prosilica FOV just clears the head.
This is 30 mm (!) below the position in SolidWorks.
Lowering the Prosilica by this amount in SW makes the FOV hit around the aluminum / plastic junction.
Turns out that head_plate_frame is in some random position in space.
It is [0.0232 0 0.0645 from its parent, head_tilt_link.
The distance from head_plate_frame to the head_kinect_prosilica is 137.376 mm X and 91.746 mm Z.
So the origin should in fact be -0.137376 0 0.091746.
John is changing the Prosilica FOV based on my numbers.
Just need to roscd and svn up.
-->
</xacro:kinect_prosilica_camera_swept_back_v0>
</xacro:if>

<!-- Kinect2 xacro -->
<xacro:if value="$(optenv KINECT2 false)">
<xacro:include filename="$(find pr2_description)/urdf/sensors/kinect2.urdf.xacro" />
Expand All @@ -165,4 +144,27 @@
</xacro:kinect2_v0>
</xacro:if>

<!-- Kinect1 xacro -->
<xacro:unless value="$(optenv KINECT2 false)">
<xacro:if value="$(optenv KINECT1 false)">
<xacro:include filename="$(find pr2_description)/urdf/sensors/kinect_prosilica_camera.urdf.xacro" />
<!-- Base of Kinect/Prosilica Mount -->
<xacro:kinect_prosilica_camera_swept_back_v0 name="head_mount" parent="head_plate_frame" >
<origin xyz="-0.137376 0 0.091746" rpy="0 0 0" />
<!--
Was -0.1 0 0.09225, -0.138 0 0.09225 looks good front back and sheet metal on bolt pattern,
-0.138 0 0.06225 is where Prosilica FOV just clears the head.
This is 30 mm (!) below the position in SolidWorks.
Lowering the Prosilica by this amount in SW makes the FOV hit around the aluminum / plastic junction.
Turns out that head_plate_frame is in some random position in space.
It is [0.0232 0 0.0645 from its parent, head_tilt_link.
The distance from head_plate_frame to the head_kinect_prosilica is 137.376 mm X and 91.746 mm Z.
So the origin should in fact be -0.137376 0 0.091746.
John is changing the Prosilica FOV based on my numbers.
Just need to roscd and svn up.
-->
</xacro:kinect_prosilica_camera_swept_back_v0>
</xacro:if>
</xacro:unless>

</robot>
10 changes: 1 addition & 9 deletions pr2_description/robots/upload_pr2.launch
Original file line number Diff line number Diff line change
@@ -1,14 +1,6 @@
<launch>
<!-- send pr2 urdf to param server -->
<group if="$(optenv KINECT2)">
<group>
<param name="robot_description" command="$(find xacro)/xacro.py '$(find pr2_description)/robots/pr2.urdf.xacro'" />
</group>
<group unless="$(optenv KINECT2)">
<group if="$(optenv KINECT1)">
<param name="robot_description" command="$(find xacro)/xacro.py '$(find pr2_description)/robots/pr2.urdf.xacro'" />
</group>
<group unless="$(optenv KINECT1)">
<param name="robot_description" command="$(find xacro)/xacro.py '$(find pr2_description)/robots/pr2_no_kinect.urdf.xacro'" />
</group>
</group>
</launch>

0 comments on commit 6afaf54

Please sign in to comment.