Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions image-filtering/include/image_filters/image_filtering_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,12 @@ class ImageFilteringNode : public rclcpp::Node {
*/
void check_and_subscribe_to_image_topic();

/**
* @brief Declare the ros2 parameters used by the node.
*
*/
void declare_parameters();

/**
* @brief Set the filter parameters for the FilterParams struct.
*
Expand Down
28 changes: 15 additions & 13 deletions image-filtering/src/image_filtering_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,21 @@ using std::placeholders::_1;

ImageFilteringNode::ImageFilteringNode(const rclcpp::NodeOptions& options)
: Node("image_filtering_node", options) {
declare_parameters();
check_and_subscribe_to_image_topic();
set_filter_params();
initialize_parameter_handler();

rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
auto qos_sensor_data = rclcpp::QoS(
rclcpp::QoSInitialization(qos_profile.history, 1), qos_profile);

std::string pub_topic = this->get_parameter("pub_topic").as_string();
image_pub_ = this->create_publisher<sensor_msgs::msg::Image>(
pub_topic, qos_sensor_data);
}

void ImageFilteringNode::declare_parameters() {
this->declare_parameter<std::string>("sub_topic");
this->declare_parameter<std::string>("pub_topic");
this->declare_parameter<std::string>("output_encoding");
Expand All @@ -27,19 +42,6 @@ ImageFilteringNode::ImageFilteringNode(const rclcpp::NodeOptions& options)
this->declare_parameter<double>("filter_params.otsu.gsc_weight_b");
this->declare_parameter<int>("filter_params.otsu.erosion_size");
this->declare_parameter<int>("filter_params.otsu.dilation_size");

rmw_qos_profile_t qos_profile = rmw_qos_profile_sensor_data;
auto qos_sensor_data = rclcpp::QoS(
rclcpp::QoSInitialization(qos_profile.history, 1), qos_profile);

check_and_subscribe_to_image_topic();
set_filter_params();

initialize_parameter_handler();

std::string pub_topic = this->get_parameter("pub_topic").as_string();
image_pub_ = this->create_publisher<sensor_msgs::msg::Image>(
pub_topic, qos_sensor_data);
}

void ImageFilteringNode::set_filter_params() {
Expand Down