From 9ebdf0f6befe7bbf1a14354520fd6f7f2aa35d8f Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Fri, 5 Aug 2022 14:31:22 +0200 Subject: [PATCH 1/2] Improve send_images: Use uniform border color --- src/test/send_images.cpp | 25 ++++++++++++++++++------- 1 file changed, 18 insertions(+), 7 deletions(-) diff --git a/src/test/send_images.cpp b/src/test/send_images.cpp index 3d15c727d6..c8a5091ae2 100644 --- a/src/test/send_images.cpp +++ b/src/test/send_images.cpp @@ -57,8 +57,8 @@ int main(int argc, char** argv) if (image_format == "rgb8") { sensor_msgs::Image msg; - int width = 100; - int height = 1000; + int width = 300; + int height = 200; msg.data.resize(width * height * 3); msg.header.frame_id = "camera_frame"; msg.height = height; @@ -74,14 +74,25 @@ int main(int argc, char** argv) { for (int y = 0; y < height; y++) { + uint8_t r = 0, g = 0, b = 0; + if (x < 5) + r = 255; + if (y < 5) + r = g = 255; + if (x >= 5 && x < width - 5 && y >= 5 && y < height - 5) + { + std::uniform_int_distribution uniform(0, RAND_MAX); + auto rand = uniform(random_generator); + r = rand & 0xff; + g = (rand >> 8) & 0xff; + b = (rand >> 16) & 0xff; + } int index = (x + y * width) * 3; - std::uniform_int_distribution uniform(0, RAND_MAX); - auto rand = uniform(random_generator); - msg.data[index] = rand & 0xff; + msg.data[index] = r; index++; - msg.data[index] = (rand >> 8) & 0xff; + msg.data[index] = g; index++; - msg.data[index] = (rand >> 16) & 0xff; + msg.data[index] = b; } } msg.header.seq = count; From d10e37172b7ca418f5bd449e6e033eb5d4303dce Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Fri, 5 Aug 2022 14:42:10 +0200 Subject: [PATCH 2/2] Avoid wrapping of texture in image displays --- src/image_view/image_view.cpp | 1 + src/rviz/default_plugin/camera_display.cpp | 1 + src/rviz/default_plugin/image_display.cpp | 1 + 3 files changed, 3 insertions(+) diff --git a/src/image_view/image_view.cpp b/src/image_view/image_view.cpp index 575f56f9d3..42deb21b16 100644 --- a/src/image_view/image_view.cpp +++ b/src/image_view/image_view.cpp @@ -108,6 +108,7 @@ void ImageView::showEvent(QShowEvent* event) Ogre::TextureUnitState* tu = material->getTechnique(0)->getPass(0)->createTextureUnitState(); tu->setTextureName(texture_->getTexture()->getName()); tu->setTextureFiltering(Ogre::TFO_NONE); + tu->setTextureAddressingMode(Ogre::TextureUnitState::TAM_CLAMP); Ogre::Rectangle2D* rect = new Ogre::Rectangle2D(true); rect->setCorners(-1.0f, 1.0f, 1.0f, -1.0f); diff --git a/src/rviz/default_plugin/camera_display.cpp b/src/rviz/default_plugin/camera_display.cpp index 2dce1c1089..d090b25c6f 100644 --- a/src/rviz/default_plugin/camera_display.cpp +++ b/src/rviz/default_plugin/camera_display.cpp @@ -150,6 +150,7 @@ void CameraDisplay::onInitialize() Ogre::TextureUnitState* tu = bg_material_->getTechnique(0)->getPass(0)->createTextureUnitState(); tu->setTextureName(texture_.getTexture()->getName()); tu->setTextureFiltering(Ogre::TFO_NONE); + tu->setTextureAddressingMode(Ogre::TextureUnitState::TAM_CLAMP); tu->setAlphaOperation(Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, 0.0); bg_material_->setCullingMode(Ogre::CULL_NONE); diff --git a/src/rviz/default_plugin/image_display.cpp b/src/rviz/default_plugin/image_display.cpp index 5baa42040e..58ee19ec3f 100644 --- a/src/rviz/default_plugin/image_display.cpp +++ b/src/rviz/default_plugin/image_display.cpp @@ -106,6 +106,7 @@ void ImageDisplay::onInitialize() Ogre::TextureUnitState* tu = material_->getTechnique(0)->getPass(0)->createTextureUnitState(); tu->setTextureName(texture_.getTexture()->getName()); tu->setTextureFiltering(Ogre::TFO_NONE); + tu->setTextureAddressingMode(Ogre::TextureUnitState::TAM_CLAMP); material_->setCullingMode(Ogre::CULL_NONE); Ogre::AxisAlignedBox aabInf;