Skip to content

Commit

Permalink
Merge pull request #957 from saikishor/multiple-cameras
Browse files Browse the repository at this point in the history
added support for multiple cameras
  • Loading branch information
doronhi authored Oct 28, 2019
2 parents d91c9c2 + 7ace746 commit 3148d2b
Show file tree
Hide file tree
Showing 5 changed files with 173 additions and 162 deletions.
86 changes: 43 additions & 43 deletions realsense2_description/urdf/_d415.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ aluminum peripherial evaluation case.
-->

<robot name="sensor_d415" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="sensor_d415" params="parent *origin">
<xacro:macro name="sensor_d415" params="name:=camera parent *origin">
<xacro:property name="M_PI" value="3.1415926535897931" />

<!-- The following values are approximate, and the camera node
Expand All @@ -31,34 +31,34 @@ aluminum peripherial evaluation case.
<xacro:property name="d415_cam_depth_py" value="0.020"/>
<xacro:property name="d415_cam_depth_pz" value="${d415_cam_height/2}"/>

<material name="aluminum">
<material name="${name}_aluminum">
<color rgba="0.5 0.5 0.5 1"/>
</material>


<!-- camera body, with origin at bottom screw mount -->
<joint name="camera_joint" type="fixed">
<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="camera_bottom_screw_frame" />
<child link="${name}_bottom_screw_frame" />
</joint>

<link name="camera_bottom_screw_frame"/>
<link name="${name}_bottom_screw_frame"/>

<joint name="camera_link_joint" type="fixed">
<joint name="${name}_link_joint" type="fixed">
<origin xyz="0 ${d415_cam_depth_py} ${d415_cam_depth_pz}" rpy="0 0 0"/>
<parent link="camera_bottom_screw_frame"/>
<child link="camera_link" />
<parent link="${name}_bottom_screw_frame"/>
<child link="${name}_link" />
</joint>

<link name="camera_link">
<link name="${name}_link">
<visual>
<origin xyz="${d415_cam_mount_from_center_offset} ${-d415_cam_depth_py} 0" rpy="${M_PI/2} 0 ${M_PI/2}"/>
<geometry>
<!-- <box size="${d415_cam_width} ${d415_cam_height} ${d415_cam_depth}"/> -->
<mesh filename="package://realsense2_description/meshes/d415.stl" />
<mesh filename="package://realsense2_description/meshes/d415.stl" />
</geometry>
<material name="aluminum"/>
<material name="${name}_aluminum"/>
</visual>
<collision>
<origin xyz="0 ${-d415_cam_depth_py} 0" rpy="0 0 0"/>
Expand All @@ -75,63 +75,63 @@ aluminum peripherial evaluation case.
</link>

<!-- camera depth joints and links -->
<joint name="camera_depth_joint" type="fixed">
<joint name="${name}_depth_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="camera_link"/>
<child link="camera_depth_frame" />
<parent link="${name}_link"/>
<child link="${name}_depth_frame" />
</joint>
<link name="camera_depth_frame"/>
<link name="${name}_depth_frame"/>

<joint name="camera_depth_optical_joint" type="fixed">
<joint name="${name}_depth_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_depth_frame" />
<child link="camera_depth_optical_frame" />
<parent link="${name}_depth_frame" />
<child link="${name}_depth_optical_frame" />
</joint>
<link name="camera_depth_optical_frame"/>
<link name="${name}_depth_optical_frame"/>

<!-- camera left IR joints and links -->
<joint name="camera_left_ir_joint" type="fixed">
<joint name="${name}_left_ir_joint" type="fixed">
<origin xyz="0 ${d415_cam_depth_to_left_ir_offset} 0" rpy="0 0 0" />
<parent link="camera_depth_frame" />
<child link="camera_left_ir_frame" />
<parent link="${name}_depth_frame" />
<child link="${name}_left_ir_frame" />
</joint>
<link name="camera_left_ir_frame"/>
<link name="${name}_left_ir_frame"/>

