From a2b9c009ee3b04d911e98c1313446d18ec5e9d12 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 20 Dec 2024 04:10:30 +0000 Subject: [PATCH] ci(pre-commit): autofix --- .../launch/nebula_node_container.launch.py | 52 +++++-------------- 1 file changed, 13 insertions(+), 39 deletions(-) diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py index 644cf71a..deb9626c 100644 --- a/common_sensor_launch/launch/nebula_node_container.launch.py +++ b/common_sensor_launch/launch/nebula_node_container.launch.py @@ -85,23 +85,17 @@ def create_parameter_dict(*args): ) assert os.path.exists( sensor_calib_fp - ), "Sensor calib file under calibration/ was not found: {}".format( - sensor_calib_fp - ) + ), "Sensor calib file under calibration/ was not found: {}".format(sensor_calib_fp) else: # Robosense sensor_calib_fp = "" # Pointcloud preprocessor parameters distortion_corrector_node_param = ParameterFile( - param_file=LaunchConfiguration("distortion_correction_node_param_path").perform( - context - ), + param_file=LaunchConfiguration("distortion_correction_node_param_path").perform(context), allow_substs=True, ) ring_outlier_filter_node_param = ParameterFile( - param_file=LaunchConfiguration("ring_outlier_filter_node_param_path").perform( - context - ), + param_file=LaunchConfiguration("ring_outlier_filter_node_param_path").perform(context), allow_substs=True, ) @@ -151,9 +145,7 @@ def create_parameter_dict(*args): # ("robosense_points", "pointcloud_raw_ex"), #for robosense # ("pandar_points", "pointcloud_raw_ex"), # for hesai ], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) ) @@ -178,9 +170,7 @@ def create_parameter_dict(*args): ("output", "self_cropped/pointcloud_ex"), ], parameters=[cropbox_parameters], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) ) @@ -202,9 +192,7 @@ def create_parameter_dict(*args): ("output", "mirror_cropped/pointcloud_ex"), ], parameters=[cropbox_parameters], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) ) @@ -223,9 +211,7 @@ def create_parameter_dict(*args): ("~/output/pointcloud", "rectified/pointcloud_ex"), ], parameters=[distortion_corrector_node_param], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) ) @@ -233,9 +219,7 @@ def create_parameter_dict(*args): if LaunchConfiguration("output_as_sensor_frame").perform(context).lower() == "true": ring_outlier_output_frame = {"output_frame": LaunchConfiguration("frame_id")} else: - ring_outlier_output_frame = { - "output_frame": "" - } # keep the output frame as the input frame + ring_outlier_output_frame = {"output_frame": ""} # keep the output frame as the input frame nodes.append( ComposableNode( package="autoware_pointcloud_preprocessor", @@ -246,9 +230,7 @@ def create_parameter_dict(*args): ("output", "pointcloud_before_sync"), ], parameters=[ring_outlier_filter_node_param, ring_outlier_output_frame], - extra_arguments=[ - {"use_intra_process_comms": LaunchConfiguration("use_intra_process")} - ], + extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) ) @@ -271,9 +253,7 @@ def generate_launch_description(): 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 launch_arguments.append( - DeclareLaunchArgument( - name, default_value=default_value, description=description - ) + DeclareLaunchArgument(name, default_value=default_value, description=description) ) common_sensor_share_dir = get_package_share_directory("common_sensor_launch") @@ -294,20 +274,14 @@ def add_launch_arg(name: str, default_value=None, description=None): add_launch_arg("gnss_port", "2380", "device gnss port number") add_launch_arg("packet_mtu_size", "1500", "packet mtu size") add_launch_arg("rotation_speed", "600", "rotational frequency") - add_launch_arg( - "dual_return_distance_threshold", "0.1", "dual return distance threshold" - ) + add_launch_arg("dual_return_distance_threshold", "0.1", "dual return distance threshold") add_launch_arg("frame_id", "lidar", "frame id") add_launch_arg("input_frame", LaunchConfiguration("base_frame"), "use for cropbox") add_launch_arg("output_frame", LaunchConfiguration("base_frame"), "use for cropbox") add_launch_arg("use_multithread", "False", "use multithread") - add_launch_arg( - "use_intra_process", "False", "use ROS 2 component container communication" - ) + add_launch_arg("use_intra_process", "False", "use ROS 2 component container communication") add_launch_arg("lidar_container_name", "nebula_node_container") - add_launch_arg( - "output_as_sensor_frame", "True", "output final pointcloud in sensor frame" - ) + add_launch_arg("output_as_sensor_frame", "True", "output final pointcloud in sensor frame") add_launch_arg( "vehicle_mirror_param_file", description="path to the file of vehicle mirror position yaml",