Skip to content

Commit

Permalink
top urdf: xacro: Rename perception_kit to camera_kit
Browse files Browse the repository at this point in the history
  • Loading branch information
PangKW-weston committed Aug 21, 2024
1 parent d1322bc commit 7a2a078
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 15 deletions.
26 changes: 13 additions & 13 deletions src/kits/top/mid360_sensor_kit_bringup/urdf/sensor_kit.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -66,13 +66,13 @@
<link name="livox_frame">
</link>

<joint name="perception_kit_base_joint" type="fixed">
<joint name="camera_kit_base_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="top_sensor_kit_link" />
<child link="perception_kit_base_link" />
<child link="camera_kit_base_link" />
</joint>

<link name="perception_kit_base_link">
<link name="camera_kit_base_link">
<inertial>
<origin xyz="0 0 -0.345" rpy="${M_PI/2} 0 ${M_PI/2}" />
<mass value="0.0" />
Expand All @@ -82,7 +82,7 @@
<origin xyz="0 0 -0.345" rpy="${M_PI/2} 0 ${M_PI/2}" />
<geometry>
<mesh
filename="package://mid360_sensor_kit_bringup/meshes/perception_kit_base_link.stl"
filename="package://mid360_sensor_kit_bringup/meshes/camera_kit_base_link.stl"
scale="0.001 0.001 0.001" />
</geometry>
<material name="silver" />
Expand All @@ -91,26 +91,26 @@
<origin xyz="0 0 -0.345" rpy="${M_PI/2} 0 ${M_PI/2}" />
<geometry>
<mesh
filename="package://mid360_sensor_kit_bringup/meshes/perception_kit_base_link.stl"
filename="package://mid360_sensor_kit_bringup/meshes/camera_kit_base_link.stl"
scale="0.001 0.001 0.001" />
</geometry>
</collision>
</link>

<xacro:perception_kit camera_pos="front" camera_type="$(arg front_camera)">
<xacro:camera_kit camera_pos="front" camera_type="$(arg front_camera)">
<origin xyz="0.118 0 -0.025" rpy="0 0 0" />
</xacro:perception_kit>
</xacro:camera_kit>

<xacro:perception_kit camera_pos="rear" camera_type="$(arg rear_camera)">
<xacro:camera_kit camera_pos="rear" camera_type="$(arg rear_camera)">
<origin xyz="-0.118 0 -0.025" rpy="0 0 ${M_PI}" />
</xacro:perception_kit>
</xacro:camera_kit>

<xacro:perception_kit camera_pos="left" camera_type="$(arg left_camera)">
<xacro:camera_kit camera_pos="left" camera_type="$(arg left_camera)">
<origin xyz="0 0.083 -0.025" rpy="0 0 ${M_PI/2}" />
</xacro:perception_kit>
</xacro:camera_kit>

<xacro:perception_kit camera_pos="right" camera_type="$(arg right_camera)">
<xacro:camera_kit camera_pos="right" camera_type="$(arg right_camera)">
<origin xyz="0 -0.083 -0.025" rpy="0 0 -${M_PI/2}" />
</xacro:perception_kit>
</xacro:camera_kit>

</robot>
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<robot name="mid360_sensor_kit" xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="perception_kit" params="camera_pos camera_type *origin">
<xacro:macro name="camera_kit" params="camera_pos camera_type *origin">

<xacro:arg name="use_nominal_extrinsics" default="false"/>
<xacro:include filename="$(find realsense2_description)/urdf/_d435.urdf.xacro" />
Expand Down Expand Up @@ -35,7 +35,7 @@
</link>

<joint name="${camera_pos}_camera_joint" type="fixed">
<parent link="perception_kit_base_link" />
<parent link="camera_kit_base_link" />
<child link="${camera_pos}_camera_link" />
<xacro:insert_block name="origin" />
</joint>
Expand Down

0 comments on commit 7a2a078

Please sign in to comment.