Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(autoware_pointcloud_preprocessor): launch file load parameter from yaml #8129

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

[imho]
I think it's better to use launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value)) to enable launch args so that user can give parameter file from outside of this launcher. (But you can do this in another PR.)

Copy link
Contributor Author

@vividf vividf Nov 7, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sorry for the late reply!

I understand your concern for consistency.
However, using that makes the launcher more complex than before (and 15 -20 lines more)

I would like to keep it for this PR. If it is really needed, let me work on it on another PR :)

Thanks!

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If it is really needed, let me work on it on another PR :)

I agree! Thanks for your reply!

Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
import launch
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
import yaml
from launch_ros.parameter_descriptions import ParameterFile


def generate_launch_description():
Expand All @@ -29,19 +29,11 @@ def generate_launch_description():
get_package_share_directory("autoware_vehicle_info_utils"), "config/polygon_remover.yaml"
)

with open(param_file, "r") as f:
polygon_remover_param = yaml.safe_load(f)["/**"]["ros__parameters"]

my_component = ComposableNode(
package=pkg,
plugin="autoware::pointcloud_preprocessor::PolygonRemoverComponent",
name="polygon_remover",
parameters=[
{
"polygon_vertices": polygon_remover_param["polygon_vertices"],
"will_visualize": polygon_remover_param["will_visualize"],
}
],
parameters=[ParameterFile(param_file, allow_substs=True)],
)

# set container to run all required components in the same process
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,9 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import os

from ament_index_python.packages import get_package_share_directory
import launch
from launch.actions import DeclareLaunchArgument
from launch.actions import LogInfo
Expand All @@ -20,6 +23,7 @@
from launch.substitutions import PythonExpression
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
from launch_ros.parameter_descriptions import ParameterFile


def launch_setup(context, *args, **kwargs):
Expand All @@ -33,91 +37,107 @@
separate_concatenate_node_and_time_sync_node.lower() == "true"
)

concatenate_and_time_sync_node_param = ParameterFile(
param_file=LaunchConfiguration("concatenate_and_time_sync_node_param_path").perform(
context
),
allow_substs=True,
)
concatenate_pointclouds_node_param = ParameterFile(
param_file=LaunchConfiguration("concatenate_pointclouds_node_param_path").perform(context),
allow_substs=True,
)
time_synchronizer_node_param = ParameterFile(
param_file=LaunchConfiguration("time_synchronizer_node_param_path").perform(context),
allow_substs=True,
)
filter_base_param = ParameterFile(
param_file=LaunchConfiguration("filter_base_param_path").perform(context),
allow_substs=True,
)
crop_box_filter_node_param = ParameterFile(
param_file=LaunchConfiguration("crop_box_filter_node_param_path").perform(context),
allow_substs=True,
)

if not is_separate_concatenate_node_and_time_sync_node:
sync_and_concat_component = ComposableNode(
package=pkg,
plugin="autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent",
name="sync_and_concatenate_filter",
remappings=[
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("output", "points_raw/concatenated"),
],
parameters=[
concatenate_and_time_sync_node_param,
{
"input_topics": LaunchConfiguration("input_points_raw_list"),
"output_frame": LaunchConfiguration("tf_output_frame"),
"approximate_sync": True,
"publish_synchronized_pointcloud": False,
"input_twist_topic_type": "twist",
}
},
],
)
concat_components = [sync_and_concat_component]
else:
time_sync_component = ComposableNode(
package=pkg,
plugin="autoware::pointcloud_preprocessor::PointCloudDataSynchronizerComponent",
name="synchronizer_filter",
remappings=[
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("output", "points_raw/concatenated"),
],
parameters=[
time_synchronizer_node_param,
{
"input_topics": LaunchConfiguration("input_points_raw_list"),
"output_frame": LaunchConfiguration("tf_output_frame"),
"approximate_sync": True,
}
},
],
)

concat_component = ComposableNode(
package=pkg,
plugin="autoware::pointcloud_preprocessor::PointCloudConcatenationComponent",
name="concatenate_filter",
remappings=[("output", "points_raw/concatenated")],
parameters=[
concatenate_pointclouds_node_param,
{
"input_topics": LaunchConfiguration("input_points_raw_list"),
"output_frame": LaunchConfiguration("tf_output_frame"),
"approximate_sync": True,
}
},
],
)
concat_components = [time_sync_component, concat_component]

# set crop box filter as a component
cropbox_component = ComposableNode(
package=pkg,
plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent",
name="crop_box_filter",
remappings=[
(
"input",
PythonExpression(
[
"'points_raw/concatenated' if len(",
LaunchConfiguration("input_points_raw_list"),
") > 1 else ",
LaunchConfiguration("input_points_raw_list"),
"[0]",
]
),
),
("output", LaunchConfiguration("output_points_raw")),
],
parameters=[
filter_base_param,
crop_box_filter_node_param,
{
"input_frame": LaunchConfiguration("tf_output_frame"),
"output_frame": LaunchConfiguration("tf_output_frame"),
"min_x": -200.0,
"max_x": 1000.0,
"min_y": -50.0,
"max_y": 50.0,
"min_z": -2.0,
"max_z": 3.0,
"negative": False,
}
},

Check warning on line 140 in sensing/autoware_pointcloud_preprocessor/launch/preprocessor.launch.py

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

launch_setup increases from 111 to 126 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
],
)

Expand Down Expand Up @@ -146,6 +166,9 @@

def generate_launch_description():
launch_arguments = []
autoware_pointcloud_preprocessor_share_dir = get_package_share_directory(
"autoware_pointcloud_preprocessor"
)

def add_launch_arg(name: str, default_value=None, description=None):
# a default_value of None is equivalent to not passing that kwarg at all
Expand All @@ -161,6 +184,52 @@
)
add_launch_arg("output_points_raw", "/points_raw/cropbox/filtered")
add_launch_arg("tf_output_frame", "base_link")
add_launch_arg(
"concatenate_and_time_sync_node_param_path",
os.path.join(
autoware_pointcloud_preprocessor_share_dir,
"config",
"concatenate_and_time_sync_node.param.yaml",
),
description="path to parameter file of concatenate and time sync node",
)
add_launch_arg(
"concatenate_pointclouds_node_param_path",
os.path.join(
autoware_pointcloud_preprocessor_share_dir,
"config",
"concatenate_pointclouds.param.yaml",
),
description="path to parameter file of concatenate pointclouds node",
)
add_launch_arg(
"time_synchronizer_node_param_path",
os.path.join(
autoware_pointcloud_preprocessor_share_dir,
"config",
"time_synchronizer_node.param.yaml",
),
description="path to parameter file of time synchronizer node",
)
add_launch_arg(
"filter_base_param_path",
os.path.join(
autoware_pointcloud_preprocessor_share_dir,
"config",
"filter.param.yaml",
),
description="path to parameter file of filter base",
)
add_launch_arg(
"crop_box_filter_node_param_path",
os.path.join(
autoware_pointcloud_preprocessor_share_dir,
"config",
"crop_box_filter.param.yaml",
),
description="path to parameter file of crop box filter node",
)

add_launch_arg(
"separate_concatenate_node_and_time_sync_node",
"true",
Expand Down
Loading