Skip to content

Commit

Permalink
use find package instead of file
Browse files Browse the repository at this point in the history
  • Loading branch information
eliasdc committed Jan 7, 2025
1 parent 161c0fe commit 54f0d13
Show file tree
Hide file tree
Showing 3 changed files with 49 additions and 47 deletions.
2 changes: 1 addition & 1 deletion realsense2_description/urdf/_d435.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ aluminum peripherial evaluation case.
<!-- the mesh origin is at front plate in between the two infrared camera axes -->
<origin xyz="${d435_zero_depth_to_glass + d435_glass_to_front} ${-d435_cam_depth_py} 0" rpy="${M_PI/2} 0 ${M_PI/2}"/>
<geometry>
<mesh filename="file://$(find realsense2_description)/meshes/d435.dae" />
<mesh filename="package://realsense2_description/meshes/d435.dae" />
</geometry>
</xacro:if>
<xacro:unless value="${use_mesh}">
Expand Down
81 changes: 41 additions & 40 deletions realsense2_description/urdf/_d455.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -21,72 +21,73 @@ This is the URDF model for the Intel RealSense 430 camera, in its
aluminum peripherial evaluation case.
-->

<robot name="sensor_d455" xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="sensor_d455"
xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Includes -->
<xacro:include filename="$(find realsense2_description)/urdf/_materials.urdf.xacro" />
<xacro:include filename="$(find realsense2_description)/urdf/_usb_plug.urdf.xacro" />
<xacro:include filename="$(find realsense2_description)/urdf/_d455.gazebo.xacro"/>
<xacro:include filename="$(find realsense2_description)/urdf/_d455.gazebo.xacro" />

<xacro:macro name="sensor_d455" params="parent *origin name:=camera use_nominal_extrinsics:=false">
<xacro:arg name="add_plug" default="false" />
<xacro:property name="M_PI" value="3.1415926535897931" />

<!-- The following values are approximate, and the camera node
publishing TF values with actual calibrated camera extrinsic values -->
<xacro:property name="d455_cam_depth_to_infra1_offset" value="0.0"/>
<xacro:property name="d455_cam_depth_to_infra2_offset" value="-0.095"/>
<xacro:property name="d455_cam_depth_to_color_offset" value="-0.059"/>
<xacro:property name="d455_cam_depth_to_infra1_offset" value="0.0" />
<xacro:property name="d455_cam_depth_to_infra2_offset" value="-0.095" />
<xacro:property name="d455_cam_depth_to_color_offset" value="-0.059" />


<!-- The following values model the aluminum peripherial case for the
d455 camera, with the camera joint represented by the actual
peripherial camera tripod mount -->
<xacro:property name="d455_cam_width" value="0.124"/>
<xacro:property name="d455_cam_height" value="0.029"/>
<xacro:property name="d455_cam_depth" value="0.026"/>
<xacro:property name="d455_cam_mount_from_center_offset" value="0.0158"/>
<xacro:property name="d455_cam_width" value="0.124" />
<xacro:property name="d455_cam_height" value="0.029" />
<xacro:property name="d455_cam_depth" value="0.026" />
<xacro:property name="d455_cam_mount_from_center_offset" value="0.0158" />
<!-- glass cover is 0.1 mm inwards from front aluminium plate -->
<xacro:property name="d455_glass_to_front" value="0.1e-3"/>
<xacro:property name="d455_glass_to_front" value="0.1e-3" />
<!-- see datasheet Revision 009, Fig. 4-4 page 68 -->
<xacro:property name="d455_zero_depth_to_glass" value="4.55e-3"/>
<xacro:property name="d455_zero_depth_to_glass" value="4.55e-3" />
<!-- convenience precomputation to avoid clutter-->
<xacro:property name="d455_mesh_x_offset" value="${d455_cam_mount_from_center_offset-d455_glass_to_front-d455_zero_depth_to_glass}"/>
<xacro:property name="d455_mesh_x_offset" value="${d455_cam_mount_from_center_offset-d455_glass_to_front-d455_zero_depth_to_glass}" />

<!-- The following offset is relative to the physical d455 camera peripherial
camera tripod mount -->
<xacro:property name="d455_cam_depth_px" value="${d455_cam_mount_from_center_offset}"/>
<xacro:property name="d455_cam_depth_py" value="0.0475"/>
<xacro:property name="d455_cam_depth_pz" value="${d455_cam_height/2}"/>
<xacro:property name="d455_cam_depth_px" value="${d455_cam_mount_from_center_offset}" />
<xacro:property name="d455_cam_depth_py" value="0.0475" />
<xacro:property name="d455_cam_depth_pz" value="${d455_cam_height/2}" />

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

<joint name="${name}_link_joint" type="fixed">
<origin xyz="${d455_mesh_x_offset} ${d455_cam_depth_py} ${d455_cam_depth_pz}" rpy="0 0 0"/>
<parent link="${name}_bottom_screw_frame"/>
<origin xyz="${d455_mesh_x_offset} ${d455_cam_depth_py} ${d455_cam_depth_pz}" rpy="0 0 0" />
<parent link="${name}_bottom_screw_frame" />
<child link="${name}_link" />
</joint>

<link name="${name}_link">
<visual>
<!-- the mesh origin is at front plate in between the two infrared camera axes -->
<!-- <origin xyz="${d455_zero_depth_to_glass-d455_cam_depth/2} ${-d455_cam_depth_py} 0" rpy="0 0 0"/> -->
<origin xyz="${d455_zero_depth_to_glass + d455_glass_to_front} ${-d455_cam_depth_py} 0" rpy="${M_PI/2} 0 ${M_PI/2}"/>
<origin xyz="${d455_zero_depth_to_glass + d455_glass_to_front} ${-d455_cam_depth_py} 0" rpy="${M_PI/2} 0 ${M_PI/2}" />
<geometry>
<!-- <box size="${d455_cam_depth} ${d455_cam_width} ${d455_cam_height}"/> -->
<mesh filename="file://$(find realsense2_description)/meshes/d455.stl" scale="0.001 0.001 0.001" />
<mesh filename="package://realsense2_description/meshes/d455.stl" scale="0.001 0.001 0.001" />
</geometry>
<material name="aluminum"/>
<material name="aluminum" />
</visual>
<collision>
<origin xyz="${d455_zero_depth_to_glass-d455_cam_depth/2} ${-d455_cam_depth_py} 0" rpy="0 0 0"/>
<origin xyz="${d455_zero_depth_to_glass-d455_cam_depth/2} ${-d455_cam_depth_py} 0" rpy="0 0 0" />
<geometry>
<box size="${d455_cam_depth} ${d455_cam_width} ${d455_cam_height}"/>
<box size="${d455_cam_depth} ${d455_cam_width} ${d455_cam_height}" />
</geometry>
</collision>
<inertial>
Expand All @@ -101,69 +102,69 @@ aluminum peripherial evaluation case.
<xacro:if value="${use_nominal_extrinsics}">
<!-- camera depth joints and links -->
<joint name="${name}_depth_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="${name}_link"/>
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="${name}_link" />
<child link="${name}_depth_frame" />
</joint>
<link name="${name}_depth_frame"/>
<link name="${name}_depth_frame" />

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

<!-- camera left IR joints and links -->
<joint name="${name}_infra1_joint" type="fixed">
<origin xyz="0 ${d455_cam_depth_to_infra1_offset} 0" rpy="0 0 0" />
<parent link="${name}_link" />
<child link="${name}_infra1_frame" />
</joint>
<link name="${name}_infra1_frame"/>
<link name="${name}_infra1_frame" />

<joint name="${name}_infra1_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="${name}_infra1_frame" />
<child link="${name}_infra1_optical_frame" />
</joint>
<link name="${name}_infra1_optical_frame"/>
<link name="${name}_infra1_optical_frame" />

<!-- camera right IR joints and links -->
<joint name="${name}_infra2_joint" type="fixed">
<origin xyz="0 ${d455_cam_depth_to_infra2_offset} 0" rpy="0 0 0" />
<parent link="${name}_link" />
<child link="${name}_infra2_frame" />
</joint>
<link name="${name}_infra2_frame"/>
<link name="${name}_infra2_frame" />

