Skip to content

Commit

Permalink
Fixed #1201
Browse files Browse the repository at this point in the history
  • Loading branch information
matlabbe committed Aug 24, 2024
1 parent 3aacddb commit 10ddeee
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion rtabmap_util/src/nodelets/disparity_to_depth.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ DisparityToDepth::DisparityToDepth(const rclcpp::NodeOptions & options) :
int qos = 0;
qos = this->declare_parameter("qos", qos);

auto node = rclcpp::Node::make_shared(this->get_name());
auto node = std::shared_ptr<DisparityToDepth>(this, [](auto *) {});
image_transport::ImageTransport it(node);
pub32f_ = image_transport::create_publisher(node.get(), "depth", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)qos).get_rmw_qos_profile());
pub16u_ = image_transport::create_publisher(node.get(), "depth_raw", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)qos).get_rmw_qos_profile());
Expand Down
2 changes: 1 addition & 1 deletion rtabmap_util/src/nodelets/pointcloud_to_depthimage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ PointCloudToDepthImage::PointCloudToDepthImage(const rclcpp::NodeOptions & optio
RCLCPP_INFO(this->get_logger(), " decimation=%d", decimation_);
RCLCPP_INFO(this->get_logger(), " upscale=%s (upscale_depth_error_ratio=%f)", upscale_?"true":"false", upscaleDepthErrorRatio_);

auto node = rclcpp::Node::make_shared(this->get_name());
auto node = std::shared_ptr<PointCloudToDepthImage>(this, [](auto *) {});
image_transport::ImageTransport it(node);
depthImage16Pub_ = image_transport::create_camera_publisher(node.get(), "image_raw", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)qos).get_rmw_qos_profile()); // 16 bits unsigned in mm
depthImage32Pub_ = image_transport::create_camera_publisher(node.get(), "image", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)qos).get_rmw_qos_profile());// 32 bits float in meters
Expand Down
2 changes: 1 addition & 1 deletion rtabmap_util/src/nodelets/rgbd_split.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ RGBDSplit::RGBDSplit(const rclcpp::NodeOptions & options) :

rgbdImageSub_ = create_subscription<rtabmap_msgs::msg::RGBDImage>("rgbd_image", rclcpp::QoS(5).reliability((rmw_qos_reliability_policy_t)qos), std::bind(&RGBDSplit::callback, this, std::placeholders::_1));

auto node = rclcpp::Node::make_shared(this->get_name());
auto node = std::shared_ptr<RGBDSplit>(this, [](auto *) {});
image_transport::ImageTransport it(node);
rgbPub_ = image_transport::create_camera_publisher(node.get(), std::string(rgbdImageSub_->get_topic_name()) + "/rgb", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)qos).get_rmw_qos_profile());
depthPub_ = image_transport::create_camera_publisher(node.get(), std::string(rgbdImageSub_->get_topic_name()) + "/depth", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)qos).get_rmw_qos_profile());
Expand Down

0 comments on commit 10ddeee

Please sign in to comment.