Skip to content
Merged
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
2 changes: 0 additions & 2 deletions orbbec_description/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,6 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<exec_depend>realsense2_gz_description</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

Expand Down
52 changes: 20 additions & 32 deletions orbbec_description/urdf/gemini335L_336L_macro.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,7 @@
<xacro:macro name="gemini_335L_336L" params="
parent
prefix:='camera'
*origin
sim_gazebo:=false
gz_fps:='5'
gz_image_width:='848'
gz_image_height:='530'">
*origin">

<!-- The original link started with camera_link -->
<joint name="${prefix}_gemini_mount_fixed_joint" type="fixed">
Expand Down Expand Up @@ -51,7 +47,7 @@

<link name="${prefix}_color_screw_frame" />
<joint
name="${prefix}_color_screw_frame_joint"
name="${prefix}_color_screw_joint"
type="fixed">
<origin
xyz="0 0 0"
Expand All @@ -66,7 +62,7 @@

<link name="${prefix}_IMU_frame" />
<joint
name="${prefix}_IMU_frame_joint"
name="${prefix}_IMU_joint"
type="fixed">
<origin
xyz="-0.002535 0.039634 0.013243"
Expand All @@ -81,7 +77,7 @@

<link name="${prefix}_depth_frame" />
<joint
name="${prefix}_depth_frame_joint"
name="${prefix}_depth_joint"
type="fixed">
<origin
xyz="0.011715 0.0475 0.014311"
Expand All @@ -96,7 +92,7 @@

<link name="${prefix}_depth_optical_frame" />
<joint
name="${prefix}_depth_optical_frame_joint"
name="${prefix}_depth_optical_joint"
type="fixed">
<origin
xyz="0 0 0"
Expand All @@ -111,7 +107,7 @@

<link name="${prefix}_infra1_frame" />
<joint
name="${prefix}_infra1_frame_joint"
name="${prefix}_infra1_joint"
type="fixed">
<origin
xyz="0.011715 0.0475 0.014311"
Expand All @@ -126,7 +122,7 @@

<link name="${prefix}_infra1_optical_frame" />
<joint
name="${prefix}_infra1_optical_frame_joint"
name="${prefix}_infra1_optical_joint"
type="fixed">
<origin
xyz="0 0 0"
Expand All @@ -141,7 +137,7 @@

<link name="${prefix}_infra2_frame" />
<joint
name="${prefix}_infra2_frame_joint"
name="${prefix}_infra2_joint"
type="fixed">
<origin
xyz="0.011715 -0.0475 0.014311"
Expand All @@ -156,7 +152,7 @@

<link name="${prefix}_infra2_optical_frame" />
<joint
name="${prefix}_infra2_optical_frame_joint"
name="${prefix}_infra2_optical_joint"
type="fixed">
<origin
xyz="0 0 0"
Expand All @@ -169,9 +165,17 @@
xyz="0 0 0" />
</joint>

<link name="${prefix}_color_frame" />
<link name="${prefix}_color_frame" >
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="0.001" ixy="0" ixz="0"
iyx="0" iyy="0.001" iyz="0"
izx="0" izy="0" izz="0.001" />
</inertial>
</link>
<joint
name="${prefix}_color_frame_joint"
name="${prefix}_color_joint"
type="fixed">
<origin
xyz="0.011715 0.02375 0.014311"
Expand All @@ -186,7 +190,7 @@

<link name="${prefix}_color_optical_frame" />
<joint
name="${prefix}_color_optical_frame_joint"
name="${prefix}_color_optical_joint"
type="fixed">
<origin
xyz="0 0 0"
Expand All @@ -199,21 +203,5 @@
xyz="0 0 0" />
</joint>

<xacro:if value="${sim_gazebo}">
<!-- Use the realsense2_gz_description which can simulate a generic depth camera -->
<xacro:include filename="$(find realsense2_gz_description)/urdf/rgbd_camera.gazebo.xacro" />
<!-- TODO: Upstream changes required for a triggered RBGD camera -->
<xacro:gazebo_rgbd
name="${prefix}"
gz_topic_name="${prefix}"
fps="${gz_fps}"
image_width="${gz_image_width}"
image_height="${gz_image_height}"
h_fov="${94 * pi/180}"
v_fov="${68 * pi/180}"
min_depth="0.17"
max_depth="6.0" />
</xacro:if>

