You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
When zoom1 is enabled, the shown image has the exact same shape as the received image, no scaling whatsoever, just a 1-to-1 mapping. Example (produced with a patched version of rqt_image_view):
Observed behavior
After enabling zoom1, the received image is scaled to be 1 px larger on both width and height. This introduces aliasing, example:
To reproduce
Start from a ROS 2 Jazzy environment
publish a test image, script:
#! /usr/bin/env python3importcv_bridgeimportnumpyasnpimportrclpy.nodefromsensor_msgs.msgimportImagedefcreate_test_image():
# all blackimg=np.zeros((320, 640), dtype=np.uint8)
# vertical white lines on the left halfimg[:,:img.shape[1]//2:2] =255# horizontal white lines on the right halfimg[::2, img.shape[1]//2:] =255returnimgclassImagePublisher(rclpy.node.Node):
def__init__(self):
super().__init__('image_publisher')
self.publisher_=self.create_publisher(Image, 'test_image', 10)
self.timer_=self.create_timer(0.5, self.publish_image)
self.image_msg_=cv_bridge.CvBridge().cv2_to_imgmsg(
create_test_image(), 'mono8')
defpublish_image(self):
self.publisher_.publish(self.image_msg_)
if__name__=='__main__':
rclpy.init()
image_publisher=ImagePublisher()
rclpy.spin(image_publisher)
image_publisher.destroy_node()
rclpy.shutdown()
Launch RQt (ros2 run rqt_image_view rqt_image_view test_image) and in image view click the zoom1 button.
Version
Recent ROS 2 Jazzy Ubuntu Noble install, though this behavior also arises in ROS 1 Noetic and probably older as well.
Presumed cause
Enabling zoom1 results in the line ui_.image_frame->setInnerFrameFixedSize(ui_.image_frame->getImage().size()); being called, which in turn calls setInnerFrameMinimumSize and setInnerFrameMaximumSize. They set the frame size to a larger size than the actual image:
with the linewidth being set in image_view.ui to 1 px. When subsequently displaying the image with painter.drawImage, Qt notices that the resolutions are different and scales it, resulting in image artifacts.
I'd appreciate if someone could explain briefly (or point to an explanation) of why a (nonzero) border is used, as I don't immediately see any visual effect of it apart from the image aliasing artifacts.
Solution proposals
I currently see three approaches to resolve this:
Set lineWidth in image_view.ui to zero and, as it's zero anyway, remove the border accounting, simplifying the code. From my initial test, this works perfectly, though perhaps this breaks something else?
When setting the frame resolution when zoom1 is enabled, compensate for the border that will be taken into account, or set it directly without taking the border into account.
When drawing the image, account for the border, resulting in the border being visible when zoom1 is enabled. Though I haven't yet seen a border when zoom1 isn't enabled.
Thanks for going through this; I'd be glad to work out any of these proposals and make a PR.
The text was updated successfully, but these errors were encountered:
Expected behavior
When
zoom1
is enabled, the shown image has the exact same shape as the received image, no scaling whatsoever, just a 1-to-1 mapping. Example (produced with a patched version ofrqt_image_view
):Observed behavior
After enabling
zoom1
, the received image is scaled to be 1 px larger on both width and height. This introduces aliasing, example:To reproduce
ros2 run rqt_image_view rqt_image_view test_image
) and in image view click thezoom1
button.Version
Recent ROS 2 Jazzy Ubuntu Noble install, though this behavior also arises in ROS 1 Noetic and probably older as well.
Presumed cause
Enabling
zoom1
results in the lineui_.image_frame->setInnerFrameFixedSize(ui_.image_frame->getImage().size());
being called, which in turn callssetInnerFrameMinimumSize
andsetInnerFrameMaximumSize
. They set the frame size to a larger size than the actual image:with the linewidth being set in
image_view.ui
to 1 px. When subsequently displaying the image withpainter.drawImage
, Qt notices that the resolutions are different and scales it, resulting in image artifacts.I'd appreciate if someone could explain briefly (or point to an explanation) of why a (nonzero) border is used, as I don't immediately see any visual effect of it apart from the image aliasing artifacts.
Solution proposals
I currently see three approaches to resolve this:
lineWidth
inimage_view.ui
to zero and, as it's zero anyway, remove the border accounting, simplifying the code. From my initial test, this works perfectly, though perhaps this breaks something else?zoom1
is enabled, compensate for the border that will be taken into account, or set it directly without taking the border into account.zoom1
is enabled. Though I haven't yet seen a border whenzoom1
isn't enabled.Thanks for going through this; I'd be glad to work out any of these proposals and make a PR.
The text was updated successfully, but these errors were encountered: