From 92723b6b846bfb9e219dde1703371c9873e2609c Mon Sep 17 00:00:00 2001 From: Danryanh7 Date: Thu, 4 Apr 2024 23:23:38 +0000 Subject: [PATCH] fixing styling --- .../lidar_object_detection/launch/eve_launch.py | 1 + .../lidar_object_detection_node.py | 13 +++++++------ 2 files changed, 8 insertions(+), 6 deletions(-) diff --git a/src/perception/lidar_object_detection/lidar_object_detection/launch/eve_launch.py b/src/perception/lidar_object_detection/lidar_object_detection/launch/eve_launch.py index af515d44..78f2c2ac 100644 --- a/src/perception/lidar_object_detection/lidar_object_detection/launch/eve_launch.py +++ b/src/perception/lidar_object_detection/lidar_object_detection/launch/eve_launch.py @@ -3,6 +3,7 @@ from ament_index_python.packages import get_package_share_directory import os + def generate_launch_description(): ld = LaunchDescription() config = os.path.join( diff --git a/src/perception/lidar_object_detection/lidar_object_detection/lidar_object_detection/lidar_object_detection_node.py b/src/perception/lidar_object_detection/lidar_object_detection/lidar_object_detection/lidar_object_detection_node.py index 4e77074e..39e8d5a7 100644 --- a/src/perception/lidar_object_detection/lidar_object_detection/lidar_object_detection/lidar_object_detection_node.py +++ b/src/perception/lidar_object_detection/lidar_object_detection/lidar_object_detection/lidar_object_detection_node.py @@ -1,3 +1,9 @@ +# pylint: disable=wrong-import-position +sys.path.append("/home/bolty/OpenPCDet") +from pcdet.utils import common_utils +from pcdet.models import build_network, load_data_to_gpu +from pcdet.datasets import DatasetTemplate +from pcdet.config import cfg, cfg_from_yaml_file import sys import argparse import rclpy @@ -8,12 +14,6 @@ from vision_msgs.msg import ObjectHypothesisWithPose, Detection3D, Detection3DArray from sensor_msgs.msg import PointCloud2, PointField -# pylint: disable=wrong-import-position -sys.path.append("/home/bolty/OpenPCDet") -from pcdet.config import cfg, cfg_from_yaml_file -from pcdet.datasets import DatasetTemplate -from pcdet.models import build_network, load_data_to_gpu -from pcdet.utils import common_utils class LidarObjectDetection(Node): def __init__(self): @@ -204,5 +204,6 @@ def main(args=None): node.destroy_node() rclpy.shutdown() + if __name__ == '__main__': main()