diff --git a/aip_xx1_gen2_launch/CMakeLists.txt b/aip_xx1_gen2_launch/CMakeLists.txt index 54e2d2b0..779ac533 100644 --- a/aip_xx1_gen2_launch/CMakeLists.txt +++ b/aip_xx1_gen2_launch/CMakeLists.txt @@ -18,4 +18,4 @@ ament_auto_package(INSTALL_TO_SHARE install(PROGRAMS scripts/septentrio_heading_converter.py DESTINATION lib/${PROJECT_NAME} -) \ No newline at end of file +) diff --git a/aip_xx1_gen2_launch/launch/lidar.launch.py b/aip_xx1_gen2_launch/launch/lidar.launch.py index 24ffcbe3..a2a6d6e1 100644 --- a/aip_xx1_gen2_launch/launch/lidar.launch.py +++ b/aip_xx1_gen2_launch/launch/lidar.launch.py @@ -105,9 +105,7 @@ def load_yaml(yaml_file_path): base_parameters["enable_blockage_diag"] = LaunchConfiguration("enable_blockage_diag").perform( context ) - base_parameters["return_mode"] = LaunchConfiguration("return_mode").perform( - context - ) + base_parameters["return_mode"] = LaunchConfiguration("return_mode").perform(context) sub_launch_actions = [] for launch in config["launches"]: diff --git a/aip_xx1_gen2_launch/scripts/septentrio_heading_converter.py b/aip_xx1_gen2_launch/scripts/septentrio_heading_converter.py index 205e2316..641049ab 100755 --- a/aip_xx1_gen2_launch/scripts/septentrio_heading_converter.py +++ b/aip_xx1_gen2_launch/scripts/septentrio_heading_converter.py @@ -13,16 +13,15 @@ # See the License for the specific language governing permissions and # limitations under the License. -import rclpy -from rclpy.node import Node -from septentrio_gnss_driver.msg import AttEuler from autoware_sensing_msgs.msg import GnssInsOrientationStamped from geometry_msgs.msg import Quaternion import numpy as np +import rclpy +from rclpy.node import Node +from septentrio_gnss_driver.msg import AttEuler class OrientationConverter(Node): - def __init__(self): super().__init__("septentrio_orientation_converter") self.publisher = self.create_publisher(