<joint name="camera_left_ir_optical_joint" type="fixed">
<joint name="${name}_left_ir_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_left_ir_frame" />
<child link="camera_left_ir_optical_frame" />
<parent link="${name}_left_ir_frame" />
<child link="${name}_left_ir_optical_frame" />
</joint>
<link name="camera_left_ir_optical_frame"/>
<link name="${name}_left_ir_optical_frame"/>

<!-- camera right IR joints and links -->
<joint name="camera_right_ir_joint" type="fixed">
<joint name="${name}_right_ir_joint" type="fixed">
<origin xyz="0 ${d415_cam_depth_to_right_ir_offset} 0" rpy="0 0 0" />
<parent link="camera_depth_frame" />
<child link="camera_right_ir_frame" />
<parent link="${name}_depth_frame" />
<child link="${name}_right_ir_frame" />
</joint>
<link name="camera_right_ir_frame"/>
<link name="${name}_right_ir_frame"/>

<joint name="camera_right_ir_optical_joint" type="fixed">
<joint name="${name}_right_ir_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_right_ir_frame" />
<child link="camera_right_ir_optical_frame" />
<parent link="${name}_right_ir_frame" />
<child link="${name}_right_ir_optical_frame" />
</joint>
<link name="camera_right_ir_optical_frame"/>
<link name="${name}_right_ir_optical_frame"/>

<!-- camera color joints and links -->
<joint name="camera_color_joint" type="fixed">
<joint name="${name}_color_joint" type="fixed">
<origin xyz="0 ${d415_cam_depth_to_color_offset} 0" rpy="0 0 0" />
<parent link="camera_depth_frame" />
<child link="camera_color_frame" />
<parent link="${name}_depth_frame" />
<child link="${name}_color_frame" />
</joint>
<link name="camera_color_frame"/>
<link name="${name}_color_frame"/>

<joint name="camera_color_optical_joint" type="fixed">
<joint name="${name}_color_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_color_frame" />
<child link="camera_color_optical_frame" />
<parent link="${name}_color_frame" />
<child link="${name}_color_optical_frame" />
</joint>
<link name="camera_color_optical_frame"/>
<link name="${name}_color_optical_frame"/>
</xacro:macro>
</robot>
86 changes: 43 additions & 43 deletions realsense2_description/urdf/_d435.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ aluminum peripherial evaluation case.
-->

<robot name="sensor_d435" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="sensor_d435" params="parent *origin">
<xacro:macro name="sensor_d435" params="name:=camera parent *origin">
<xacro:property name="M_PI" value="3.1415926535897931" />

<!-- The following values are approximate, and the camera node
Expand All @@ -32,35 +32,35 @@ aluminum peripherial evaluation case.
<xacro:property name="d435_cam_depth_py" value="0.0175"/>
<xacro:property name="d435_cam_depth_pz" value="${d435_cam_height/2}"/>

<material name="aluminum">
<material name="${name}_aluminum">
<color rgba="0.5 0.5 0.5 1"/>
</material>


<!-- camera body, with origin at bottom screw mount -->
<joint name="camera_joint" type="fixed">
<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="camera_bottom_screw_frame" />
<child link="${name}_bottom_screw_frame" />
</joint>
<link name="camera_bottom_screw_frame"/>
<link name="${name}_bottom_screw_frame"/>

<joint name="camera_link_joint" type="fixed">
<joint name="${name}_link_joint" type="fixed">
<origin xyz="0 ${d435_cam_depth_py} ${d435_cam_depth_pz}" rpy="0 0 0"/>
<parent link="camera_bottom_screw_frame"/>
<child link="camera_link" />
<parent link="${name}_bottom_screw_frame"/>
<child link="${name}_link" />
</joint>

<link name="camera_link">
<link name="${name}_link">
<visual>
<origin xyz="${d435_cam_mount_from_center_offset} ${-d435_cam_depth_py} 0" rpy="${M_PI/2} 0 ${M_PI/2}"/>
<geometry>
<!-- <box size="${d435_cam_width} ${d435_cam_height} ${d435_cam_depth}"/> -->
<mesh filename="package://realsense2_description/meshes/d435.dae" />
<mesh filename="package://realsense2_description/meshes/d435.dae" />
<!--<mesh filename="package://realsense2_description/meshes/d435/d435.dae" />-->

