Skip to content

Commit

Permalink
corrected lints
Browse files Browse the repository at this point in the history
Signed-off-by: pradyum <[email protected]>
  • Loading branch information
pradyum committed Nov 10, 2024
1 parent 29cc3e6 commit 66100ce
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 4 deletions.
4 changes: 3 additions & 1 deletion include/dual_laser_merger/dual_laser_merger.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
9 changes: 6 additions & 3 deletions src/dual_laser_merger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,12 @@ MergerNode::MergerNode(const rclcpp::NodeOptions & options)
}

merged_pub =
this->create_publisher<sensor_msgs::msg::LaserScan>(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<sensor_msgs::msg::LaserScan>(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<tf2_ros::Buffer>(this->get_clock());
tf2_listener = std::make_shared<tf2_ros::TransformListener>(*tf2_buffer, this);
Expand Down

0 comments on commit 66100ce

Please sign in to comment.