<joint name="${name}_infra2_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="${name}_infra2_frame" />
<child link="${name}_infra2_optical_frame" />
</joint>
<link name="${name}_infra2_optical_frame"/>
<link name="${name}_infra2_optical_frame" />

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

<joint name="${name}_color_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
<parent link="${name}_color_frame" />
<child link="${name}_color_optical_frame" />
</joint>
<link name="${name}_color_optical_frame"/>
<link name="${name}_color_optical_frame" />

<!-- IMU -->
<!-- see datasheet Revision 009, page 114 -->
<xacro:property name="d455_imu_px" value="-0.01602"/>
<xacro:property name="d455_imu_py" value="-0.03022"/>
<xacro:property name="d455_imu_pz" value="+0.0074"/>
<xacro:property name="d455_imu_px" value="-0.01602" />
<xacro:property name="d455_imu_py" value="-0.03022" />
<xacro:property name="d455_imu_pz" value="+0.0074" />

<link name="${name}_accel_frame" />
<link name="${name}_accel_optical_frame" />
Expand Down Expand Up @@ -203,11 +204,11 @@ aluminum peripherial evaluation case.
</xacro:if>

<!-- Realsense Gazebo Plugin -->
<xacro:gazebo_d455 camera_name="${name}" reference_link="${name}_link" depth_optical_frame="${name}_depth_optical_frame" color_optical_frame="${name}_color_optical_frame" infrared1_optical_frame="${name}_left_ir_optical_frame" infrared2_optical_frame="${name}_right_ir_optical_frame" publish_pointcloud="true" accel_optical_frame="${name}_accel_optical_frame" gyro_optical_frame="${name}_gyro_optical_frame"/>
<xacro:gazebo_d455 camera_name="${name}" reference_link="${name}_link" depth_optical_frame="${name}_depth_optical_frame" color_optical_frame="${name}_color_optical_frame" infrared1_optical_frame="${name}_left_ir_optical_frame" infrared2_optical_frame="${name}_right_ir_optical_frame" publish_pointcloud="true" accel_optical_frame="${name}_accel_optical_frame" gyro_optical_frame="${name}_gyro_optical_frame" />

<xacro:if value="$(arg add_plug)">
<xacro:usb_plug parent="${name}_link" name="${name}_usb_plug">
<origin xyz="${-0.00406-d455_cam_depth_px} ${-0.03701-d455_cam_depth_py} ${-d455_cam_depth_pz}" rpy="${M_PI/2} 0 0"/>
<origin xyz="${-0.00406-d455_cam_depth_px} ${-0.03701-d455_cam_depth_py} ${-d455_cam_depth_pz}" rpy="${M_PI/2} 0 0" />
</xacro:usb_plug>
</xacro:if>
</xacro:macro>
Expand Down
13 changes: 7 additions & 6 deletions realsense2_description/urdf/_usb_plug.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,8 @@ This is the URDF model for the Intel RealSense 415 camera, in it's
aluminum peripherial evaluation case.
-->

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

Expand All @@ -33,18 +34,18 @@ aluminum peripherial evaluation case.
<link name="${name}_link">
<visual>
<!-- 0.044850 0.008000 0.018500 -->
<origin xyz="0. -0.022425 0." rpy="0 0 ${M_PI/2}"/>
<origin xyz="0. -0.022425 0." rpy="0 0 ${M_PI/2}" />
<geometry>
<!--box size="0.044850 0.008 0.0185" /-->
<mesh filename="file://$(find realsense2_description)/meshes/plug.stl" />
<mesh filename="package://realsense2_description/meshes/plug.stl" />
</geometry>
<material name="plastic"/>
<material name="plastic" />
</visual>
<collision>
<origin xyz="0. -0.022425 0." rpy="0 0 ${M_PI/2}"/>
<origin xyz="0. -0.022425 0." rpy="0 0 ${M_PI/2}" />
<geometry>
<!--box size="0.044850 0.008 0.0185" /-->
<mesh filename="file://$(find realsense2_description)/meshes/plug_collision.stl" />
<mesh filename="package://realsense2_description/meshes/plug_collision.stl" />
</geometry>
</collision>
</link>
Expand Down

0 comments on commit 54f0d13

Please sign in to comment.