</geometry>
<material name="aluminum"/>
<material name="${name}_aluminum"/>
</visual>
<collision>
<origin xyz="0 ${-d435_cam_depth_py} 0" rpy="0 0 0"/>
Expand All @@ -77,63 +77,63 @@ aluminum peripherial evaluation case.
</link>

<!-- camera depth joints and links -->
<joint name="camera_depth_joint" type="fixed">
<joint name="${name}_depth_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="camera_link"/>
<child link="camera_depth_frame" />
<parent link="${name}_link"/>
<child link="${name}_depth_frame" />
</joint>
<link name="camera_depth_frame"/>
<link name="${name}_depth_frame"/>

<joint name="camera_depth_optical_joint" type="fixed">
<joint name="${name}_depth_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_depth_frame" />
<child link="camera_depth_optical_frame" />
<parent link="${name}_depth_frame" />
<child link="${name}_depth_optical_frame" />
</joint>
<link name="camera_depth_optical_frame"/>
<link name="${name}_depth_optical_frame"/>

<!-- camera left IR joints and links -->
<joint name="camera_left_ir_joint" type="fixed">
<joint name="${name}_left_ir_joint" type="fixed">
<origin xyz="0 ${d435_cam_depth_to_left_ir_offset} 0" rpy="0 0 0" />
<parent link="camera_depth_frame" />
<child link="camera_left_ir_frame" />
<parent link="${name}_depth_frame" />
<child link="${name}_left_ir_frame" />
</joint>
<link name="camera_left_ir_frame"/>
<link name="${name}_left_ir_frame"/>

<joint name="camera_left_ir_optical_joint" type="fixed">
<joint name="${name}_left_ir_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_left_ir_frame" />
<child link="camera_left_ir_optical_frame" />
<parent link="${name}_left_ir_frame" />
<child link="${name}_left_ir_optical_frame" />
</joint>
<link name="camera_left_ir_optical_frame"/>
<link name="${name}_left_ir_optical_frame"/>

<!-- camera right IR joints and links -->
<joint name="camera_right_ir_joint" type="fixed">
<joint name="${name}_right_ir_joint" type="fixed">
<origin xyz="0 ${d435_cam_depth_to_right_ir_offset} 0" rpy="0 0 0" />
<parent link="camera_depth_frame" />
<child link="camera_right_ir_frame" />
<parent link="${name}_depth_frame" />
<child link="${name}_right_ir_frame" />
</joint>
<link name="camera_right_ir_frame"/>
<link name="${name}_right_ir_frame"/>

<joint name="camera_right_ir_optical_joint" type="fixed">
<joint name="${name}_right_ir_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_right_ir_frame" />
<child link="camera_right_ir_optical_frame" />
<parent link="${name}_right_ir_frame" />
<child link="${name}_right_ir_optical_frame" />
</joint>
<link name="camera_right_ir_optical_frame"/>
<link name="${name}_right_ir_optical_frame"/>

<!-- camera color joints and links -->
<joint name="camera_color_joint" type="fixed">
<joint name="${name}_color_joint" type="fixed">
<origin xyz="0 ${d435_cam_depth_to_color_offset} 0" rpy="0 0 0" />
<parent link="camera_depth_frame" />
<child link="camera_color_frame" />
<parent link="${name}_depth_frame" />
<child link="${name}_color_frame" />
</joint>
<link name="camera_color_frame"/>
<link name="${name}_color_frame"/>

<joint name="camera_color_optical_joint" type="fixed">
<joint name="${name}_color_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="camera_color_frame" />
<child link="camera_color_optical_frame" />
<parent link="${name}_color_frame" />
<child link="${name}_color_optical_frame" />
</joint>
<link name="camera_color_optical_frame"/>
<link name="${name}_color_optical_frame"/>
</xacro:macro>
</robot>
Loading

0 comments on commit 3148d2b

Please sign in to comment.