Skip to content

Commit

Permalink
enable autosize parameter in disparity view (#875)
Browse files Browse the repository at this point in the history
appears to be bug left over from ROS 2 port
  • Loading branch information
mikeferguson authored Jan 19, 2024
1 parent 8afb78d commit 1fbe467
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 4 deletions.
1 change: 1 addition & 0 deletions image_view/include/image_view/disparity_view_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ class DisparityViewNode
static unsigned char colormap[];

std::string window_name_;
bool autosize_;
rclcpp::Subscription<stereo_msgs::msg::DisparityImage>::SharedPtr sub_;
cv::Mat_<cv::Vec3b> disparity_color_;
bool initialized;
Expand Down
6 changes: 2 additions & 4 deletions image_view/src/disparity_view_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,9 +82,7 @@ DisparityViewNode::DisparityViewNode(const rclcpp::NodeOptions & options)

// Default window name is the resolved topic name
window_name_ = this->declare_parameter("window_name", topic);
// bool autosize = this->declare_parameter("autosize", false);

// cv::namedWindow(window_name_, autosize ? cv::WND_PROP_AUTOSIZE : 0);
autosize_ = this->declare_parameter("autosize", false);

sub_ = this->create_subscription<stereo_msgs::msg::DisparityImage>(
topic, rclcpp::QoS(10), std::bind(&DisparityViewNode::imageCb, this, std::placeholders::_1));
Expand Down Expand Up @@ -114,7 +112,7 @@ void DisparityViewNode::imageCb(const stereo_msgs::msg::DisparityImage::SharedPt
}

if (!initialized) {
cv::namedWindow(window_name_, false ? cv::WND_PROP_AUTOSIZE : 0);
cv::namedWindow(window_name_, autosize_ ? cv::WND_PROP_AUTOSIZE : 0);
initialized = true;
}

Expand Down

0 comments on commit 1fbe467

Please sign in to comment.