Skip to content

Commit

Permalink
Use simulation flag to decide how to load meshes. (#524)
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl authored May 14, 2024
1 parent 0ef4b38 commit 0144d79
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 5 deletions.
20 changes: 17 additions & 3 deletions depthai_descriptions/urdf/include/base_macro.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,21 @@

<xacro:macro name="base" params="camera_name camera_model parent base_frame
cam_pos_x cam_pos_y cam_pos_z
cam_roll cam_pitch cam_yaw has_imu r:=0.8 g:=0.8 b:=0.8 a:=0.8 ">
cam_roll cam_pitch cam_yaw has_imu r:=0.8 g:=0.8 b:=0.8 a:=0.8 simulation:=false">

<xacro:if value="${simulation}">
<xacro:property
name="file_prefix"
value="file://$(find depthai_descriptions)"
/>
</xacro:if>
<xacro:unless value="${simulation}">
<xacro:property
name="file_prefix"
value="package://depthai_descriptions"
/>
</xacro:unless>

<!-- base_link of the sensor-->
<link name="${base_frame}"/>
<xacro:property name="M_PI" value="3.1415926535897931" />
Expand All @@ -21,7 +35,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="file://$(find depthai_descriptions)/urdf/models/${model}.stl" />
<mesh filename="${file_prefix}/urdf/models/${model}.stl" />
</geometry>
<material name="mat">
<color rgba="${r} ${g} ${b} ${a}"/>
Expand Down Expand Up @@ -75,4 +89,4 @@
</xacro:if>

</xacro:macro>
</robot>
</robot>
4 changes: 2 additions & 2 deletions depthai_descriptions/urdf/include/depthai_macro.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

<xacro:macro name="depthai_camera" params="camera_name camera_model parent base_frame
cam_pos_x cam_pos_y cam_pos_z
cam_roll cam_pitch cam_yaw r:=0.8 g:=0.8 b:=0.8 a:=0.8 ">
cam_roll cam_pitch cam_yaw r:=0.8 g:=0.8 b:=0.8 a:=0.8 simulation:=false">

<xacro:include filename="$(find depthai_descriptions)/urdf/include/base_macro.urdf.xacro"/>
<xacro:property name="M_PI" value="3.1415926535897931" />
Expand All @@ -20,7 +20,7 @@
<xacro:property name="has_imu" value="true" />
</xacro:if>

<xacro:base camera_name="${camera_name}" parent="${parent}" camera_model="${camera_model}" base_frame="${base_frame}" cam_pos_x="${cam_pos_x}" cam_pos_y="${cam_pos_y}" cam_pos_z="${cam_pos_z}" cam_roll="${cam_roll}" cam_pitch="${cam_pitch}" cam_yaw="${cam_yaw}" has_imu="${has_imu}"/>
<xacro:base camera_name="${camera_name}" parent="${parent}" camera_model="${camera_model}" base_frame="${base_frame}" cam_pos_x="${cam_pos_x}" cam_pos_y="${cam_pos_y}" cam_pos_z="${cam_pos_z}" cam_roll="${cam_roll}" cam_pitch="${cam_pitch}" cam_yaw="${cam_yaw}" has_imu="${has_imu}" simulation="${simulation}"/>

<!-- RGB Camera -->
<xacro:unless value="${model in ['OAK-D-SR']}">
Expand Down

0 comments on commit 0144d79

Please sign in to comment.