Skip to content

Commit

Permalink
use image_transport to subscribe to image messages (#523)
Browse files Browse the repository at this point in the history
* use image_transport to subscribe to image messages

use image_transport in camera_display and image_display
use image_transport to get camera_info_topic

* update README after reenabling image transport

* Add image transport dependency to package.xml

Signed-off-by: Audrow <audrow.nash@gmail.com>

* Update headers to fix macOS warnings

Signed-off-by: Audrow Nash <audrow.nash@gmail.com>

Co-authored-by: Martin Idel <martin.idel@googlemail.com>

* Add Macros to fix linking in Windows

Signed-off-by: Audrow Nash <audrow.nash@gmail.com>

Co-authored-by: Martin Idel <martin.idel@googlemail.com>

* Move Windows visibility macros to header files

Signed-off-by: Audrow Nash <audrow.nash@gmail.com>

Co-authored-by: ketatam <mohamed.amine.ketata@tngtech.com>
Co-authored-by: Audrow <audrow.nash@gmail.com>
Co-authored-by: Martin Idel <martin.idel@googlemail.com>
  • Loading branch information
4 people committed May 7, 2021
1 parent c74ca56 commit 731f24d
Show file tree
Hide file tree
Showing 12 changed files with 440 additions and 24 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -4,3 +4,4 @@ bin
build
lib
*.sublime-workspace
**/.idea/**
1 change: 0 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,6 @@ These features have not been ported to `ros2/rviz` yet.
| Effort |

Other features:
- Image transport features
- Stereo

In case you wished to see those features in RViz for ROS 2, feel free to add a pull request.
Expand Down
13 changes: 13 additions & 0 deletions rviz_default_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@ find_package(rviz_ogre_vendor REQUIRED)
find_package(Qt5 REQUIRED COMPONENTS Widgets Test)

find_package(geometry_msgs REQUIRED)
find_package(image_transport REQUIRED)
find_package(interactive_markers REQUIRED)
find_package(laser_geometry REQUIRED)
find_package(map_msgs REQUIRED)
Expand All @@ -79,7 +80,9 @@ set(rviz_default_plugins_headers_to_moc
include/rviz_default_plugins/displays/grid/grid_display.hpp
include/rviz_default_plugins/displays/grid_cells/grid_cells_display.hpp
include/rviz_default_plugins/displays/illuminance/illuminance_display.hpp
include/rviz_default_plugins/displays/image/get_transport_from_topic.hpp
include/rviz_default_plugins/displays/image/image_display.hpp
include/rviz_default_plugins/displays/image/image_transport_display.hpp
include/rviz_default_plugins/displays/laser_scan/laser_scan_display.hpp
include/rviz_default_plugins/displays/map/map_display.hpp
include/rviz_default_plugins/displays/marker/marker_common.hpp
Expand Down Expand Up @@ -132,6 +135,7 @@ set(rviz_default_plugins_source_files
src/rviz_default_plugins/displays/grid_cells/grid_cells_display.cpp
src/rviz_default_plugins/displays/fluid_pressure/fluid_pressure_display.cpp
src/rviz_default_plugins/displays/illuminance/illuminance_display.cpp
src/rviz_default_plugins/displays/image/get_transport_from_topic.cpp
src/rviz_default_plugins/displays/image/image_display.cpp
src/rviz_default_plugins/displays/image/ros_image_texture.cpp
src/rviz_default_plugins/displays/interactive_markers/integer_action.cpp
Expand Down Expand Up @@ -252,6 +256,7 @@ ament_target_dependencies(rviz_default_plugins
tf2_ros
urdf
visualization_msgs
image_transport
)

ament_export_include_directories(include)
Expand Down Expand Up @@ -362,6 +367,13 @@ if(BUILD_TESTING)
ament_target_dependencies(frame_info_test ${TEST_TARGET_DEPENDENCIES})
endif()

ament_add_gmock(get_transport_from_topic_test
test/rviz_default_plugins/displays/image/get_transport_from_topic_test.cpp)
if(TARGET get_transport_from_topic_test)
target_include_directories(get_transport_from_topic_test PUBLIC ${TEST_INCLUDE_DIRS} ${rviz_common_INCLUDE_DIRS})
target_link_libraries(get_transport_from_topic_test ${TEST_LINK_LIBRARIES} ${rviz_common})
endif()

ament_add_gmock(grid_cells_display_test
test/rviz_default_plugins/displays/grid_cells/grid_cells_display_test.cpp
${SKIP_DISPLAY_TESTS})
Expand Down Expand Up @@ -1014,3 +1026,4 @@ if(BUILD_TESTING)
endif()

ament_package()

Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
/*
* Copyright (c) 2009, Willow Garage, Inc.
* Copyright (c) 2018, Bosch Software Innovations GmbH.
* Copyright (c) 2020, TNG Technology Consulting GmbH.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
Expand Down Expand Up @@ -47,10 +48,11 @@

# include "sensor_msgs/msg/camera_info.hpp"

# include "rviz_rendering/render_window.hpp"
# include "rviz_common/message_filter_display.hpp"
# include "rviz_default_plugins/displays/image/image_transport_display.hpp"
# include "rviz_default_plugins/displays/image/ros_image_texture_iface.hpp"
# include "rviz_default_plugins/visibility_control.hpp"
# include "rviz_rendering/render_window.hpp"

#endif

namespace Ogre
Expand All @@ -65,17 +67,16 @@ namespace rviz_common
{

class QueueSizeProperty;

class RenderPanel;

namespace properties
{

class EnumProperty;
class FloatProperty;
class IntProperty;
class RosTopicProperty;
class DisplayGroupVisibilityProperty;

} // namespace properties
} // namespace rviz_common

Expand All @@ -96,7 +97,7 @@ struct ImageDimensions
*
*/
class RVIZ_DEFAULT_PLUGINS_PUBLIC CameraDisplay
: public rviz_common::MessageFilterDisplay<sensor_msgs::msg::Image>,
: public rviz_default_plugins::displays::ImageTransportDisplay<sensor_msgs::msg::Image>,
public Ogre::RenderTargetListener
{
Q_OBJECT
Expand Down Expand Up @@ -197,7 +198,9 @@ private Q_SLOTS:
bool force_render_;

uint32_t vis_bit_;

void setupSceneNodes();

void setupRenderPanel();
};

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
/*
* Copyright (c) 2020, TNG Technology Consulting 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 OWNER 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__DISPLAYS__IMAGE__GET_TRANSPORT_FROM_TOPIC_HPP_
#define RVIZ_DEFAULT_PLUGINS__DISPLAYS__IMAGE__GET_TRANSPORT_FROM_TOPIC_HPP_

#include <string>

#include "rviz_default_plugins/visibility_control.hpp"

namespace rviz_default_plugins
{
namespace displays
{

RVIZ_DEFAULT_PLUGINS_PUBLIC
std::string getTransportFromTopic(const std::string & topic);

RVIZ_DEFAULT_PLUGINS_PUBLIC
std::string getBaseTopicFromTopic(const std::string & topic);


} // end namespace displays
} // end namespace rviz_default_plugins

#endif // RVIZ_DEFAULT_PLUGINS__DISPLAYS__IMAGE__GET_TRANSPORT_FROM_TOPIC_HPP_
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
/*
* Copyright (c) 2012, Willow Garage, Inc.
* Copyright (c) 2017, Bosch Software Innovations GmbH.
* Copyright (c) 2020, TNG Technology Consulting GmbH.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
Expand Down Expand Up @@ -49,6 +50,7 @@

# include "rviz_default_plugins/displays/image/ros_image_texture_iface.hpp"
# include "rviz_default_plugins/visibility_control.hpp"
#include "rviz_default_plugins/displays/image/image_transport_display.hpp"
#endif


Expand All @@ -68,7 +70,7 @@ namespace displays
*
*/
class RVIZ_DEFAULT_PLUGINS_PUBLIC ImageDisplay : public
rviz_common::MessageFilterDisplay<sensor_msgs::msg::Image>
rviz_default_plugins::displays::ImageTransportDisplay<sensor_msgs::msg::Image>
{
Q_OBJECT

Expand Down
Loading

0 comments on commit 731f24d

Please sign in to comment.