Skip to content

Commit

Permalink
feat(aip_x1, aip_x1_1): use interpolate
Browse files Browse the repository at this point in the history
Signed-off-by: 1222-takeshi <[email protected]>
  • Loading branch information
1222-takeshi committed Feb 20, 2024
1 parent 199563e commit b02dc5e
Show file tree
Hide file tree
Showing 4 changed files with 65 additions and 39 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,20 +17,30 @@
negative: False

common_ground_filter:
plugin: "ground_segmentation::RayGroundFilterComponent"
plugin: "ground_segmentation::ScanGroundFilterComponent"
parameters:
initial_max_slope: 10.0
general_max_slope: 10.0
local_max_slope: 10.0
min_height_threshold: 0.3
radial_divider_angle: 1.0
concentric_divider_distance: 0.0
use_vehicle_footprint: True
global_slope_max_angle_deg: 10.0
local_slope_max_angle_deg: 13.0 # recommended 30.0 for non elevation_grid_mode
split_points_distance_tolerance: 0.2
use_virtual_ground_point: True
split_height_distance: 0.2
radial_divider_angle_deg: 1.0

# common_ground_filter:
# plugin: "ground_segmentation::RayGroundFilterComponent"
# parameters:
# initial_max_slope: 10.0
# general_max_slope: 10.0
# local_max_slope: 10.0
# min_height_threshold: 0.3
# radial_divider_angle: 1.0
# concentric_divider_distance: 0.0
# use_vehicle_footprint: True

short_height_obstacle_detection_area_filter:
parameters:
min_x: 0.0
max_x: 19.6 # max_x: 18.0m + base_link2livox_front_center distance 1.6m
max_x: 21.6 # max_x: 20.0m + base_link2xt32_front_center distance 1.6m
min_y: -4.0
max_y: 4.0
min_z: -0.5
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,8 @@ def __init__(self, context):
def get_vehicle_info(self):
# TODO: need to rename key from "ros_params" to "global_params" after Humble
gp = self.context.launch_configurations.get("ros_params", {})
if not gp:
gp = dict(self.context.launch_configurations.get("global_params", {}))
p = {}
p["vehicle_length"] = gp["front_overhang"] + gp["wheel_base"] + gp["rear_overhang"]
p["vehicle_width"] = gp["wheel_tread"] + gp["left_overhang"] + gp["right_overhang"]
Expand Down Expand Up @@ -82,8 +84,8 @@ def create_additional_pipeline(self, lidar_name):
{
"input_frame": LaunchConfiguration("base_frame"),
"output_frame": LaunchConfiguration("base_frame"),
"min_z": self.vehicle_info["min_height_offset"],
"max_z": self.vehicle_info["max_height_offset"],
# "min_z": self.vehicle_info["min_height_offset"],
# "max_z": self.vehicle_info["max_height_offset"],
},
self.ground_segmentation_param[f"{lidar_name}_crop_box_filter"]["parameters"],
],
Expand Down
42 changes: 21 additions & 21 deletions aip_x1_1_launch/launch/velodyne_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -104,35 +104,35 @@ def create_parameter_dict(*args):
)
)

# nodes.append(
# ComposableNode(
# package="velodyne_pointcloud",
# plugin="velodyne_pointcloud::Interpolate",
# name="velodyne_interpolate_node",
# remappings=[
# ("velodyne_points_ex", "self_cropped/pointcloud_ex"),
# ("velodyne_points_interpolate", "rectified/pointcloud"),
# ("velodyne_points_interpolate_ex", "rectified/pointcloud_ex"),
# ],
# extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
# )
# )

nodes.append(
ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::DistortionCorrectorComponent",
name="distortion_corrector_node",
package="velodyne_pointcloud",
plugin="velodyne_pointcloud::Interpolate",
name="velodyne_interpolate_node",
remappings=[
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("~/input/imu", "/sensing/imu/imu_data"),
("~/input/pointcloud", "self_cropped/pointcloud_ex"),
("~/output/pointcloud", "rectified/pointcloud_ex"),
("velodyne_points_ex", "self_cropped/pointcloud_ex"),
("velodyne_points_interpolate", "rectified/pointcloud"),
("velodyne_points_interpolate_ex", "rectified/pointcloud_ex"),
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
)

# nodes.append(
# ComposableNode(
# package="pointcloud_preprocessor",
# plugin="pointcloud_preprocessor::DistortionCorrectorComponent",
# name="distortion_corrector_node",
# remappings=[
# ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
# ("~/input/imu", "/sensing/imu/imu_data"),
# ("~/input/pointcloud", "self_cropped/pointcloud_ex"),
# ("~/output/pointcloud", "rectified/pointcloud_ex"),
# ],
# extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
# )
# )

nodes.append(
ComposableNode(
package="pointcloud_preprocessor",
Expand Down
28 changes: 21 additions & 7 deletions aip_x1_launch/launch/velodyne_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -104,16 +104,30 @@ def create_parameter_dict(*args):
)
)

# nodes.append(
# ComposableNode(
# package="pointcloud_preprocessor",
# plugin="pointcloud_preprocessor::DistortionCorrectorComponent",
# name="distortion_corrector_node",
# remappings=[
# ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
# ("~/input/imu", "/sensing/imu/imu_data"),
# ("~/input/pointcloud", "self_cropped/pointcloud_ex"),
# ("~/output/pointcloud", "rectified/pointcloud_ex"),
# ],
# extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
# )
# )

nodes.append(
ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::DistortionCorrectorComponent",
name="distortion_corrector_node",
package="velodyne_pointcloud",
plugin="velodyne_pointcloud::Interpolate",
name="velodyne_interpolate_node",
remappings=[
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("~/input/imu", "/sensing/imu/imu_data"),
("~/input/pointcloud", "self_cropped/pointcloud_ex"),
("~/output/pointcloud", "rectified/pointcloud_ex"),
("velodyne_points_ex", "self_cropped/pointcloud_ex"),
("velodyne_points_interpolate", "rectified/pointcloud"),
("velodyne_points_interpolate_ex", "rectified/pointcloud_ex"),
],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
Expand Down

0 comments on commit b02dc5e

Please sign in to comment.