From 66100ce1ddaa98ac7da31a9a6cc445744fbfaf15 Mon Sep 17 00:00:00 2001 From: pradyum Date: Mon, 11 Nov 2024 03:54:26 +0530 Subject: [PATCH] corrected lints Signed-off-by: pradyum --- include/dual_laser_merger/dual_laser_merger.hpp | 4 +++- src/dual_laser_merger.cpp | 9 ++++++--- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/include/dual_laser_merger/dual_laser_merger.hpp b/include/dual_laser_merger/dual_laser_merger.hpp index 7b87d9b..f513aaa 100644 --- a/include/dual_laser_merger/dual_laser_merger.hpp +++ b/include/dual_laser_merger/dual_laser_merger.hpp @@ -72,7 +72,9 @@ class MergerNode : public rclcpp::Node int input_queue_size_param; std::string target_frame_param; double tolerance_param, min_height_param, max_height_param, angle_min_param, angle_max_param, - angle_increment_param, scan_time_param, range_min_param, range_max_param, inf_epsilon_param, laser_1_x_offset, laser_1_y_offset, laser_1_yaw_offset, laser_2_x_offset, laser_2_y_offset, laser_2_yaw_offset; + angle_increment_param, scan_time_param, range_min_param, range_max_param, inf_epsilon_param, + laser_1_x_offset, laser_1_y_offset, laser_1_yaw_offset, laser_2_x_offset, laser_2_y_offset, + laser_2_yaw_offset; bool use_inf_param, enable_calibration_param; uint32_t ranges_size; double range, angle; diff --git a/src/dual_laser_merger.cpp b/src/dual_laser_merger.cpp index 7e0a070..485ac00 100644 --- a/src/dual_laser_merger.cpp +++ b/src/dual_laser_merger.cpp @@ -30,9 +30,12 @@ MergerNode::MergerNode(const rclcpp::NodeOptions & options) } merged_pub = - this->create_publisher(this->get_parameter("merged_topic").as_string(), rclcpp::SensorDataQoS()); - laser_1_sub.subscribe(this, this->get_parameter("laser_1_topic").as_string(), rclcpp::SensorDataQoS()); - laser_2_sub.subscribe(this, this->get_parameter("laser_2_topic").as_string(), rclcpp::SensorDataQoS()); + this->create_publisher(this->get_parameter( + "merged_topic").as_string(), rclcpp::SensorDataQoS()); + laser_1_sub.subscribe(this, this->get_parameter("laser_1_topic").as_string(), + rclcpp::SensorDataQoS()); + laser_2_sub.subscribe(this, this->get_parameter("laser_2_topic").as_string(), + rclcpp::SensorDataQoS()); tf2_buffer = std::make_shared(this->get_clock()); tf2_listener = std::make_shared(*tf2_buffer, this);