Skip to content

Commit 40711b7

Browse files
committed
add test for compressed image display
1 parent 0bc298d commit 40711b7

File tree

4 files changed

+108
-1
lines changed

4 files changed

+108
-1
lines changed

rviz_default_plugins/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -883,13 +883,17 @@ if(BUILD_TESTING)
883883
${SKIP_VISUAL_TESTS}
884884
TIMEOUT 180)
885885
if(TARGET image_display_visual_test)
886+
find_package(OpenCV REQUIRED)
887+
find_package(image_transport_plugins REQUIRED)
888+
include_directories(${OpenCV_INCLUDE_DIRS})
886889
target_include_directories(image_display_visual_test PRIVATE test)
887890
target_link_libraries(image_display_visual_test
888891
Qt5::Test
889892
rviz_visual_testing_framework::rviz_visual_testing_framework
890893
rclcpp::rclcpp
891894
${sensor_msgs_TARGETS}
892895
${std_msgs_TARGETS}
896+
${OpenCV_LIBRARIES}
893897
)
894898
endif()
895899

rviz_default_plugins/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,8 @@
6464
<test_depend>ament_lint_auto</test_depend>
6565
<test_depend>rviz_rendering_tests</test_depend>
6666
<test_depend>rviz_visual_testing_framework</test_depend>
67+
<test_depend>image_transport_plugins</test_depend>
68+
<test_depend>vision_opencv</test_depend>
6769

6870
<export>
6971
<build_type>ament_cmake</build_type>

rviz_default_plugins/test/rviz_default_plugins/displays/image/image_display_visual_test.cpp

Lines changed: 18 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -36,9 +36,11 @@
3636

3737
#include "../../page_objects/image_display_page_object.hpp"
3838
#include "../../publishers/image_publisher.hpp"
39+
#include "../../publishers/compressed_image_publisher.hpp"
40+
3941

4042
TEST_F(VisualTestFixture, test_image_display_with_published_image) {
41-
auto path_publisher = std::make_unique<VisualTestPublisher>(
43+
auto image_publisher = std::make_unique<VisualTestPublisher>(
4244
std::make_shared<nodes::ImagePublisher>(), "image_frame");
4345

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

5254
assertScreenShotsIdentity();
5355
}
56+
57+
TEST_F(VisualTestFixture, test_compressed_image_display_with_published_image) {
58+
auto compressed_image_publisher = std::make_unique<VisualTestPublisher>(
59+
std::make_shared<nodes::CompressedImagePublisher>(), "image_frame");
60+
61+
setCamPose(Ogre::Vector3(0, 0, 16));
62+
setCamLookAt(Ogre::Vector3(0, 0, 0));
63+
64+
auto image_display = addDisplay<ImageDisplayPageObject>();
65+
image_display->setTopic("/image");
66+
67+
captureRenderWindow(image_display);
68+
69+
assertScreenShotsIdentity();
70+
}
Lines changed: 84 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,84 @@
1+
// Copyright (c) 2018, Bosch Software Innovations GmbH.
2+
// All rights reserved.
3+
//
4+
// Redistribution and use in source and binary forms, with or without
5+
// modification, are permitted provided that the following conditions are met:
6+
//
7+
// * Redistributions of source code must retain the above copyright
8+
// notice, this list of conditions and the following disclaimer.
9+
//
10+
// * Redistributions in binary form must reproduce the above copyright
11+
// notice, this list of conditions and the following disclaimer in the
12+
// documentation and/or other materials provided with the distribution.
13+
//
14+
// * Neither the name of the copyright holder nor the names of its
15+
// contributors may be used to endorse or promote products derived from
16+
// this software without specific prior written permission.
17+
//
18+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
22+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28+
// POSSIBILITY OF SUCH DAMAGE.
29+
30+
31+
#ifndef RVIZ_DEFAULT_PLUGINS__PUBLISHERS__COMPRESSED_IMAGE_PUBLISHER_HPP_
32+
#define RVIZ_DEFAULT_PLUGINS__PUBLISHERS__COMPRESSED_IMAGE_PUBLISHER_HPP_
33+
34+
#include <cmath>
35+
#include <iostream>
36+
#include <string>
37+
#include <vector>
38+
39+
#include <opencv2/opencv.hpp>
40+
#include "rclcpp/rclcpp.hpp"
41+
#include "rclcpp/clock.hpp"
42+
#include "sensor_msgs/msg/compressed_image.hpp"
43+
#include "std_msgs/msg/header.hpp"
44+
45+
using namespace std::chrono_literals; // NOLINT
46+
47+
namespace nodes
48+
{
49+
50+
class CompressedImagePublisher : public rclcpp::Node
51+
{
52+
public:
53+
explicit CompressedImagePublisher(const std::string & topic_name = "image")
54+
: Node("compressed_image_publisher")
55+
{
56+
publisher = this->create_publisher<sensor_msgs::msg::CompressedImage>(topic_name, 10);
57+
timer = this->create_wall_timer(100ms,
58+
std::bind(&CompressedImagePublisher::timer_callback, this));
59+
}
60+
61+
private:
62+
void timer_callback()
63+
{
64+
auto message = sensor_msgs::msg::CompressedImage();
65+
message.header = std_msgs::msg::Header();
66+
message.header.frame_id = "image_frame";
67+
message.header.stamp = rclcpp::Clock().now();
68+
69+
cv::Mat image(200, 300, CV_8UC3, cv::Scalar(0, 255, 0));
70+
std::vector<uchar> compressed_image;
71+
cv::imencode(".jpg", image, compressed_image);
72+
73+
message.data.assign(compressed_image.begin(), compressed_image.end());
74+
message.format = "jpeg";
75+
publisher->publish(message);
76+
}
77+
78+
rclcpp::TimerBase::SharedPtr timer;
79+
rclcpp::Publisher<sensor_msgs::msg::CompressedImage>::SharedPtr publisher;
80+
};
81+
82+
} // namespace nodes
83+
84+
#endif // RVIZ_DEFAULT_PLUGINS__PUBLISHERS__COMPRESSED_IMAGE_PUBLISHER_HPP_

0 commit comments

Comments
 (0)