From 8f168606449bbd85bad55b056aecc825294506db Mon Sep 17 00:00:00 2001 From: Michael Ferguson Date: Wed, 17 Jan 2024 16:51:37 -0500 Subject: [PATCH] image_view: fix encoding, help string (#850) * encoding shouldn't be hard coded, pull it from the message * help string needs to be updated to proper parameter format --- image_view/src/image_view_node.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/image_view/src/image_view_node.cpp b/image_view/src/image_view_node.cpp index 3362c3052..2ebc5a599 100644 --- a/image_view/src/image_view_node.cpp +++ b/image_view/src/image_view_node.cpp @@ -122,7 +122,8 @@ ImageViewNode::ImageViewNode(const rclcpp::NodeOptions & options) RCLCPP_WARN( this->get_logger(), "Topic 'image' has not been remapped! " "Typical command-line usage:\n" - "\t$ rosrun image_view image_view image:= [transport]"); + "\t$ ros2 run image_view image_view --ros-args -p image:= " + "[-p image_transport:=]"); } // Default window name is the resolved topic name @@ -210,9 +211,11 @@ void ImageViewNode::imageCb(const sensor_msgs::msg::Image::ConstSharedPtr & msg) } } + std::string encoding = msg->encoding.empty() ? "bgr8" : msg->encoding; + queued_image_.set( cv_bridge::cvtColorForDisplay( - cv_bridge::toCvShare(msg), "bgr8", options)); + cv_bridge::toCvShare(msg), encoding, options)); } catch (cv_bridge::Exception & e) { RCLCPP_ERROR_EXPRESSION( this->get_logger(), (static_cast(this->now().seconds()) % 30 == 0),