</xacro:macro>
</robot>
52 changes: 20 additions & 32 deletions orbbec_description/urdf/gemini335Le_macro.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,7 @@
<xacro:macro name="gemini_335Le" params="
parent
name:='camera'
*origin
sim_gazebo:=false
gz_fps:='5'
gz_image_width:='848'
gz_image_height:='530'">
*origin">

<!-- The original link started with camera_link -->
<joint name="${name}_gemini_mount_fixed_joint" type="fixed">
Expand Down Expand Up @@ -56,7 +52,7 @@

<link name="${name}_bottom_screw_frame" />
<joint
name="${name}_bottom_screw_frame_joint"
name="${name}_bottom_screw_joint"
type="fixed">
<origin
xyz="0 0 0"
Expand All @@ -71,7 +67,7 @@

<link name="${name}_infra2_frame" />
<joint
name="${name}_infra2_frame_joint"
name="${name}_infra2_joint"
type="fixed">
<origin
xyz="0.034005 -0.0475 0.014048"
Expand All @@ -86,7 +82,7 @@

<link name="${name}_infra2_optical_frame" />
<joint
name="${name}_infra2_optical_frame_joint"
name="${name}_infra2_optical_joint"
type="fixed">
<origin
xyz="0 0 0"
Expand All @@ -102,7 +98,7 @@

<link name="${name}_infra1_frame" />
<joint
name="${name}_infra1_frame_joint"
name="${name}_infra1_joint"
type="fixed">
<origin
xyz="0.034005 0.0475 0.014048"
Expand All @@ -117,7 +113,7 @@

<link name="${name}_infra1_optical_frame" />
<joint
name="${name}_infra1_optical_frame_joint"
name="${name}_infra1_optical_joint"
type="fixed">
<origin
xyz="0 0 0"
Expand All @@ -132,7 +128,7 @@

<link name="${name}_depth_frame" />
<joint
name="${name}_depth_frame_joint"
name="${name}_depth_joint"
type="fixed">
<parent
link="${name}_infra1_frame" />
Expand All @@ -144,7 +140,7 @@

<link name="${name}_depth_optical_frame" />
<joint
name="${name}_depth_optical_frame_joint"
name="${name}_depth_optical_joint"
type="fixed">
<parent
link="${name}_infra1_optical_frame" />
Expand All @@ -154,9 +150,17 @@
xyz="0 0 0" />
</joint>

<link name="${name}_color_frame" />
<link name="${name}_color_frame" >
<inertial>
<mass value="0.01" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="0.001" ixy="0" ixz="0"
iyx="0" iyy="0.001" iyz="0"
izx="0" izy="0" izz="0.001" />
</inertial>
</link>
<joint
name="${name}_frame_frame_joint"
name="${name}_color_joint"
type="fixed">
<origin
xyz="0.034014 0.02375 0.014048"
Expand All @@ -171,7 +175,7 @@

<link name="${name}_color_optical_frame" />
<joint
name="${name}_color_optical_frame_joint"
name="${name}_color_optical_joint"
type="fixed">
<origin
xyz="0 0 0"
Expand All @@ -186,7 +190,7 @@

<link name="${name}_imu_frame" />
<joint
name="${name}_imu_frame_joint"
name="${name}_imu_joint"
type="fixed">
<origin
xyz="0.019757 0.03619 0.013358"
Expand All @@ -199,21 +203,5 @@
xyz="0 0 0" />
</joint>

<xacro:if value="${sim_gazebo}">
<!-- Use the realsense2_gz_description which can simulate a generic depth camera -->
<xacro:include filename="$(find realsense2_gz_description)/urdf/rgbd_camera.gazebo.xacro" />
<!-- TODO: Upstream changes required for a triggered RBGD camera -->
<xacro:gazebo_rgbd
name="${name}"
gz_topic_name="${name}"
fps="${gz_fps}"
image_width="${gz_image_width}"
image_height="${gz_image_height}"
h_fov="${94 * pi/180}"
v_fov="${68 * pi/180}"
min_depth="0.25"
max_depth="6.0" />
</xacro:if>

</xacro:macro>
</robot>