Skip to content

Commit

Permalink
Add feedback
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde committed Jul 12, 2024
1 parent c4f867c commit 3bb201e
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
4 changes: 2 additions & 2 deletions stereo_image_proc/src/stereo_image_proc/disparity_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -327,11 +327,11 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options)
sub_l_image_.subscribe(
this, left_topic, hints.getTransport(), sensor_data_qos, sub_opts);
sub_l_info_.subscribe(this, left_info_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts);
sensor_data_qos.get_rmw_qos_profile(), sub_opts);
sub_r_image_.subscribe(
this, right_topic, hints.getTransport(), sensor_data_qos, sub_opts);
sub_r_info_.subscribe(this, right_info_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts);
sensor_data_qos.get_rmw_qos_profile(), sub_opts);
}
};

Expand Down
6 changes: 3 additions & 3 deletions stereo_image_proc/src/stereo_image_proc/point_cloud_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -192,11 +192,11 @@ PointCloudNode::PointCloudNode(const rclcpp::NodeOptions & options)
sub_l_image_.subscribe(
this, left_topic, hints.getTransport(), sensor_data_qos, sub_opts);
sub_l_info_.subscribe(this, left_info_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts);
sensor_data_qos.get_rmw_qos_profile(), sub_opts);
sub_r_info_.subscribe(this, right_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts);
sensor_data_qos.get_rmw_qos_profile(), sub_opts);
sub_disparity_.subscribe(this, disparity_topic,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts);
sensor_data_qos.get_rmw_qos_profile(), sub_opts);
}
};
pub_points2_ = create_publisher<sensor_msgs::msg::PointCloud2>("points2", 1, pub_opts);
Expand Down

0 comments on commit 3bb201e

Please sign in to comment.