Skip to content

Commit

Permalink
add test for compressed image display
Browse files Browse the repository at this point in the history
  • Loading branch information
mjforan committed Nov 20, 2024
1 parent 4f5f147 commit 48133ae
Show file tree
Hide file tree
Showing 4 changed files with 108 additions and 1 deletion.
4 changes: 4 additions & 0 deletions rviz_default_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -883,13 +883,17 @@ if(BUILD_TESTING)
${SKIP_VISUAL_TESTS}
TIMEOUT 180)
if(TARGET image_display_visual_test)
find_package(OpenCV REQUIRED)
find_package(image_transport_plugins REQUIRED)
include_directories(${OpenCV_INCLUDE_DIRS})
target_include_directories(image_display_visual_test PRIVATE test)
target_link_libraries(image_display_visual_test
Qt5::Test
rviz_visual_testing_framework::rviz_visual_testing_framework
rclcpp::rclcpp
${sensor_msgs_TARGETS}
${std_msgs_TARGETS}
${OpenCV_LIBRARIES}
)
endif()

Expand Down
2 changes: 2 additions & 0 deletions rviz_default_plugins/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,8 @@
<test_depend>ament_lint_auto</test_depend>
<test_depend>rviz_rendering_tests</test_depend>
<test_depend>rviz_visual_testing_framework</test_depend>
<test_depend>image_transport_plugins</test_depend>
<test_depend>vision_opencv</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,11 @@

#include "../../page_objects/image_display_page_object.hpp"
#include "../../publishers/image_publisher.hpp"
#include "../../publishers/compressed_image_publisher.hpp"


TEST_F(VisualTestFixture, test_image_display_with_published_image) {
auto path_publisher = std::make_unique<VisualTestPublisher>(
auto image_publisher = std::make_unique<VisualTestPublisher>(
std::make_shared<nodes::ImagePublisher>(), "image_frame");

setCamPose(Ogre::Vector3(0, 0, 16));
Expand All @@ -51,3 +53,18 @@ TEST_F(VisualTestFixture, test_image_display_with_published_image) {

assertScreenShotsIdentity();
}

TEST_F(VisualTestFixture, test_compressed_image_display_with_published_image) {
auto compressed_image_publisher = std::make_unique<VisualTestPublisher>(
std::make_shared<nodes::CompressedImagePublisher>(), "image_frame");

setCamPose(Ogre::Vector3(0, 0, 16));
setCamLookAt(Ogre::Vector3(0, 0, 0));

auto image_display = addDisplay<ImageDisplayPageObject>();
image_display->setTopic("/image");

captureRenderWindow(image_display);

assertScreenShotsIdentity();
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
// Copyright (c) 2018, Bosch Software Innovations GmbH.
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the copyright holder nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.


#ifndef RVIZ_DEFAULT_PLUGINS__PUBLISHERS__COMPRESSED_IMAGE_PUBLISHER_HPP_
#define RVIZ_DEFAULT_PLUGINS__PUBLISHERS__COMPRESSED_IMAGE_PUBLISHER_HPP_

#include <cmath>
#include <iostream>
#include <string>
#include <vector>

#include <opencv2/opencv.hpp>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/clock.hpp"
#include "sensor_msgs/msg/compressed_image.hpp"
#include "std_msgs/msg/header.hpp"

using namespace std::chrono_literals; // NOLINT

namespace nodes
{

class CompressedImagePublisher : public rclcpp::Node
{
public:
explicit CompressedImagePublisher(const std::string & topic_name = "image")
: Node("compressed_image_publisher")
{
publisher = this->create_publisher<sensor_msgs::msg::CompressedImage>(topic_name, 10);
timer = this->create_wall_timer(100ms,
std::bind(&CompressedImagePublisher::timer_callback, this));
}

private:
void timer_callback()
{
auto message = sensor_msgs::msg::CompressedImage();
message.header = std_msgs::msg::Header();
message.header.frame_id = "image_frame";
message.header.stamp = rclcpp::Clock().now();

cv::Mat image(200, 300, CV_8UC3, cv::Scalar(0, 255, 0));
std::vector<uchar> compressed_image;
cv::imencode(".jpg", image, compressed_image);

message.data.assign(compressed_image.begin(), compressed_image.end());
message.format = "jpeg";
publisher->publish(message);
}

rclcpp::TimerBase::SharedPtr timer;
rclcpp::Publisher<sensor_msgs::msg::CompressedImage>::SharedPtr publisher;
};

} // namespace nodes

#endif // RVIZ_DEFAULT_PLUGINS__PUBLISHERS__COMPRESSED_IMAGE_PUBLISHER_HPP_

0 comments on commit 48133ae

Please sign in to comment.