Skip to content

Commit

Permalink
fixes
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
  • Loading branch information
ahcorde committed Jul 12, 2024
1 parent 3bb201e commit 15e45f0
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
6 changes: 3 additions & 3 deletions stereo_image_proc/src/stereo_image_proc/disparity_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -315,7 +315,7 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options)
image_transport::getCameraInfoTopic(right_topic), false);

// REP-2003 specifies that subscriber should be SensorDataQoS
const auto sensor_data_qos = rclcpp::SensorDataQoS().get_rmw_qos_profile();
const auto sensor_data_qos = rclcpp::SensorDataQoS();

// Support image transport for compression
image_transport::TransportHints hints(this);
Expand All @@ -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,
sensor_data_qos.get_rmw_qos_profile(), sub_opts);
sensor_data_qos, sub_opts);
sub_r_image_.subscribe(
this, right_topic, hints.getTransport(), sensor_data_qos, sub_opts);
sub_r_info_.subscribe(this, right_info_topic,
sensor_data_qos.get_rmw_qos_profile(), sub_opts);
sensor_data_qos, sub_opts);
}
};

Expand Down
10 changes: 5 additions & 5 deletions stereo_image_proc/src/stereo_image_proc/point_cloud_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ PointCloudNode::PointCloudNode(const rclcpp::NodeOptions & options)
image_transport::getCameraInfoTopic(left_topic), false);

// REP-2003 specifies that subscriber should be SensorDataQoS
const auto sensor_data_qos = rclcpp::SensorDataQoS().get_rmw_qos_profile();
const auto sensor_data_qos = rclcpp::SensorDataQoS();

// Support image transport for compression
image_transport::TransportHints hints(this);
Expand All @@ -190,13 +190,13 @@ PointCloudNode::PointCloudNode(const rclcpp::NodeOptions & options)
sub_opts.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies();

sub_l_image_.subscribe(
this, left_topic, hints.getTransport(), sensor_data_qos, sub_opts);
this, left_topic, hints.getTransport(), sensor_data_qos.get_rmw_qos_profile(), sub_opts);
sub_l_info_.subscribe(this, left_info_topic,
sensor_data_qos.get_rmw_qos_profile(), sub_opts);
sensor_data_qos, sub_opts);
sub_r_info_.subscribe(this, right_topic,
sensor_data_qos.get_rmw_qos_profile(), sub_opts);
sensor_data_qos, sub_opts);
sub_disparity_.subscribe(this, disparity_topic,
sensor_data_qos.get_rmw_qos_profile(), sub_opts);
sensor_data_qos, sub_opts);
}
};
pub_points2_ = create_publisher<sensor_msgs::msg::PointCloud2>("points2", 1, pub_opts);
Expand Down

0 comments on commit 15e45f0

Please sign in to comment.