Skip to content

Commit

Permalink
create xacro macro for sensors
Browse files Browse the repository at this point in the history
Signed-off-by: Autumn60 <harada.akiro@gmail.com>
  • Loading branch information
Autumn60 committed Aug 30, 2024
1 parent ebe2c2f commit 4477d00
Show file tree
Hide file tree
Showing 5 changed files with 93 additions and 52 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="front_lrf" params="name parent *joint_origin">
<link name="${name}_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://fourth_robot_sensor_kit_description/mesh/front_lrf/front_lrf.dae"/>
</geometry>
</visual>
</link>

<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="joint_origin"/>
<parent link="${parent}"/>
<child link="${name}_link"/>
</joint>
</xacro:macro>
</robot>
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="gim30" params="name parent *joint_origin">
<link name="${name}_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://fourth_robot_sensor_kit_description/mesh/gim30/gim30.dae"/>
</geometry>
</visual>
</link>

<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="joint_origin"/>
<parent link="${parent}"/>
<child link="${name}_link"/>
</joint>
</xacro:macro>
</robot>
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="gps" params="name parent *joint_origin">
<link name="${name}_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://fourth_robot_sensor_kit_description/mesh/gps/gps.dae"/>
</geometry>
</visual>
</link>

<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="joint_origin"/>
<parent link="${parent}"/>
<child link="${name}_link"/>
</joint>
</xacro:macro>
</robot>
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="rear_lrf" params="name parent *joint_origin">
<link name="${name}_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://fourth_robot_sensor_kit_description/mesh/rear_lrf/rear_lrf.dae"/>
</geometry>
</visual>
</link>

<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="joint_origin"/>
<parent link="${parent}"/>
<child link="${name}_link"/>
</joint>
</xacro:macro>
</robot>
Original file line number Diff line number Diff line change
Expand Up @@ -2,38 +2,23 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="sensors_calibration" value="${xacro.load_yaml('$(find fourth_robot_sensor_kit_description)/config/sensors_calibration.param.yaml')}"/>

<link name="front_lrf_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://fourth_robot_sensor_kit_description/mesh/front_lrf/front_lrf.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<joint name="front_lrf_joint" type="fixed">
<parent link="base_link"/>
<child link="front_lrf_link"/>
<xacro:include filename="$(find fourth_robot_sensor_kit_description)/urdf/front_lrf/front_lrf.urdf.xacro"/>
<xacro:include filename="$(find fourth_robot_sensor_kit_description)/urdf/rear_lrf/rear_lrf.urdf.xacro"/>
<xacro:include filename="$(find fourth_robot_sensor_kit_description)/urdf/gim30/gim30.urdf.xacro"/>
<xacro:include filename="$(find fourth_robot_sensor_kit_description)/urdf/gps/gps.urdf.xacro"/>

<xacro:front_lrf name="front_lrf" parent="base_link">
<origin
xyz="${sensors_calibration['base_link']['front_lrf_link']['x']}
${sensors_calibration['base_link']['front_lrf_link']['y']}
${sensors_calibration['base_link']['front_lrf_link']['z']}"
${sensors_calibration['base_link']['front_lrf_link']['y']}
${sensors_calibration['base_link']['front_lrf_link']['z']}"
rpy="${sensors_calibration['base_link']['front_lrf_link']['roll']}
${sensors_calibration['base_link']['front_lrf_link']['pitch']}
${sensors_calibration['base_link']['front_lrf_link']['yaw']}"
${sensors_calibration['base_link']['front_lrf_link']['pitch']}
${sensors_calibration['base_link']['front_lrf_link']['yaw']}"
/>
</joint>
</xacro:front_lrf>

<link name="rear_lrf_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://fourth_robot_sensor_kit_description/mesh/rear_lrf/rear_lrf.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<joint name="rear_lrf_joint" type="fixed">
<parent link="base_link"/>
<child link="rear_lrf_link"/>
<xacro:rear_lrf name="rear_lrf" parent="base_link">
<origin
xyz="${sensors_calibration['base_link']['rear_lrf_link']['x']}
${sensors_calibration['base_link']['rear_lrf_link']['y']}
Expand All @@ -42,19 +27,9 @@
${sensors_calibration['base_link']['rear_lrf_link']['pitch']}
${sensors_calibration['base_link']['rear_lrf_link']['yaw']}"
/>
</joint>
</xacro:rear_lrf>

<link name="gim30_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://fourth_robot_sensor_kit_description/mesh/gim30/gim30.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<joint name="gim30_joint" type="fixed">
<parent link="base_link"/>
<child link="gim30_link"/>
<xacro:gim30 name="gim30" parent="base_link">
<origin
xyz="${sensors_calibration['base_link']['gim30_link']['x']}
${sensors_calibration['base_link']['gim30_link']['y']}
Expand All @@ -63,19 +38,9 @@
${sensors_calibration['base_link']['gim30_link']['pitch']}
${sensors_calibration['base_link']['gim30_link']['yaw']}"
/>
</joint>
</xacro:gim30>

<link name="gps_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://fourth_robot_sensor_kit_description/mesh/gps/gps.dae" scale="1 1 1"/>
</geometry>
</visual>
</link>
<joint name="gps_joint" type="fixed">
<parent link="base_link"/>
<child link="gps_link"/>
<xacro:gps name="gps" parent="base_link">
<origin
xyz="${sensors_calibration['base_link']['gps_link']['x']}
${sensors_calibration['base_link']['gps_link']['y']}
Expand All @@ -84,5 +49,5 @@
${sensors_calibration['base_link']['gps_link']['pitch']}
${sensors_calibration['base_link']['gps_link']['yaw']}"
/>
</joint>
</xacro:gps>
</robot>

0 comments on commit 4477d00

Please sign in to comment.