Skip to content

Commit

Permalink
feat(extrinsic_ground_plane_calibrator): redesign, generalization, an…
Browse files Browse the repository at this point in the history
…d improvement of the calibrator (#97)

* Refactored/improved some parts of the ground plane calibrator and made it usable for the xx1/omiya combination

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* Changing default parameters for the review

* Added launchers for the x2

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* Fixed typo

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* Fixed typos in the launchers

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

* Fixed one last typo

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>

---------

Signed-off-by: Kenzo Lobos-Tsunekawa <[email protected]>
  • Loading branch information
knzo25 authored Sep 28, 2023
1 parent 880695b commit 62957b2
Show file tree
Hide file tree
Showing 15 changed files with 1,507 additions and 283 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="vehicle_id" default="default"/>
<let name="sensor_model" value="aip_x2"/>
<arg name="rviz" default="false"/>

<let name="rviz_profile" value="$(find-pkg-share extrinsic_ground_plane_calibrator)/rviz/x2.rviz"/>

<!--2023/04/21 - Parking lot -->
<let name="use_crop_box_filter" value="true"/>
<let name="crop_box_min_x" value="-12.0"/>
<let name="crop_box_min_y" value="-12.0"/>
<let name="crop_box_min_z" value="-12.0"/>
<let name="crop_box_max_x" value="12.0"/>
<let name="crop_box_max_y" value="12.0"/>
<let name="crop_box_max_z" value="-0.5"/>

<group>
<push-ros-namespace namespace="front_unit"/>
<include file="$(find-pkg-share extrinsic_calibration_manager)/launch/$(var sensor_model)/ground_plane_front_unit.launch.xml">
<arg name="vehicle_id" value="$(var vehicle_id)"/>
<arg name="sensor_model" value="$(var sensor_model)"/>

<arg name="use_crop_box_filter" value="$(var use_crop_box_filter)"/>
<arg name="crop_box_min_x" value="$(var crop_box_min_x)"/>
<arg name="crop_box_min_y" value="$(var crop_box_min_y)"/>
<arg name="crop_box_min_z" value="$(var crop_box_min_z)"/>
<arg name="crop_box_max_x" value="$(var crop_box_max_x)"/>
<arg name="crop_box_max_y" value="$(var crop_box_max_y)"/>
<arg name="crop_box_max_z" value="$(var crop_box_max_z)"/>
</include>
</group>

<group>
<push-ros-namespace namespace="rear_unit"/>
<include file="$(find-pkg-share extrinsic_calibration_manager)/launch/$(var sensor_model)/ground_plane_rear_unit.launch.xml">
<arg name="vehicle_id" value="$(var vehicle_id)"/>
<arg name="sensor_model" value="$(var sensor_model)"/>

<arg name="use_crop_box_filter" value="$(var use_crop_box_filter)"/>
<arg name="crop_box_min_x" value="$(var crop_box_min_x)"/>
<arg name="crop_box_min_y" value="$(var crop_box_min_y)"/>
<arg name="crop_box_min_z" value="$(var crop_box_min_z)"/>
<arg name="crop_box_max_x" value="$(var crop_box_max_x)"/>
<arg name="crop_box_max_y" value="$(var crop_box_max_y)"/>
<arg name="crop_box_max_z" value="$(var crop_box_max_z)"/>
</include>
</group>

<group>
<push-ros-namespace namespace="top_unit"/>
<include file="$(find-pkg-share extrinsic_calibration_manager)/launch/$(var sensor_model)/ground_plane_top_unit.launch.xml">
<arg name="vehicle_id" value="$(var vehicle_id)"/>
<arg name="sensor_model" value="$(var sensor_model)"/>

<arg name="use_crop_box_filter" value="$(var use_crop_box_filter)"/>
<arg name="crop_box_min_x" value="$(var crop_box_min_x)"/>
<arg name="crop_box_min_y" value="$(var crop_box_min_y)"/>
<arg name="crop_box_min_z" value="$(var crop_box_min_z)"/>
<arg name="crop_box_max_x" value="$(var crop_box_max_x)"/>
<arg name="crop_box_max_y" value="$(var crop_box_max_y)"/>
<arg name="crop_box_max_z" value="$(var crop_box_max_z)"/>
</include>
</group>

<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(var rviz_profile)" if="$(var rviz)"/>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="vehicle_id" default="default"/>
<let name="sensor_model" value="aip_x2"/>
<let name="base_frame" value="base_link"/>
<let name="parent_frame" value="base_link"/>
<let name="child_frame" value="front_unit_base_link"/>
<let name="pointcloud_topic" value="/sensing/lidar/front_lower/pointcloud_raw"/>

<arg name="use_crop_box_filter"/>
<arg name="crop_box_min_x"/>
<arg name="crop_box_min_y"/>
<arg name="crop_box_min_z"/>
<arg name="crop_box_max_x"/>
<arg name="crop_box_max_y"/>
<arg name="crop_box_max_z"/>

<!-- extrinsic_calibration_client -->
<arg name="src_yaml" default="$(find-pkg-share individual_params)/config/$(var vehicle_id)/$(var sensor_model)/sensors_calibration.yaml"/>
<arg name="dst_yaml" default="$(env HOME)/sensors_calibration_front.yaml"/>

<node pkg="extrinsic_calibration_client" exec="extrinsic_calibration_client" name="extrinsic_calibration_client" output="screen">
<param name="src_path" value="$(var src_yaml)"/>
<param name="dst_path" value="$(var dst_yaml)"/>
</node>

<!-- extrinsic_calibration_manager -->
<node pkg="extrinsic_calibration_manager" exec="extrinsic_calibration_manager" name="extrinsic_calibration_manager" output="screen">
<param name="parent_frame" value="$(var parent_frame)"/>
<param name="child_frames" value="
[$(var child_frame)]"/>
</node>

<!-- front_unit_base_link: extrinsic_ground_plane_calibrator -->
<group>
<include file="$(find-pkg-share extrinsic_ground_plane_calibrator)/launch/calibrator.launch.xml">
<arg name="ns" value="$(var parent_frame)/$(var child_frame)"/>
<arg name="base_frame" value="$(var base_frame)"/>
<arg name="parent_frame" value="$(var parent_frame)"/>
<arg name="child_frame" value="$(var child_frame)"/>
<arg name="pointcloud_topic" value="$(var pointcloud_topic)"/>

<arg name="min_plane_points_percentage" value="5.0"/>

<arg name="use_crop_box_filter" value="$(var use_crop_box_filter)"/>
<arg name="crop_box_min_x" value="$(var crop_box_min_x)"/>
<arg name="crop_box_min_y" value="$(var crop_box_min_y)"/>
<arg name="crop_box_min_z" value="$(var crop_box_min_z)"/>
<arg name="crop_box_max_x" value="$(var crop_box_max_x)"/>
<arg name="crop_box_max_y" value="$(var crop_box_max_y)"/>
<arg name="crop_box_max_z" value="$(var crop_box_max_z)"/>
</include>
</group>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="vehicle_id" default="default"/>
<let name="sensor_model" value="aip_x2"/>
<let name="base_frame" value="base_link"/>
<let name="parent_frame" value="base_link"/>
<let name="child_frame" value="rear_unit_base_link"/>
<let name="pointcloud_topic" value="/sensing/lidar/rear_lower/pointcloud_raw"/>

<let name="rviz_profile" value="$(find-pkg-share extrinsic_ground_plane_calibrator)/rviz/xx1.rviz"/>
<arg name="rviz" default="true"/>

<!-- extrinsic_calibration_client -->
<arg name="src_yaml" default="$(find-pkg-share individual_params)/config/$(var vehicle_id)/$(var sensor_model)/sensors_calibration.yaml"/>
<arg name="dst_yaml" default="$(env HOME)/sensors_calibration_rear.yaml"/>

<node pkg="extrinsic_calibration_client" exec="extrinsic_calibration_client" name="extrinsic_calibration_client" output="screen">
<param name="src_path" value="$(var src_yaml)"/>
<param name="dst_path" value="$(var dst_yaml)"/>
</node>

<!-- extrinsic_calibration_manager -->
<node pkg="extrinsic_calibration_manager" exec="extrinsic_calibration_manager" name="extrinsic_calibration_manager" output="screen">
<param name="parent_frame" value="$(var parent_frame)"/>
<param name="child_frames" value="
[$(var child_frame)]"/>
</node>

<!-- rear_unit_base_link: extrinsic_ground_plane_calibrator -->
<group>
<include file="$(find-pkg-share extrinsic_ground_plane_calibrator)/launch/calibrator.launch.xml">
<arg name="ns" value="$(var parent_frame)/$(var child_frame)"/>
<arg name="base_frame" value="$(var base_frame)"/>
<arg name="parent_frame" value="$(var parent_frame)"/>
<arg name="child_frame" value="$(var child_frame)"/>
<arg name="pointcloud_topic" value="$(var pointcloud_topic)"/>

<arg name="min_plane_points_percentage" value="5.0"/>

<arg name="use_crop_box_filter" value="$(var use_crop_box_filter)"/>
<arg name="crop_box_min_x" value="$(var crop_box_min_x)"/>
<arg name="crop_box_min_y" value="$(var crop_box_min_y)"/>
<arg name="crop_box_min_z" value="$(var crop_box_min_z)"/>
<arg name="crop_box_max_x" value="$(var crop_box_max_x)"/>
<arg name="crop_box_max_y" value="$(var crop_box_max_y)"/>
<arg name="crop_box_max_z" value="$(var crop_box_max_z)"/>
</include>
</group>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="vehicle_id" default="default"/>
<let name="sensor_model" value="aip_x2"/>
<let name="base_frame" value="base_link"/>
<let name="parent_frame" value="base_link"/>
<let name="child_frame" value="top_unit_base_link"/>
<let name="pointcloud_topic" value="/sensing/lidar/left_upper/pointcloud_raw"/>

<!-- extrinsic_calibration_client -->
<arg name="src_yaml" default="$(find-pkg-share individual_params)/config/$(var vehicle_id)/$(var sensor_model)/sensors_calibration.yaml"/>
<arg name="dst_yaml" default="$(env HOME)/sensors_calibration_top.yaml"/>

<node pkg="extrinsic_calibration_client" exec="extrinsic_calibration_client" name="extrinsic_calibration_client" output="screen">
<param name="src_path" value="$(var src_yaml)"/>
<param name="dst_path" value="$(var dst_yaml)"/>
</node>

<!-- extrinsic_calibration_manager -->
<node pkg="extrinsic_calibration_manager" exec="extrinsic_calibration_manager" name="extrinsic_calibration_manager" output="screen">
<param name="parent_frame" value="$(var parent_frame)"/>
<param name="child_frames" value="
[$(var child_frame)]"/>
</node>

<!-- top_unit_base_link: extrinsic_ground_plane_calibrator -->
<group>
<include file="$(find-pkg-share extrinsic_ground_plane_calibrator)/launch/calibrator.launch.xml">
<arg name="ns" value="$(var parent_frame)/$(var child_frame)"/>
<arg name="base_frame" value="$(var base_frame)"/>
<arg name="parent_frame" value="$(var parent_frame)"/>
<arg name="child_frame" value="$(var child_frame)"/>
<arg name="pointcloud_topic" value="$(var pointcloud_topic)"/>

<arg name="min_plane_points_percentage" value="5.0"/>

<arg name="use_crop_box_filter" value="$(var use_crop_box_filter)"/>
<arg name="crop_box_min_x" value="$(var crop_box_min_x)"/>
<arg name="crop_box_min_y" value="$(var crop_box_min_y)"/>
<arg name="crop_box_min_z" value="$(var crop_box_min_z)"/>
<arg name="crop_box_max_x" value="$(var crop_box_max_x)"/>
<arg name="crop_box_max_y" value="$(var crop_box_max_y)"/>
<arg name="crop_box_max_z" value="$(var crop_box_max_z)"/>
</include>
</group>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,9 @@
<let name="sensor_model" value="aip_xx1"/>

<group>
<push-ros-namespace namespace="sensor_kit"/>
<include file="$(find-pkg-share extrinsic_calibration_manager)/launch/$(var sensor_model)/ground_plane_sensor_kit.launch.xml">
<push-ros-namespace namespace="sensors"/>
<include file="$(find-pkg-share extrinsic_calibration_manager)/launch/$(var sensor_model)/ground_plane_sensors.launch.xml">
<arg name="vehicle_id" value="$(var vehicle_id)"/>
</include>
</group>

<!--group>
<push-ros-namespace namespace="sensors" />
<include file="$(find-pkg-share extrinsic_calibration_manager)/launch/$(var sensor_model)/ground_plane_sensors.launch.xml">
<arg name="vehicle_id" value="$(var vehicle_id)" />
</include>
</group-->
</launch>

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,9 @@
<let name="base_frame" value="base_link"/>
<let name="parent_frame" value="base_link"/>

<let name="rviz_profile" value="$(find-pkg-share extrinsic_ground_plane_calibrator)/rviz/xx1.rviz"/>
<arg name="rviz" default="true"/>

<!-- extrinsic_calibration_client -->
<arg name="src_yaml" default="$(find-pkg-share individual_params)/config/$(var vehicle_id)/$(var sensor_model)/sensors_calibration.yaml"/>
<arg name="dst_yaml" default="$(env HOME)/sensors_calibration.yaml"/>
Expand All @@ -18,17 +21,48 @@
<node pkg="extrinsic_calibration_manager" exec="extrinsic_calibration_manager" name="extrinsic_calibration_manager" output="screen">
<param name="parent_frame" value="$(var parent_frame)"/>
<param name="child_frames" value="
[velodyne_rear_base_link]"/>
[sensor_kit_base_link]"/>
</node>

<!-- velodyne_rear_base_link: extrinsic_ground_plane_calibrator -->
<!-- sensor_kit_base_link: extrinsic_ground_plane_calibrator -->
<group>
<include file="$(find-pkg-share extrinsic_ground_plane_calibrator)/launch/calibrator.launch.xml">
<arg name="ns" value="$(var parent_frame)/velodyne_rear_base_link"/>
<arg name="ns" value="$(var parent_frame)/sensor_kit_base_link"/>
<arg name="base_frame" value="$(var base_frame)"/>
<arg name="parent_frame" value="$(var parent_frame)"/>
<arg name="child_frame" value="velodyne_rear_base_link"/>
<arg name="pointcloud_topic" value="/sensing/lidar/rear/pointcloud_raw"/>
<arg name="child_frame" value="sensor_kit_base_link"/>
<arg name="pointcloud_topic" value="/sensing/lidar/top/pointcloud_raw"/>

<arg name="min_plane_points_percentage" value="5.0"/>

<!--2023/03/23 - Inside garage -->
<!--arg name="use_crop_box_filter" value="true" />
<arg name="crop_box_min_x" value="-3.0" />
<arg name="crop_box_min_y" value="-9.0" />
<arg name="crop_box_min_z" value="-3.0" />
<arg name="crop_box_max_x" value="3.0" />
<arg name="crop_box_max_y" value="9.0" />
<arg name="crop_box_max_z" value="-1.0" /-->

<!--2023/03/23 - Parking lot - 1 -->
<arg name="use_crop_box_filter" value="true"/>
<arg name="crop_box_min_x" value="-9.0"/>
<arg name="crop_box_min_y" value="-9.0"/>
<arg name="crop_box_min_z" value="-9.0"/>
<arg name="crop_box_max_x" value="9.0"/>
<arg name="crop_box_max_y" value="9.0"/>
<arg name="crop_box_max_z" value="-1.0"/>

<!--2023/03/23 - Parking lot - 2 -->
<!--arg name="use_crop_box_filter" value="true" />
<arg name="crop_box_min_x" value="-15.0" />
<arg name="crop_box_min_y" value="-15.0" />
<arg name="crop_box_min_z" value="-3.0" />
<arg name="crop_box_max_x" value="15.0" />
<arg name="crop_box_max_y" value="15.0" />
<arg name="crop_box_max_z" value="-1.0" /-->
</include>
</group>

<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(var rviz_profile)" if="$(var rviz)"/>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -113,9 +113,7 @@
<group if="$(eval &quot;'$(var mode)' == 'ground_plane' &quot;)">
<include file="$(find-pkg-share extrinsic_calibration_manager)/launch/$(var sensor_model)/ground_plane.launch.xml">
<arg name="vehicle_id" value="$(var vehicle_id)"/>
<arg name="map_path" value="$(var map_path)"/>
<arg name="pointcloud_map_file" value="$(var pointcloud_map_file)"/>
<arg name="map_calibration_area_file" value="$(var map_calibration_area_file)"/>
<arg name="rviz" value="$(var calibration_rviz)"/>
</include>
</group>

Expand Down
Loading

0 comments on commit 62957b2

Please sign in to comment.